麥克納姆輪全向移動原理
什麼是麥克納姆輪
在競賽機器人和特殊工種機器人中,全向移動經常是一個必需的功能。「全向移動」意味著可以在平面內做出任意方向平移同時自轉的動作。為了實現全向移動,一般機器人會使用「全向輪」(Omni Wheel)或「麥克納姆輪」(Mecanum Wheel)這兩種特殊輪子。
全向輪:
全向輪與麥克納姆輪的共同點在於他們都由兩大部分組成:輪轂和輥子(roller)。輪轂是整個輪子的主體支架,輥子則是安裝在輪轂上的鼓狀物。全向輪的輪轂軸與輥子轉軸相互垂直,而麥克納姆輪的輪轂軸與輥子轉軸呈 45° 角。理論上,這個夾角可以是任意值,根據不同的夾角可以製作出不同的輪子,但最常用的還是這兩種。
全向輪與麥克納姆輪(以下簡稱「麥輪」)在結構、力學特性、運動學特性上都有差異,其本質原因是輪轂軸與輥子轉軸的角度不同。經過分析,二者的運動學和力學特性區別可以通過以下表格來體現。
計算過程如下,供參考,學霸可點開大圖驗算:
近年來,麥輪的應用逐漸增多,特別是在 Robocon、FRC 等機器人賽事上。這是因為麥克納姆輪可以像傳統輪子一樣,安裝在相互平行的軸上。而若想使用全向輪完成類似的功能,幾個輪轂軸之間的角度就必須是 60°,90° 或 120° 等角度,這樣的角度生產和製造起來比較麻煩。所以許多工業全向移動平臺都是使用麥克納姆輪而不是全向輪,比如這個國產的叉車: 全向移動平臺 麥克納姆輪叉車 美科斯叉車
另外一個原因,可能是麥輪的造型比全向輪要酷炫得多,看起來有一種不明覺厲的感覺……
的確,第一次看到麥輪運轉起來,不少人都會驚歎。以下視訊直觀地說明了麥輪底盤在平移和旋轉時的輪子旋轉方向。
麥輪的安裝方法
麥輪一般是四個一組使用,兩個左旋輪,兩個右旋輪。左旋輪和右旋輪呈手性對稱,區別如下圖。
安裝方式有多種,主要分為:X-正方形(X-square)、X-長方形(X-rectangle)、O-正方形(O-square)、O-長方形(O-rectangle)。其中 X 和 O 表示的是與四個輪子地面接觸的輥子所形成的圖形;正方形與長方形指的是四個輪子與地面接觸點所圍成的形狀。
- X-正方形:輪子轉動產生的力矩會經過同一個點,所以 yaw 軸無法主動旋轉,也無法主動保持 yaw 軸的角度。一般幾乎不會使用這種安裝方式。
- X-長方形:輪子轉動可以產生 yaw 軸轉動力矩,但轉動力矩的力臂一般會比較短。這種安裝方式也不多見。
- O-正方形:四個輪子位於正方形的四個頂點,平移和旋轉都沒有任何問題。受限於機器人底盤的形狀、尺寸等因素,這種安裝方式雖然理想,但可遇而不可求。
- O-長方形:輪子轉動可以產生 yaw 軸轉動力矩,而且轉動力矩的力臂也比較長。是最常見的安裝方式。
麥輪底盤的正逆運動學模型
以O-長方形的安裝方式為例,四個輪子的著地點形成一個矩形。正運動學模型(forward kinematic model)將得到一系列公式,讓我們可以通過四個輪子的速度,計算出底盤的運動狀態;而逆運動學模型(inverse kinematic model)得到的公式則是可以根據底盤的運動狀態解算出四個輪子的速度。需要注意的是,底盤的運動可以用三個獨立變數來描述:X軸平動、Y軸平動、yaw 軸自轉;而四個麥輪的速度也是由四個獨立的電機提供的。所以四個麥輪的合理速度是存在某種約束關係的,逆運動學可以得到唯一解,而正運動學中不符合這個約束關係的方程將無解。
先試圖構建逆運動學模型,由於麥輪底盤的數學模型比較複雜,我們在此分四步進行:
①將底盤的運動分解為三個獨立變數來描述;
②根據第一步的結果,計算出每個輪子軸心位置的速度;
③根據第二步的結果,計算出每個輪子與地面接觸的輥子的速度;
④根據第三部的結果,計算出輪子的真實轉速。
一、底盤運動的分解
我們知道,剛體在平面內的運動可以分解為三個獨立分量:X軸平動、Y軸平動、yaw 軸自轉。如下圖所示,底盤的運動也可以分解為三個量:
表示 X 軸運動的速度,即左右方向,定義向右為正;
表示 Y 軸運動的速度,即前後方向,定義向前為正;
表示 yaw 軸自轉的角速度,定義逆時針為正。
以上三個量一般都視為四個輪子的幾何中心(矩形的對角線交點)的速度。
二、計算出輪子軸心位置的速度
定義:
為從幾何中心指向輪子軸心的向量;
為輪子軸心的運動速度向量;
為輪子軸心沿垂直於 的方向(即切線方向)的速度分量;
那麼可以計算出:
分別計算 X、Y 軸的分量為:
同理可以算出其他三個輪子軸心的速度。
三、計算輥子的速度
根據輪子軸心的速度,可以分解出沿輥子方向的速度 和垂直於輥子方向的速度 。其中 是可以無視的(思考題:為什麼垂直方向的速度可以無視?),而
其中 是沿輥子方向的單位向量。
四、計算輪子的速度
從輥子速度到輪子轉速的計算比較簡單:
根據上圖所示的 和 的定義,有
結合以上四個步驟,可以根據底盤運動狀態解算出四個輪子的轉速:
以上方程組就是O-長方形麥輪底盤的逆運動學模型,而正運動學模型可以直接根據逆運動學模型中的三個方程解出來,此處不再贅述。
另一種計算方式
「傳統」的推導過程雖然嚴謹,但還是比較繁瑣的。這裡介紹一種簡單的逆運動學計算方式。
我們知道,全向移動底盤是一個純線性系統,而剛體運動又可以線性分解為三個分量。那麼只需要計算出麥輪底盤在「沿X軸平移」、「沿Y軸平移」、「繞幾何中心自轉」時,四個輪子的速度,就可以通過簡單的加法,計算出這三種簡單運動所合成的「平動+旋轉」運動時所需要的四個輪子的轉速。而這三種簡單運動時,四個輪子的速度可以通過簡單的測試,或是推動底盤觀察現象得出。
當底盤沿著 X 軸平移時:
當底盤沿著 Y 軸平移時:
當底盤繞幾何中心自轉時:
將以上三個方程組相加,得到的恰好是根據「傳統」方法計算出的結果。這種計算方式不僅適用於O-長方形的麥輪底盤,也適用於任何一種全向移動的機器人底盤。
Makeblock 麥輪底盤的組裝
理論分析完成,可以開始嘗試將其付諸實踐了。
第一步,組裝矩形框架。
第二步,組裝電機模組。
由於麥輪底盤的四個輪子速度有約束關係,必須精確地控制每個輪子的速度,否則將會導致輥子與地面發生滑動摩擦,不僅會讓底盤運動異常,還會讓麥輪的壽命減少。所以必須使用編碼電機。
第三步,將電機模組安裝到框架上。
第四步,將麥輪安裝到框架上。
第五步,安裝電路板並接線。
編碼電機必須配上相應的驅動板才能正常工作。這裡使用的 Makeblock 編碼電機驅動板,每一塊板可以驅動兩個電機。接線順序在下文中會提及,也可以隨意接上,在程式碼中定義好對應的順序即可。
第六步,裝上電池。
至此,一個能獨立執行的麥輪底盤就完成了。
控制程式
根據麥輪的底盤的運動學模型,要完全控制它的運動,需要有三個控制量:X軸速度、Y軸速度、自轉角速度。要產生這三個控制量,有很多種方法,本文將使用一個 USB 遊戲手柄,左邊的搖桿產生平移速度,右邊的搖桿產生角速度。
然後插上一個無線 USB 遊戲手柄。
然後再新增其他細節,就大功告成啦!
其他細節:
#include <Wire.h>
#include <SoftwareSerial.h>
#include "MeOrion.h"
MeUSBHost joypad(PORT_3);
// 手柄程式碼(紅燈亮模式)
// 預設:128-127-128-127-15-0-0-128
// 左一:128-127-128-127-15-1-0-128
// 右一:128-127-128-127-15-2-0-128
// 左二:128-127-128-127-15-4-0-128
// 右二:128-127-128-127-15-8-0-128
// 三角:128-127-128-127-31-0-0-128 (0001 1111)
// 方形:128-127-128-127-143-0-0-128 (1000 1111)
// 叉號:128-127-128-127-79-0-0-128 (0100 1111)
// 圓圈:128-127-128-127-47-0-0-128 (0010 1111)
// 向上:128-127-128-127-0-0-0-128 (0000 0000)
// 向下:128-127-128-127-4-0-0-128 (0000 0100)
// 向左:128-127-128-127-6-0-0-128 (0000 0110)
// 向右:128-127-128-127-2-0-0-128 (0000 0010)
// 左上:128-127-128-127-7-0-0-128 (0000 0111)
// 左下:128-127-128-127-5-0-0-128 (0000 0101)
// 右上:128-127-128-127-1-0-0-128 (0000 0001)
// 右下:128-127-128-127-3-0-0-128 (0000 0011)
// 選擇:128-127-128-127-15-16-0-128
// 開始:128-127-128-127-15-32-0-128
// 搖桿:右X-右Y-左X-左Y-15-0-0-128
MeEncoderMotor motor1(0x02, SLOT2);
MeEncoderMotor motor2(0x02, SLOT1);
MeEncoderMotor motor3(0x0A, SLOT2);
MeEncoderMotor motor4(0x0A, SLOT1);
// 底盤:a = 130mm, b = 120mm
float linearSpeed = 100;
float angularSpeed = 100;
float maxLinearSpeed = 200;
float maxAngularSpeed = 200;
float minLinearSpeed = 30;
float minAngularSpeed = 30;
void setup()
{
// 要上電才能工作,不能只是插上 USB 線來除錯。
motor1.begin();
motor2.begin();
motor3.begin();
motor4.begin();
Serial.begin(57600);
joypad.init(USB1_0);
}
void loop()
{
Serial.println("loop:");
//setEachMotorSpeed(100, 50, 50, 100);
if(!joypad.device_online)
{
// 若一直輸出離線狀態,重新拔插 USB Host 的 RJ25 線試一下。
Serial.println("Device offline.");
joypad.probeDevice();
delay(1000);
}
else
{
int len = joypad.host_recv();
parseJoystick(joypad.RECV_BUFFER);
delay(5);
}
//delay(500);
}
void setEachMotorSpeed(float speed1, float speed2, float speed3, float speed4)
{
motor1.runSpeed(speed1);
motor2.runSpeed(-speed2);
motor3.runSpeed(-speed3);
motor4.runSpeed(-speed4);
}
void parseJoystick(unsigned char *buf) //Analytic function, print 8 bytes from USB Host
{
// 輸出手柄的資料,除錯用
// int i = 0;
// for(i = 0; i < 7; i++)
// {
// Serial.print(buf[i]); //It won't work if you connect to the Makeblock Orion.
// Serial.print('-');
// }
// Serial.println(buf[7]);
// delay(10);
// 速度增減
switch (buf[5])
{
case 1:
linearSpeed += 5;
if (linearSpeed > maxLinearSpeed)
{
linearSpeed = maxLinearSpeed;
}
break;
case 2:
angularSpeed += 5;
if (angularSpeed > maxAngularSpeed)
{
angularSpeed = maxAngularSpeed;
}
break;
case 4:
linearSpeed -= 5;
if (linearSpeed < minLinearSpeed)
{
linearSpeed = minLinearSpeed;
}
break;
case 8:
angularSpeed -= 5;
if (angularSpeed < minAngularSpeed)
{
angularSpeed = minAngularSpeed;
}
break;
default:
break;
}
if ((128 != buf[0]) || (127 != buf[1]) || (128 != buf[2]) || (127 != buf[3]))
{
// 處理搖桿
float x = ((float)(buf[2]) - 127) / 128;
float y = (127 - (float)(buf[3])) / 128;
float a = (127 - (float)(buf[0])) / 128;
mecanumRun(x * linearSpeed, y * linearSpeed, a * angularSpeed);
}
else
{
switch (buf[4])
{
case 0:
mecanumRun(0, linearSpeed, 0);
break;
case 4:
mecanumRun(0, -linearSpeed, 0);
break;
case 6:
mecanumRun(-linearSpeed, 0, 0);
break;
case 2:
mecanumRun(linearSpeed, 0, 0);
break;
case 7:
mecanumRun(-linearSpeed/2, linearSpeed/2, 0);
break;
case 5:
mecanumRun(-linearSpeed/2, -linearSpeed/2, 0);
break;
case 1:
mecanumRun(linearSpeed/2, linearSpeed/2, 0);
break;
case 3:
mecanumRun(linearSpeed/2, -linearSpeed/2, 0);
break;
default:
mecanumRun(0, 0, 0);
break;
}
}
}
void mecanumRun(float xSpeed, float ySpeed, float aSpeed)
{
float speed1 = ySpeed - xSpeed + aSpeed;
float speed2 = ySpeed + xSpeed - aSpeed;
float speed3 = ySpeed - xSpeed - aSpeed;
float speed4 = ySpeed + xSpeed + aSpeed;
float max = speed1;
if (max < speed2) max = speed2;
if (max < speed3) max = speed3;
if (max < speed4) max = speed4;
if (max > maxLinearSpeed)
{
speed1 = speed1 / max * maxLinearSpeed;
speed2 = speed2 / max * maxLinearSpeed;
speed3 = speed3 / max * maxLinearSpeed;
speed4 = speed4 / max * maxLinearSpeed;
}
setEachMotorSpeed(speed1, speed2, speed3, speed4);
}
//=======================================================================================//
//=======================================================================================//
文章中所有圖片資料均來自:熾點機器人
我們來畫個受力示意圖吧
先來看看前後移動
圖中紅色實線箭頭是車輪向前轉產生的摩擦力
藍色箭頭是車輪向後轉產生的摩擦力
虛線是分力
於是左邊的小車就會向前跑,右邊的小車會向後跑
接下來我們畫原地旋轉
於是左邊的小車就順時針旋轉
右邊的小車逆時針旋轉
讓我們再來看看平移
左邊的小車向左平移
右邊的小車向右平移
接下來看看斜著跑
只要同向轉動對角線上兩個輪子,
就能斜著跑啦