全向輪運動學與V-rep中全向移動機器人仿真


   Wheeled mobile robots may be classified in two major categories, omnidirectional and nonholonomic. Omnidirectional mobile robots have no equality constraints on the chassis velocity $\dot{q}=(\dot{\phi},\dot{x},\dot{y})$ Omnidirectional wheeled mobile robots typically employ either omniwheel or mecanum wheels. Omniwheels and mecanum wheels are not steered, only driven forward or backward. Because of their small diameter rollers, omniwheels and mecanum wheels work best on hard, flat ground全方位運動平台通常裝有全向輪:omniwheels(全向輪)或 mecanum wheels(麥克納姆輪)。借助於橫向移動和原地回旋的特性,全方位運動平台可方便的穿梭於狹窄擁擠空間中,靈活完成各種任務,相比傳統移動平台有明顯優勢。  

  全方位運動系統中,Mecanum輪應用最廣泛。Mecanum輪(又稱瑞典輪)是瑞典Mecanum AB公司工程師Bengt Ilron提出的特殊輪系,其特點為沿輪毅圓周排布着與輪子成一定角度且可繞自身軸線進行旋轉的輥子。由三個或以上Mecanum 輪按照一定方式排列組成的移動平台具有平面內三個自由度,可同時獨立的前后、左右和原地旋轉運動,可在不改變自身姿態的情況下向任意方向移動。

  其運動學本質是:輪轂外圍安裝一周與輪轂軸線呈一定角度的無動力輥子作為輪胎,該輥子不僅可繞輪轂軸公轉,也能在地面摩擦力作用下繞各自的支撐芯軸自轉,兩種運動的合成使得接觸地面的輥子中心合速度與輪轂軸有一定的夾角,通過調節輪轂速度可改變輥子中心合速度的大小和方向。由同樣結構的若干Mecanum 輪按一定規則組成的輪組系統,通過改變各輪轂速度的線性組合,進而控制運動系統中心合速度大小和方向,使機器人實現平面3自由度全方位運動。由於其外觀上與斜齒輪相似,麥克納姆輪也有齒輪嚙合時相類似的問題:為了保證運動的平穩性,當前一個輥子與地面即將分離時,后一個輥子必須與地面接觸。 

 全向輪運動學 

  如下圖所示,坐標系{S}為空間中靜止的參考系,坐標系{b}固定在車身上隨機器人運動。那么機器人在靜止參考系中的位置和姿態可以用向量$q$描述,$q=(\phi,x,y)$。在自身參考系{b}中的線速度及角速度為$\upsilon _b=(\omega_{bz},v_{bx},v_{by})$

  那么兩個參考系之間速度的轉換公式如下:

   全方位移動機器人必須安裝至少3個全向輪,才能實現以任意三維速度$\dot{q}=(\dot{\phi},\dot{x},\dot{y})$進行運動。下圖為兩種典型的全向移動機器人,一種裝有3個全向輪,另一種裝有4個麥克納姆輪。

  為了控制全向移動機器人,我們需要知道給每個輪子多大的角速度才能使機器人達到目標速度$\dot{q}$。為了解答這個問題,我們需要理解單個輪子的運動學,為此建立如下圖所示的輪子坐標系:

  坐標系$\hat{X_w}-\hat{Y_w}$建立在輪子中心,根據速度合成定理車輪中心的速度$v=(v_x,v_y)$滿足下面的公式:

  其中$\gamma$為小輥子滾動方向與驅動輪平面的夾角(通常全向輪為0°,麥克納姆輪為±45°),$v_{drive}$是驅動速度,$v_{slide}$是自由滑動的速度。解方程(13.3)可以得到

  假設輪子半徑為$r$,輪子轉動的角速度為$u$,那么根據上式可得:

   為了推導出從小車速度$\dot{q}=(\dot{\phi},\dot{x},\dot{y})$到輪子$i$的角速度$u_i$的轉換關系,參考最上面的坐標系布置圖。輪子坐標系在小車坐標系{b}中的位置和姿態可以用向量$(\beta_i,x_i,y_i)$來表達,其中輪子半徑為$r_i$,輥子滑動角度為$\gamma_i$。那么從$\dot{q}$到$u_i$的轉換關系如下:

  從右到左進行解讀:第一個變換矩陣將靜止坐標系下的$\dot{q}$變換為小車局部坐標系{b}中的$\upsilon _b$;第二個變換矩陣將小車的局部速度轉換為坐標系{b}中的輪子線速度;第三個變換矩陣將坐標系{b}中的輪子線速度轉換為輪子坐標系$\hat{X_w}-\hat{Y_w}$中的線速度;最后一個變換矩陣將依據公式(13.4)計算輪子角速度。

  將這幾個矩陣合並,可以得到對單個輪子的變換矩陣$h_i(\phi)$如下:

  對於一個全向移動機器人來說,輪子數量$m \geqslant 3 $,矩陣$H(\phi) \in R^{m \times 3}$將靜止參考系中的機器人速度$\dot{q} \in R^3$轉換為輪子驅動角速度$u \in R^m$,將m行$h_i(\phi)$向量堆疊到一起組成矩陣$H(\phi)$,有如下公式:

  根據上式我們也可以直接計算出小車局部坐標系下的速度和驅動輪角速度之間的關系,這時轉換矩陣將不依賴小車在靜止參考坐標系中的朝向角$\phi$:

  小車上輪子的位置和朝向$(\beta_i,x_i,y_i)$,以及輥子夾角$\gamma_i$的選擇必須使得矩陣$H(0)$的秩為3。如果rank(H) < 3,則系統中存在奇異位形,反映在運動學上就是失去部分自由度,即小車不能實現全方位運動。

  由於全向輪結構和運動學的特殊性,系統中並不是任一種輪組排列結構形式都可實現全方位運動,多輪構成的系統運動能力和運動控制性能及其驅動性能均與輪組的結構形式密切相關。下面就是兩種典型的布局,麥克納姆輪在小車中的朝向都一致$\beta_i=0$:

   根據上面的公式,3個全向輪布置的移動機器人運動學模型為:

  4個麥克納姆輪布置的移動機器人運動學模型為:

  對麥克納姆輪型移動機器人來說,為向前移動,所有輪子要以相同的速度向前轉動;為了側向移動,1、3輪向前轉,2、4輪向后轉,轉速要相同...

 

 V-rep中全向移動機器人仿真 

   在V-rep的模型瀏覽器中可以找到麥克納姆輪組件:

  為了搭建麥克納姆輪的模型,一種很自然的想法是在輪轂上創建多個關節,並在關節上添加與地面接觸的輥子。這樣雖然符合實際情況,但是會影響仿真速度、仿真穩定性及精度。There is the obvious natural approach to simulate them by modelling each auxiliary wheel on top of the actuated wheel. This will slow down simulation, make it less stable, and also less precise. But this is possible. The better approach for this is to use a trick: instead of using a complicated wheel, simply use a sphere, attached to a passive axis, itself attached to a non-respondable sphere, itself attached to an actuated axis. Then, in each simulation step, reset the orientation of the passive wheel.

  我們看看V-rep中麥克納姆輪是怎樣搭建起來的(參考V-rep Forum里的這兩個問題:Object Orientation around an AxisRobotino problem)。在圖層中將輪子的虛擬外形隱藏,顯示兩個轉動關節以及實際與地面接觸的“輪子”。從下圖可以看出這個實際的輪子是由一個球體模擬的,這個球不僅可以繞着驅動軸轉動,還可以繞着另一個虛擬軸free "sliding" joint轉動,轉動方向即為free "sliding" direction。

  這兩個軸之間的角度即為上面討論的$\gamma$角。注意要從底面方向上看(可以切換到bottom view),因為輪子與地面接觸的輥子在最下端,不要看反了:

  V-rep中提供的mecanum輪由兩個轉動關節和兩個球體組成,用來模擬實際復雜的輪子。The wheel is composed by 2 spheres and 2 revolute joints in following configuration: robotBody → activeJoint → nonRespondableSphere → passiveJoint → respondableSphere

  V-rep中進行動力學仿真時對dynamic chain以及物體質量屬性等參數有一系列要求,為了能正確進行仿真必須遵守這些准則,具體要參考官方文檔:Designing dynamic simulations.

  Dynamically enabled joints are joints that are in force or torque mode, and that have a shape as parent object and exactly one child object which must be a non-static shapeFollowing are a few example situations where a joint won't be dynamically enabled:

  • the joint is not in force or torque mode, and the joint is not operating in a hybrid fashion.
  • the joint's parent is not a shape.
  • the joint has more than one child object.
  • the joint directly connects to another joint.
  • the joint (or one of the two shapes it connects) is located in a model (hierarchy tree) that is not dynamically simulated 

  注意V-rep中的球型關節本質上是直接由三個正交的轉動副串接而成的。考慮到上面第4點,這三個關節直接相互串接,因此球型關節不能設置為Torque/force模式,它總是工作在passive模式。Spherical joints are always passive joints, and cannot act as motors.

[Two equivalent mechanisms (in this configuration): spherical joint (left) and 3 revolute joints (right)]

   Never have a static shape between two dynamic items. The static shape will interrupt the logical behaviour of the dynamic chain:

[Wrong and correct construction]

   基於這幾點考慮要在activeJoint → passiveJoint的運動鏈中插入nonRespondableSphere,這個中間連接件是non-static & non-respondable的。如果是static類型,那么仿真時在驅動關節旁邊會出現警告圖標。Objects that are supposed to by dynamically simulated but which, for a reason or another cannot be dynamically simulated, will display following the warning icon:

  在進行動力學仿真時點擊工具欄上的Visualize and verify dynamic content按鈕,就可以以不同顏色顯示各個圖層(包括隱藏圖層)中的動態物體。

[Dynamic content visualization button]

  下面是幾種顏色類型。pure shape物體的邊線為黑色,其中non-static&respondable類型的物體面為紅色,static&respondable類型的物體面為白色。Torque/force模式下的關節如果motor enabled顏色為紅色,如果沒有enabled,顏色為藍色。注意點擊顯示動態內容的按鈕后,Passive等模式下的關節將不會在仿真時顯示出來。

  從下圖我們可以很清楚地看出YouBot由不同動力學特性的部件構成。其中,以藍色顯示的自由關節在底盤運動過程中始終保持水平,沒有隨着父節點的驅動關節一起旋轉。這是因為在腳本執行過程中會周期性的調用函數設置該關節相對於驅動關節的位置和姿態。如果我們將這兩行代碼注釋掉,或者直接disable這個腳本,那么在仿真過程中這個自由關節會隨着驅動關節一起旋轉,底盤運動時會產生奇怪的行為。

   下面是單個麥克納姆輪的代碼。There must be a non-threaded child script attached to one of those objects, preferably the first joint. It is in charge of resetting the respondable sphere and reorienting the passive joints in each simulation loop.

-- Following script resets the second joint on the omni-wheel (important to achieve the desired omni-wheel effect)

if (sim_call_type==sim_childscriptcall_initialization) then 
    rolling = simGetObjectHandle('rollingJoint_fl')
    slipping = simGetObjectHandle('slippingJoint_fl')
    wheel = simGetObjectHandle('wheel_respondable_fl')
end 


if (sim_call_type==sim_childscriptcall_actuation) then 
    simResetDynamicObject(wheel)
    simSetObjectPosition(slipping,rolling,{0,0,0})
    simSetObjectOrientation(slipping,rolling,{-math.pi/4,0,0})
    simSetObjectPosition(wheel,rolling,{0,0,0})
    simSetObjectOrientation(wheel,rolling,{0,0,0})
end 
View Code

 

  接下來看一個用麥克納姆輪搭建的移動機器人的例子。在模型瀏覽器中的移動機器人目錄下找到KUKA YouBot模型,並將其拖入新建的場景中:

  刪掉機械臂相關的結構和代碼,選中youBot進行仿真會彈出一個GUI界面,通過上面的滑塊可以控制底盤的前進后退、橫向移動以及轉動速度:

   注意YouBot的原始Lua代碼中控制麥克納姆輪底盤運動時並沒有按照實際的公式去計算4個輪子的角速度(忽略了輪子尺寸,以及輪子間距等幾何參數),在V-rep中測得這些參數后再修改公式的代碼如下:

if (sim_call_type==sim_childscriptcall_initialization) then 

    -- Make sure we have version 2.4.12 or above (the omni-wheels are not supported otherwise)
    v=simGetInt32Parameter(sim_intparam_program_version)
    if (v<20412) then
        simDisplayDialog('Warning','The YouBot model is only fully supported from V-REP version 2.4.12 and above.&&nThis simulation will not run as expected!',sim_dlgstyle_ok,false,'',nil,{0.8,0,0,0,0,0})
    end

    --Prepare initial values and retrieve handles:
    wheelJoints={-1,-1,-1,-1} -- front left, rear left, rear right, front right
    wheelJoints[1]=simGetObjectHandle('rollingJoint_fl')
    wheelJoints[2]=simGetObjectHandle('rollingJoint_rl')
    wheelJoints[3]=simGetObjectHandle('rollingJoint_rr')
    wheelJoints[4]=simGetObjectHandle('rollingJoint_fr')

    youBot=simGetObjectHandle('youBot')
    ui=simGetUIHandle('youBot_UI')
    simSetUIButtonLabel(ui,0,simGetObjectName(youBot)..' user interface') -- Set the UI title (with the name of the current robot)

    forwBackVelRange={-240*math.pi/180,240*math.pi/180}  -- min and max wheel rotation vel. for backward/forward movement
    leftRightVelRange={-240*math.pi/180,240*math.pi/180} -- min and max wheel rotation vel. for left/right movement
    rotVelRange={-240*math.pi/180,240*math.pi/180}       -- min and max wheel rotation vel. for left/right rotation movement

    forwBackVel=0
    leftRightVel=0
    rotVel=0

    r= 0.05  -- wheel radius(m)
end 


if (sim_call_type==sim_childscriptcall_actuation) then 

    buttonID=simGetUIEventButton(ui)
    if (buttonID==200) then -- Forward/backward slider was changed
        forwBackVel=forwBackVelRange[1]+simGetUISlider(ui,buttonID)*0.001*(forwBackVelRange[2]-forwBackVelRange[1])
    end
    if (buttonID==201) then -- left/right slider was changed
        leftRightVel=leftRightVelRange[1]+simGetUISlider(ui,buttonID)*0.001*(leftRightVelRange[2]-leftRightVelRange[1])
    end
    if (buttonID==202) then -- left/right rotation slider was changed
        rotVel=rotVelRange[1]+simGetUISlider(ui,buttonID)*0.001*(rotVelRange[2]-rotVelRange[1])
    end
    if (buttonID==212) then -- stop button was clicked
        forwBackVel=0
        leftRightVel=0
        rotVel=0
        -- Reset the wheel movement sliders to the neutral position:
        simSetUISlider(ui,200,500)
        simSetUISlider(ui,201,500)
        simSetUISlider(ui,202,500)
    end

    -- Now apply the desired wheel velocities:
--[[
    simSetJointTargetVelocity(wheelJoints[1],-forwBackVel-leftRightVel-rotVel)
    simSetJointTargetVelocity(wheelJoints[2],-forwBackVel+leftRightVel-rotVel)
    simSetJointTargetVelocity(wheelJoints[3],-forwBackVel-leftRightVel+rotVel)
    simSetJointTargetVelocity(wheelJoints[4],-forwBackVel+leftRightVel+rotVel)
--]]
    simAddStatusbarMessage(string.format("Vx:%.2f  Vy:%.2f  Rot:%.2f", forwBackVel,leftRightVel,rotVel))

    simSetJointTargetVelocity(wheelJoints[1], (-forwBackVel-leftRightVel-0.38655*rotVel)/r )
    simSetJointTargetVelocity(wheelJoints[2], (-forwBackVel+leftRightVel-0.38655*rotVel)/r )
    simSetJointTargetVelocity(wheelJoints[3], (-forwBackVel-leftRightVel+0.38655*rotVel)/r )
    simSetJointTargetVelocity(wheelJoints[4], (-forwBackVel+leftRightVel+0.38655*rotVel)/r )
end 
View Code

  修改代碼后V-rep的狀態欄中會顯示滑塊設定的角速度。為了驗證公式的正確性,我們可以添加一個Graph來記錄底盤旋轉時的角速度,與設定值進行對比。經過比較,發現設定值與實際值相差很小。由於尺寸測量時的誤差以及物理仿真涉及到輪子與地面的接觸、摩擦等因素影響,還是會存在一定的誤差。

 

 

 

參考:

麥克納姆輪淺談

萬向輪、全向輪的優缺點是什么?

麥克納姆輪和全向輪他們的優缺點分別是什么?

Mecanum輪結構特征及運動誤差

Mecanum四輪全方位移動機構運動分析與仿真

Mecanum輪全方位移動機器人技術及其應用

Mecanum四輪系統全方位運動性能分析及布局結構優選

Mecanum wheel-Wikipedia

Introduction to Autonomous Mobile Robots.  Chapter 3 Mobile Robot Kinematics 

Modern Robotics Mechanics, Planning, and Control. Chapter 13 Omnidirectional Wheeled Mobile Robots


免責聲明!

本站轉載的文章為個人學習借鑒使用,本站對版權不負任何法律責任。如果侵犯了您的隱私權益,請聯系本站郵箱yoyou2525@163.com刪除。



 
粵ICP備18138465號   © 2018-2025 CODEPRJ.COM