1. 程式人生 > >ROS系統玩轉自主移動機器人(5)-- ROS系統建模

ROS系統玩轉自主移動機器人(5)-- ROS系統建模

關節 evo 編譯 val mpi ans ros 三維 mil

註:本篇博文全部源碼下載地址為:Git Repo傳送門

1. 下載到本地後解壓到當前文件夾然後運行:catkin_make 編譯。

2. 源碼是在 Ubuntu14.04 + Indigo 環境下編寫。

  前面博文已經介紹了機器人平臺的機械結構設計、嵌入式硬件平臺的搭建等內容,從本片開始介紹本開源機器人平臺ROS系統的相關程序,主要有:

  • ROS系統建模;
  • Gazebo仿真;
  • ROS系統機器人SLAM框架;
  • SLAM中Gmapping和地圖構建;
  • SLAM中AMCL算法;
  • 機器人正逆運動學;
  • 路徑規劃;
  • ROS系統與機器人視覺;
  • ROS系統與語音交互;
  • 。。。

  隨著本開源項目展開,所有的代碼都會公開源碼且GitHub托管。需要註明的是:

  1. 這裏的開源的代碼全部是基於X86平臺的Linux開發的;
  2. 代碼中很多是和嵌入式平臺(小車運控板)交互的內容,小車的嵌入式軟件所有的源代碼後面也會分幾篇博文介紹並全部公開。

  OK,現在開始介紹機器人在ROS系統的建模方法,這裏可以參考博主之前寫的一篇雙臂機器人的ROS建模方法(傳送門),在開始動手自己建模之前,強烈推薦先精讀ROS系統最基本的建模相關的語法介紹:

  • Urdf/XML詳解(傳送門
  • XML macro language—Xacro(傳送門

  經過這兩篇文章的學習,基本可以掌握ROS系統的模型描述文件的基本語法,本開源平臺仍然采用Xacro文件進行模型建立。

一、模型描述文件中網格(mesh)文件的生成

  前面的文章已經介紹了本開源機器人平臺的機械結構設計(傳送門),下面簡單講解一下模型描述文件中的引用三維網格文件的生成。Urdf/Xacro文件中支持兩種網格三維文件類型:.STL文件類型和 .DAE文件類型。

  • 生成 .STL文件類型:

  我們利用SolidWorks創建機器人三維模型之後,首先可以直接保存成STL文件類型。

    Tips:SW中從裝配體(或零件)保存到STL文件時可以先創建參考坐標系,然後另存為的時候,在選項中選擇參考坐標系就可以在模型上自定義坐標系的位置。

  • 生成 .DAE文件類型:

在上一步生成的STL的基礎上,利用三維動畫制作軟件Blender生成 .DAE文件,很簡單,只需要在“文件”下拉菜單中“導入”菜單經文件導入,然後用“導出”菜單選擇導出成 .DAE格式的文件即可。

二、 模型描述文件的編寫

  本開源機器人建模文件集成在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仿真環境。

三、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中

四、ROS系統的tf tree(空間坐標變換樹)

  這裏tf應該是transform的縮寫,是指空間中兩個三維坐標系的轉換關系,這種轉換關系一般可以分為:平移和旋轉。表征這些轉換關系的方法也有很多,比較常用的就是:

  • 齊次轉換矩陣
  • 歐拉角(RPY)
  • 四元數

  其實他們這件是可以相互轉化的。

  前面有一篇博文: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

郵箱:[email protected]

ROS系統玩轉自主移動機器人(5)-- ROS系統建模