注:本篇博文全部源碼下載地址為:Git Repo。
1. 下載到本地后解壓到當前文件夾然后運行:catkin_make 編譯。
2. 源碼是在 Ubuntu14.04 + Indigo 環境下編寫。
一、ROS系統的MoveIt模塊簡介
機器人操作系統ROS目前最受關注的兩個模塊是導航(Navigation)和機械臂控制(MoveIt!),其中,機械臂控制模塊(后面簡稱MoveIt)可以讓用戶快速建立機械臂模型並實現機械臂的控制(包括建模、運動學求解、運動規划、避障等),后續我將分幾篇博客分別介紹如何一步步使用MoveIt控制自己的機械臂,算是對以前的學習內容的記錄和分享。
關於MoveIt最全面的講解可以參考MoveIt官方網站,推薦大家多參考官方文檔和例程,這里的博文系列權當簡介和入門。
如果用幾個特點來概括MoveIt,主要有:
- 它是屬於ROS系統的一部分,用於控制多關節機械臂;
- 提供了一系列成熟的插件和工具,可以實現機械臂控制的快速配置;
- 封裝了大量API,方便用戶在MoveIt模塊上進行二次開發,進而做出更多有意思的應用。
這里借用官方經典圖例做簡單說明,如下如:

MoveIt結構圖
上圖可以看出:
1.MoveIt 的核心節點(node)為move_group,外圍的幾個部分分別為:ROS Param Server, Robot Controllers, Robot 3D Sensors, User Interface, Robot Sensors,其中:
- ROS Param Server:這部分載入的是用戶定義的模型文件(xacro或urdf)和一些配置文件。(重要)
- Robot Controllers: 這部分可以看做是和真正的機器人部分(硬件控制接口)打交道的部分,即運動規划的數據由此發給機器人驅動部分,后續會詳細講解。(重要)
- Robot 3D Sensors: 這部分作用是載入RGB-D相機或激光雷達等獲得的點雲數據用於機械手的抓取或避障等。
- User Interface: 這部分是用戶接口,MoveIt提供一系列的API供用戶完成自定義的功能,這里主要。(重要)
- Robot Sensors: 這部分是接收機械臂的傳感器數據,然后預估出機器人的狀態並發布。
二、MoveIt的安裝(Ubuntu14.04,Indigo)
首先確保你的Linux上正確安裝了ROS系統,安裝步驟參考:http://wiki.ros.org/indigo/Installation/Ubuntu。然后安裝moveit,如果不想挑戰源碼編譯,MoveIt可以用apt-get快速安裝,只需要輸入:
$ sudo apt-get install ros-indigo-moveit-full
三、本系列博文所用雙臂機器人簡介
本系列博文將以一個雙臂機器人為例,詳細講解基於MoveIt的使用方法,我為這個雙臂機器人取名為:rob,並在Solidworks中簡單繪制了該機器人的三維模型,結構示意圖如下:

Rob結構示意圖
Rob包含兩個手臂,左右對稱布局,每個手臂包含5個自由度,關節情況如下圖所示。

關節分布情況示意圖
這種關節分布是仿人形的雙臂機器人常用的手臂設置形式,但這種結構並不能完全覆蓋人手臂所有的自由度(人的手臂包含7個自由度),但用於說明 MoveIt 的使用已經足夠了。此外,各個關節的自由度范圍如下表所示。
| 關節 | 肩關節前后轉動(左) | 肩關節左右轉動(左) | 肩關節軸向轉動(左) | 肘關節前后轉動(左) | 腕關節軸向轉動(左) | 肩關節前后轉動(右) | 肩關節左右轉動(右) | 肩關節軸向轉動(右) | 肘關節前后轉動(右) | 腕關節軸向轉動(右) |
| 范圍(度°) | -25~175 | 0~60 | -80~80 | 0~90 | -80~80 | -25~175 | 0~60 | -80~80 | 0~90 | -80~80 |
四、機器人的ROS模型建立
這個系列主要介紹機器人ROS模型的建立方法,ROS系統帶來的好處之一就是:我們無需自己建立復雜的數學模型來描述自己的機器人幾何尺寸、運動學和動力學等,只需要用它提供的模型描述方法即可實現快速建模。
ROS系統的模型描述方法主要有兩種格式: URDF 和 XACRO。
1. 語法簡練。采用編程話的腳本語言格式,可以定義變量、常量、引入數學表達式等,極易上手。
2. 方便復用。它可以進行一系列的宏定義,並且可以包含其他.xacro文件。
下面,開始用xacro文件建立Rob的機器人模型,完整的源代碼可以在:git上獲取(git建模源碼),下文會截取一部分代碼做簡要說明。
1. 第一部分是文件的頭和一些宏定義,robot name我們可以自己隨便定義,然后分別給出了幾組顏色和常數的定義,最后給出了關節傳動部分的宏定義。
<?xml version="1.0"?> <robot name="rob_robot" xmlns:xacro="http://ros.org/wiki/xacro"> <!-- Include materials --> <material name="Black"> <color rgba="0.0 0.0 0.0 1.0"/> </material> <material name="White"> <color rgba="1.0 1.0 1.0 1.0"/> </material>
常量的定義方法如下,在引用這里定義的常量的時候,用${XX},例如在如果在下面的代碼中想引用M_PI,只需要用:${M_PI} 即可。
<!-- Constants -->
<property name="deg_to_rad" value="0.01745329251994329577"/> <property name="M_PI" value="3.14159"/>
關節的傳動參數宏定義方法如下,xacro:macro name 定義了本宏的名稱,這個名稱由用戶定義,后續引用該宏的時候就是根據名字來的,具體如何操作參考下文介紹或git上的源代碼,注意,這里宏定義內部的一些具體數值僅為說明而存在,具體的機器人關節應該是不一樣的。
<!-- transmission block macro definition --> <xacro:macro name="transmission_block" params="joint_name"> <transmission name="tran1"> <type>transmission_interface/SimpleTransmission</type> <joint name="${joint_name}"> <hardwareInterface>PositionJointInterface</hardwareInterface> </joint> <actuator name="motor1"> <hardwareInterface>PositionJointInterface</hardwareInterface> <mechanicalReduction>1</mechanicalReduction> </actuator> </transmission> </xacro:macro>
2,base_link的定義。
base_link是所有的其他關節的基礎,也就是基坐標系所在的link,這里他的幾何圖形我們直接引用他的dae文件,至於如何用Solidworks繪制模型然后制作成dae文件,后續找機會專門寫一篇博客進行介紹,下面的gazebo句段是為了我們的模型在gazebo環境中仿真用的,注意,base_link 只是定義了“機械臂的基座” 它本身是不包含 joint 的。
<!-- BASE LINK AND --> <link name="base_link"> <visual> <!-- <origin xyz="-0.22 -0.15 0.00" rpy="0 0 0" /> --> <origin xyz="0.1 -0.11 0.13" rpy="0 0 1.570796" /> <geometry> <mesh filename="package://rob_description/meshes/body_link_humanoid.dae"/> </geometry> <material name="green" /> </visual> <collision> <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> <!-- --> <geometry> <mesh filename="package://rob_description/meshes/body_link_humanoid.dae"/> </geometry> </collision> </link> <gazebo reference="base_link"> <material>Gazebo/green</material> </gazebo>
3. 其他關節的定義。
至於其他關節的定義,一個 Link 就對應一個 Joint ,示例如下,這里定義的是 l_shoulder_joint 和 l_shoulder_link。在Joint 的定義中,有一個limit 的程序段,這里規定的是關節的力限制、速度限制和關節運動范圍限制,速度限制的單位是m/s(移動關節)或rad/s(轉動關節),詳細的說面看:這里。
代碼中間: <xacro: ...../> 就是引用上文中我們定義的關於傳動參數的宏定義。
如果在xacro 代碼中想用數學表達式,使用的格式是:${ 數學表達式 } ,如下面代碼中所示。
其余關節的定義詳見源代碼。
<!-- left shoulder link and joint --> <joint name="l_shoulder_joint" type="revolute"> <parent link="base_link"/> <child link="l_shoulder_link"/> <origin xyz="0 0.11 0.74" rpy="0 0 3.14159" /> <axis xyz="0 1 0" /> <limit effort="300" velocity="${0.2*0.6981}" lower="-0.43633" upper="3.0543"/><!-- (-25 +175)=(-25 175) --> <!-- velocity: m/s for prismatic, rad/s for revolute --> <dynamics damping="50" friction="1"/> </joint> <xacro:transmission_block joint_name="l_shoulder_joint"/> <link name="l_shoulder_link"> <visual> <origin xyz="-0.04 0.02 0.04" rpy="1.5708 1.5708 0" /> <geometry> <mesh filename="package://rob_description/meshes/l_shoulder_link.dae"/> </geometry> <material name="green" /> </visual> <collision> <origin xyz="-0.04 0.02 0.04" rpy="1.5708 1.5708 0" /> <geometry> <mesh filename="package://rob_description/meshes/l_shoulder_link.dae"/> </geometry> </collision>> <xacro:inertial_matrix mass="1"/> </link> <gazebo reference="l_shoulder_link"> <material>Gazebo/green</material> </gazebo>
4. 將 XACRO文件轉換成 URDF 文件 並檢查。
轉換的方法很簡單,ROS封裝了實現方法,我們只需進入xacro 所在的文件夾,然后鍵入如下命令即可:
rosrun xacro xacro.py rob.xacro > rob.urdf
為了檢驗我們的模型的准確性,我們進行簡單的檢查,在同一個目錄下輸入:
check_urdf rob.urdf
即可得到如下圖顯示,可以看到雙臂的關節鏈接情況。

為了更直觀的觀看關節鏈接情況,我們在同一個目錄下輸入下面這行命令,就會得到 rob_robot.gv 和 file rob_robot.pdf 兩個文件,打開后者如下圖所示。
urdf_to_graphiz rob.urdf

5. 在RViz中觀看模型。
編寫 launch 文件,取名: description.launch ,內容如下:
<launch> <arg name="model" /> <!-- Parsing xacro and setting robot_description parameter --> <param name="robot_description" command="$(find xacro)/xacro.py $(find rob_description)/urdf/rob.xacro"/> <!-- Setting gui parameter to true for display joint slider --> <param name="use_gui" value="true"/> <!-- Starting Joint state publisher node which will publish the joint values --> <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /> <!-- Starting robot state publish which will publish tf --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /> <!-- Launch visualization in rviz --> <node name="rviz" pkg="rviz" type="rviz" args="-d $(find rob_description)/urdf/urdf.rviz" required="true" /> </launch>
輸入命令:
roslaunch rob_description description.launch
得到:

轉動每個關節,檢查無誤后,模型建立完成,下一篇經介紹如何使用 MoveIt 控制 Rob 機器人。
6. Tips 建模常見錯誤:
問題1:如果在查看模型時發現錯誤提示:No transform from [xxxx] to [base_link]
解決辦法:出現這個錯誤首先要懷疑是你的xacro描述文件編寫的格式出現了錯誤,如頭部多了空格、中間關鍵字拼寫錯誤等,建議耐下心來逐行逐句檢查語法。
問題2: 源碼中和xacro文件同一目錄的 urdf.rviz 文件是什么作用?
答:所有的 .rviz 文件都是 Rviz 的配置文件,這里我們在launch 文件中制定了他的配置文件,如果不指定Rviz 啟動時會讀取默認的配置文件,用戶可以根據需求啟動Rviz后在左上角工具欄上保存自己滿意的配置文件。
<-- 本篇完 -->
歡迎留言、私信、郵箱、微信等任何形式的技術交流。
作者信息:
名稱:Shawn
郵箱:zhanggx0102@163.com
微信二維碼:↓

