注:本篇博文所有源碼下載地址爲:Git Repo傳送門。html
1. 下載到本地後解壓到當前文件夾而後運行:catkin_make 編譯。node
2. 源碼是在 Ubuntu14.04 + Indigo 環境下編寫。git
前面博文已經介紹了機器人平臺的機械結構設計、嵌入式硬件平臺的搭建等內容,從本片開始介紹本開源機器人平臺ROS系統的相關程序,主要有:github
隨着本開源項目展開,全部的代碼都會公開源碼且GitHub託管。須要註明的是:算法
OK,如今開始介紹機器人在ROS系統的建模方法,這裏能夠參考博主以前寫的一篇雙臂機器人的ROS建模方法(傳送門),在開始動手本身建模以前,強烈推薦先精讀ROS系統最基本的建模相關的語法介紹:微信
通過這兩篇文章的學習,基本能夠掌握ROS系統的模型描述文件的基本語法,本開源平臺仍然採用Xacro文件進行模型創建。app
1、模型描述文件中網格(mesh)文件的生成框架
前面的文章已經介紹了本開源機器人平臺的機械結構設計(傳送門),下面簡單講解一下模型描述文件中的引用三維網格文件的生成。Urdf/Xacro文件中支持兩種網格三維文件類型:.STL文件類型和 .DAE文件類型。ide
咱們利用SolidWorks建立機器人三維模型以後,首先能夠直接保存成STL文件類型。工具
Tips:SW中從裝配體(或零件)保存到STL文件時能夠先建立參考座標系,而後另存爲的時候,在選項中選擇參考座標系就能夠在模型上自定義座標系的位置。
在上一步生成的STL的基礎上,利用三維動畫製做軟件Blender生成 .DAE文件,很簡單,只須要在「文件」下拉菜單中「導入」菜單經文件導入,而後用「導出」菜單選擇導出成 .DAE格式的文件便可。
2、 模型描述文件的編寫
本開源機器人建模文件集成在homerobot_description軟件包(package)裏面,能夠在本篇文章開頭給出的代碼倉下載,該package的文件樹結構如圖1所示:
圖1 homerobot_description包文件樹
其中模型描述文件名稱爲:homerobot.xacro,這裏截取幾個比較重要的片斷解釋一下。
1. 開始的一些宏定義和聲明就不作解釋了,base_footprint相關定義以下:
<link name="base_footprint"> <visual> <geometry> <box size="0.001 0.001 0.001"/> </geometry> <origin rpy="0 0 0" xyz="0 0 0"/> </visual> </link> <joint name="base_footprint_joint" type="fixed"> <origin xyz="0 0 0.084" /> <parent link="base_footprint" /> <child link="base_link" /> </joint>
這個座標系(base_footprint)不是必須的,而是習慣性的寫法,它是人爲定義出來的一個能夠稱做爲「影子」的座標系,它和base_link惟一的不一樣點就是Z座標上的值不一樣。這裏咱們先繪製了一個很是小的正方體(geometry)做爲連桿(link),而後規定了關節(joint)的屬性,即base_link和base_footprint的鏈接關係。
2. 關於base_link的定義
<link name="base_link"> <visual> <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> <geometry> <mesh filename="package://homerobot_description/meshes/base_link.dae"/> </geometry> <material name="green" /> </visual> <collision> <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> <geometry> <mesh filename="package://homerobot_description/meshes/base_link.dae"/> </geometry> </collision> <xacro:inertial_matrix mass="5"/> </link>
這裏就涉及到引用.dae文件的語法了:
<mesh filename="package://homerobot_description/meshes/base_link.dae"/>
因爲咱們的三維網格文件base_link.dae提早就生成好了,因此這裏直接引用就能夠了,後面咱們會經過可視化工具看到,這裏link和joint的語法參考文章前面給出的詳解文檔,此外,這裏有一個宏定義的引用語句:
<xacro:inertial_matrix mass="5"/>
這裏引用開頭定義的宏:轉動慣量矩陣計算,而後將質量參數(mass="5")傳入宏就指明瞭base_link的慣量矩陣。<collision>語句指出了base_link的碰撞檢測範圍,這裏能夠引用本體,也能夠人爲擴大一個範圍。
3. 主動輪的定義
<joint name="L_Wheel_joint" type="continuous"> <parent link="base_link"/> <child link="L_Wheel_link"/> <origin xyz="-0.075 0.1885 -0.034" rpy="1.5707963 0 0" /> <axis xyz="0 0 -1" /> <limit effort="100" velocity="100"/> <!-- velocity: m/s for prismatic, rad/s for revolute --> <!-- <dynamics damping="50" friction="1"/> --> <dynamics damping="0.1" friction="0.5"/> <!-- friction: N for prismatic joints, N.m for revolute joints --> </joint> <link name="L_Wheel_link"> <visual> <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> <geometry> <mesh filename="package://homerobot_description/meshes/L_wheel.dae"/> </geometry> <material name="Black" /> </visual> <collision> <origin xyz="0.0 0.0 0.0" rpy="0 0 0" /> <geometry> <mesh filename="package://homerobot_description/meshes/L_wheel.dae"/> </geometry> </collision> <xacro:inertial_matrix mass="1"/> </link>
這裏有幾個參數值得注意:
<axis xyz="0 0 -1" />
指定了轉軸爲Z軸;
<limit effort="100" velocity="100"/>
最大的驅動力矩和最大轉速均設定爲100,這裏能夠根據不一樣平臺修改,其中,速度單位對於移動副來講是m/s,對於轉動副來講是rad/s,這裏joint的類型type是continuous,即連續轉動,所以這裏單位是後者。
4. Xacro文件的include用法
在Xacro文件中一樣能夠引用外部的一些設置文件,在這裏有一句:
<xacro:include filename="$(find homerobot_description)/urdf/homerobot.gazebo" />
這裏引用了homerobot_description包下面的homerobot.gazebo文件,這個文件是對機器人在gazebo仿真環境下的一些仿真參數設置,後面分一篇博文詳細講講ROS系統與Gazebo仿真環境。
3、ROS系統和Rviz可視化工具
ROS系統很是好的集成了Rviz這一可視化調試工具,大大方便了機器人開發調試的工做(除了偶爾會crash,這個工具真的很是贊)。這裏咱們固然要用可視化工具看看上面編寫完成的機器人模型描述文件,編寫launch文件,名稱爲:description.launch,內容以下:
<launch> <arg name="model" /> <!-- Parsing xacro and setting robot_description parameter --> <param name="robot_description" textfile="$(find homerobot_description)/urdf/homerobot.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 homerobot_description)/launch/urdf.rviz" required="true"/> </launch>
關於如何理解launch文件,請參考官方文檔(傳送門)。若是一切正常的話就會看到下面的圖示效果。
圖2 機器人平臺在Rviz中
4、ROS系統的tf tree(空間座標變換樹)
這裏tf應該是transform的縮寫,是指空間中兩個三維座標系的轉換關係,這種轉換關係通常能夠分爲:平移和旋轉。表徵這些轉換關係的方法也有不少,比較經常使用的就是:
其實他們這件是能夠相互轉化的。
前面有一篇博文:ROS系統MoveIt玩轉雙臂機器人系列(五)--淺議機器人運動學與D-H建模(傳送門)中有簡單介紹了空間座標系的基礎知識。
具體到ROS系統中,它提出了tf tree的概念,也就是在建模的時候你就已經指定了一個機器人一共有幾個座標系,各個座標系之間的轉換關係是如何的(上面xacro文件中的link和joint定義的時候就已經說明了各個零部件之間的位置關係和運動關係),若是有信息缺失則tf tree必定是有缺失的。ROS系統提供了tf查看工具,在命令行運行:
rosrun rqt_tf_tree rqt_tf_tree
就能夠獲得下圖所示的效果,咱們能夠直觀的看出各個link之間的轉換關係。
圖3 tf樹截圖
<-- 本篇完 -->
歡迎留言、私信、郵箱、微信等任何形式的技術交流。
做者信息:
名稱:Shawn
郵箱:zhanggx0102@163.com