1. 程式人生 > >ROS探索(4)——SmartCar模擬

ROS探索(4)——SmartCar模擬

在之前的部落格中描述了在 rviz 下的 TurtleBot 的模擬和簡易模型 SmartCar 的搭建,在本節介紹一下如何對 SmartCar 進行 rviz 上的模擬

由於 ROS 對 *.urdf 檔案的支援不是很好,因此使用巨集定義的,拓展性、相容性較好 *.xacro 檔案替換 *.urdf 進行優化。

 *.xacro 檔案主要包括3部分:smartcar_body.urdf.xacro(SmartCar模型描述檔案),gazebo.urdf.xacro(gazebo屬性描述檔案),smartcar.urdf.xacro(主體控制檔案)

smartcar_body.urdf.xacro(SmartCar模型描述檔案):


<?xml version="1.0"?>
<robot name="smartcar" xmlns:xacro="http://ros.org/wiki/xacro">
  <property name="M_PI" value="3.14159"/>

  <!-- Macro for SmartCar body. Including Gazebo extensions, but does not include Kinect -->
  <include filename="$(find smartcar_description)/urdf/gazebo.urdf.xacro"/>

  <property name="base_x" value="0.33" />
  <property name="base_y" value="0.33" />

  <xacro:macro name="smartcar_body">


	<link name="base_link">
	<inertial>
      <origin xyz="0 0 0.055"/>
      <mass value="100.0" />
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <box size="0.25 .16 .05"/>
      </geometry>
	  <origin rpy="0 0 0" xyz="0 0 0.055"/>
      <material name="blue">
	  <color rgba="0 0 .8 1"/>
      </material>
   </visual>
   <collision>
      <origin rpy="0 0 0" xyz="0 0 0.055"/>
      <geometry>
        <box size="0.25 .16 .05" />
      </geometry>
    </collision>
  </link>


 <link name="left_front_wheel">
	<inertial>
      <origin  xyz="0.08 0.08 0.025"/>
      <mass value="1" />
       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <cylinder length=".02" radius="0.025"/>
      </geometry>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
      <geometry>
         <cylinder length=".02" radius="0.025"/>
      </geometry>
    </collision>
  </link>

  <joint name="left_front_wheel_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="left_front_wheel"/>
    <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  <link name="right_front_wheel">
	<inertial>
      <origin xyz="0.08 -0.08 0.025"/>
      <mass value="1" />
       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <cylinder length=".02" radius="0.025"/>
      </geometry>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
      <geometry>
         <cylinder length=".02" radius="0.025"/>
      </geometry>
    </collision>
  </link>

  <joint name="right_front_wheel_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="right_front_wheel"/>
    <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
 </joint>

 <link name="left_back_wheel">
    <inertial>
      <origin xyz="-0.08 0.08 0.025"/>
      <mass value="1" />
       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <cylinder length=".02" radius="0.025"/>
      </geometry>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
   </visual>
   <collision>
       <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
      <geometry>
         <cylinder length=".02" radius="0.025"/>
      </geometry>
    </collision>
  </link>

  <joint name="left_back_wheel_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="left_back_wheel"/>
    <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  <link name="right_back_wheel">
	<inertial>
       <origin xyz="-0.08 -0.08 0.025"/>
       <mass value="1" />
       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <cylinder length=".02" radius="0.025"/>
      </geometry>
      <material name="black">
        <color rgba="0 0 0 1"/>
      </material>
   </visual>
   <collision>
      <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
      <geometry>
         <cylinder length=".02" radius="0.025"/>
      </geometry>
    </collision>
  </link>


  <joint name="right_back_wheel_joint" type="continuous">
    <axis xyz="0 0 1"/>
    <parent link="base_link"/>
    <child link="right_back_wheel"/>
    <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>
    <limit effort="100" velocity="100"/>
    <joint_properties damping="0.0" friction="0.0"/>
  </joint>

  <link name="head">
	<inertial>
      <origin xyz="0.08 0 0.08"/>
      <mass value="1" />
      <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
    </inertial>
    <visual>
      <geometry>
        <box size=".02 .03 .03"/>
      </geometry>
	  <material name="white">
		<color rgba="1 1 1 1"/>
	  </material>
     </visual>
     <collision>
      <origin xyz="0.08 0 0.08"/>
      <geometry>
         <cylinder length=".02" radius="0.025"/>
      </geometry>
    </collision>
  </link>

  <joint name="tobox" type="fixed">
    <parent link="base_link"/>
    <child link="head"/>
    <origin xyz="0.08 0 0.08"/>
  </joint>
  </xacro:macro>

</robot>
gazebo.urdf.xacro(gazebo屬性描述檔案):
<?xml version="1.0"?>

<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
	xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
	xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
	xmlns:xacro="http://ros.org/wiki/xacro"
	name="smartcar_gazebo">

<!-- ASUS Xtion PRO camera for simulation -->
<!-- gazebo_ros_wge100 plugin is in kt2_gazebo_plugins package -->
<xacro:macro name="smartcar_sim">
    <gazebo reference="base_link">
      <material>Gazebo/Blue</material>
      <turnGravityOff>false</turnGravityOff>
    </gazebo>

    <gazebo reference="right_front_wheel">
      <material>Gazebo/FlatBlack</material>
		</gazebo>

		<gazebo reference="right_back_wheel">
        <material>Gazebo/FlatBlack</material>
    </gazebo>

    <gazebo reference="left_front_wheel">
        <material>Gazebo/FlatBlack</material>
    </gazebo>

    <gazebo reference="left_back_wheel">
        <material>Gazebo/FlatBlack</material>
    </gazebo>

    <gazebo reference="head">
        <material>Gazebo/White</material>
    </gazebo>

</xacro:macro>

</robot>
smartcar.urdf.xacro(主體控制檔案)
<?xml version="1.0"?>

<robot name="smartcar"
  xmlns:xi="http://www.w3.org/2001/XInclude"
	xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
  xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
	xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
	xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
  xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
  xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
	xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
	xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
	xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
  xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
  xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"
	xmlns:xacro="http://ros.org/wiki/xacro">

  <include filename="$(find smartcar_description)/urdf/smartcar_body.urdf.xacro" />

  <!-- Body of SmartCar, with plates, standoffs and Create (including sim sensors) -->
  <smartcar_body/>

  <smartcar_sim/>

</robot>
為了能使用指令控制 SmartCar 在 rviz 中的運動,我們可能還需要更改呼叫的 *.rviz 檔案,使呼叫的 rviz 支援指令操作。

因此使用cp指令將 /opt/ros/indigo/share/urdf_tutorial 目錄下的 urdf.rviz拷貝到專案目錄 ~/catkin_ws/src/smartcar_description 下,然後參照 Git 提供的Demo rbx1 的sim.rviz(在 rviz 下的 TurtleBot 的模擬時使用過,檔案位置在 rbx1/rbx1_nav 目錄下),主要更改部分是將 Fixed Frame 的物件改為 odom。更改部分Visualization Manager到

Tools之間,程式碼如下:

Panels:
  - Class: rviz/Displays
    Help Height: 78
    Name: Displays
    Property Tree Widget:
      Expanded:
        - /Global Options1
        - /Status1
      Splitter Ratio: 0.5
    Tree Height: 565
  - Class: rviz/Selection
    Name: Selection
  - Class: rviz/Tool Properties
    Expanded:
      - /2D Pose Estimate1
      - /2D Nav Goal1
      - /Publish Point1
    Name: Tool Properties
    Splitter Ratio: 0.588679
  - Class: rviz/Views
    Expanded:
      - /Current View1
    Name: Views
    Splitter Ratio: 0.5
  - Class: rviz/Time
    Experimental: false
    Name: Time
    SyncMode: 0
    SyncSource: ""
Visualization Manager:
  Class: ""
  Displays:
  - Alpha: 0.5
    Cell Size: 0.5
    Class: rviz/Grid
    Color: 160; 160; 164
    Enabled: true
    Line Style:
    Line Width: 0.03
    Value: Lines
    Name: Grid
    Normal Cell Count: 0
    Offset:
      X: 0
      Y: 0
      Z: 0
    Plane: XY
    Plane Cell Count: 20
    Reference Frame: odom
    Value: true
  - Angle Tolerance: 0.05
    Class: rviz/Odometry
    Color: 221; 200; 14
    Enabled: true
    Keep: 100
    Length: 0.6
    Name: Odometry
    Position Tolerance: 0.1
    Topic: /odom
    Value: true
  - Angle Tolerance: 0.1
    Class: rviz/Odometry
    Color: 253; 124; 0
    Enabled: false
    Keep: 100
    Length: 0.6
    Name: Odometry EKF
    Position Tolerance: 0.1
    Topic: /odom
    Value: false
  - Alpha: 1
    Class: rviz/RobotModel
    Collision Enabled: false
    Enabled: true
    Links:
      All Links Enabled: true
      Expand Joint Details: false
      Expand Link Details: false
      Expand Tree: false
      Link Tree Style: Links in Alphabetic Order
      base_link:
        Alpha: 1
        Show Axes: false
        Show Trail: false
        Value: true
      left_front_wheel:
        Alpha: 1
        Show Axes: false
        Show Trail: false
        Value: true
      right_front_wheel:
        Alpha: 1
        Show Axes: false
        Show Trail: false
        Value: true
      left_back_wheel:
          Alpha: 1
          Show Axes: false
          Show Trail: false
          Value: true
      right_back_wheel:
          Alpha: 1
          Show Axes: false
          Show Trail: false
          Value: true
      head:
          Alpha: 1
          Show Axes: false
          Show Trail: false
          Value: true
    Name: RobotModel
    Robot Description: robot_description
    TF Prefix: ""
    Update Interval: 0
    Value: true
    Visual Enabled: true
  Enabled: true
  Global Options:
    Background Color: 31; 31; 31
    Fixed Frame: odom
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz/Interact
      Hide Inactive Objects: true
    - Class: rviz/MoveCamera
    - Class: rviz/Select
    - Class: rviz/FocusCamera
    - Class: rviz/Measure
    - Class: rviz/SetInitialPose
      Topic: /initialpose
    - Class: rviz/SetGoal
      Topic: /move_base_simple/goal
    - Class: rviz/PublishPoint
      Single click: true
      Topic: /clicked_point
  Value: true
  Views:
    Current:
      Class: rviz/Orbit
      Distance: 10
      Focal Point:
        X: 0
        Y: 0
        Z: 0
      Name: Current View
      Near Clip Distance: 0.01
      Pitch: 0.465398
      Target Frame: <Fixed Frame>
      Value: Orbit (rviz)
      Yaw: 0.885398
    Saved: ~
Window Geometry:
  Displays:
    collapsed: false
  Height: 882
  Hide Left Dock: false
  Hide Right Dock: false
  QMainWindow State: 000000ff00000000fd00000004000000000000013c000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000259000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
  Selection:
    collapsed: false
  Time:
    collapsed: false
  Tool Properties:
    collapsed: false
  Views:
    collapsed: false
  Width: 1216
  X: 53
  Y: 60
編寫launch檔案
<launch>
  <param name="/use_sim_time" value="false" />

	<!-- Load the URDF/Xacro model of our robot -->
  <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find smartcar_description)/urdf/smartcar.urdf.xacro'" />
	<arg name="gui" default="false" />

	<param name="robot_description" command="$(arg urdf_file)" />
	<param name="use_gui" value="$(arg gui)"/>

	<node name="arbotix" pkg="arbotix_python" type="arbotix_driver" output="screen">
    <rosparam file="$(find smartcar_description)/config/smartcar_arbotix.yaml" command="load" />
    <param name="sim" value="true"/>
  </node>

	<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >
	</node>
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">
    <param name="publish_frequency" type="double" value="20.0" />
  </node>

	<!-- We need a static transforms for the wheels -->
  <node pkg="tf" type="static_transform_publisher" name="odom_left_wheel_broadcaster" args="0 0 0 0 0 0 /base_link /left_front_link 100" />
  <node pkg="tf" type="static_transform_publisher" name="odom_right_wheel_broadcaster" args="0 0 0 0 0 0 /base_link /right_front_link 100" />

	<!--<node name="rviz" pkg="rviz" type="rviz" args="-d $(find smartcar_description)/urdf.vcg" />-->
  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find smartcar_description)/smartcar.rviz" />
</launch>
模擬實現:
$ roscore
開啟一個新視窗:
$ source catkin_ws/devel/setup.bash
$ roslaunch smartcar_description smartcar_display.rviz.launch
開啟一個新視窗:
$ source catkin_ws/devel/setup.bash
$ rostopic pub -r 10 /cmd_vel geometry_msgs/Twist '{linear: {x: 0.5, y: 0, z: 0}, angular: {x: 0, y: 0, z: 0.5}}'
效果如下


參考:

http://blog.csdn.net/hcx25909/article/details/8951833

http://wiki.ros.org/urdf/Tutorials/Using%20Xacro%20to%20Clean%20Up%20a%20URDF%20File