< >
Home » ROS探索总结 » ROS探索总结-6.使用smartcar进行仿真

ROS探索总结-6.使用smartcar进行仿真

使用smartcar进行仿真

之前的博客中,我们使用rviz进行了TurtleBot的仿真,而且使用urdf文件建立了自己的机器人smartcar,本篇博客是将两者进行结合,使用smartcar机器人在rviz中进行仿真。

urdf相关工具安装(补充)

  1. 安装urdf_tutorial,可以使用其中的例子
$ sudo apt-get install ros-indigo-urdf-tutorial  
  1. 安装liburdfdom-tools,提供对urdf文件的检查
$ sudo apt-get install liburdfdom-tools

一、模型完善

之前我们使用的都是urdf文件格式的模型,在很多情况下,ROS对urdf文件的支持并不是很好,使用宏定义的.xacro文件兼容性更好,扩展性也更好。所以我们把之前的urdf文件重新整理编写成.xacro文件。

.xacro文件主要分为三部分:

1、机器人主体smartcar_body.urdf.xacro

<?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="1.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="0.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="0.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="0.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="0.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="0.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>

注意:原版本在indigo可能运行有问题,修改的indigo版本如下:

<?xml version="1.0"?>  
<robot name="smartcar" xmlns:xacro="http://ros.org/wiki/xacro">  
  <xacro:property name="M_PI" value="3.14159"/>    
  <!-- Macro for SmartCar body. Including Gazebo extensions, but does not include Kinect -->  
  <xacro:include filename="$(find smartcar_description)/urdf/gazebo.urdf.xacro"/>  
  <xacro:property name="base_x" value="0.33" />  
  <xacro: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="1.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="0.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="0.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="0.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="0.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="0.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>
  • 修改property,为xacro:property
  • 修改include, 为xacro:include

2、gazebo属性部分 gazebo.urdf.xacro

<?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>  

    </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>

3、主文件 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>

注意:原来的在indigo下运行有问题,修改的indigo版本如下:

<?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">  

 

  <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>
  • 修改include, 为xacro:include

二、lanuch文件smartcar_display.rviz.launch

在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="driver.py" 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" />  

</launch>

注意:原来的版本在indigo运行有问题,修改的indigo版本如下:

<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.rviz" />  

</launch>
  • 修改driver.py为arbotix_driver

  • 修改urdf.vcg 为urdf.rviz,确保在smartcar_description目录下有urdf.rviz。从urdf_tutorial目录提取

$ cd ~/catkin_ws/src/smartcar_description
$ cp /opt/ros/indigo/share/urdf_tutorial/urdf.rviz  .
  1. 在indigo版本里,新增smartcar_description/config/smartcar_arbotix.yaml文件,内容为:
port: /dev/ttyUSB0
baud: 115200
rate: 20
sync_write: True
sync_read: True
read_rate: 20
write_rate: 20

controllers: {
   #  Pololu motors: 1856 cpr = 0.3888105m travel = 4773 ticks per meter (empirical: 4100)
   base_controller: {type: diff_controller, base_frame_id: base_link, base_width: 0.26, ticks_meter: 4100, Kp: 12, Kd: 12, Ki: 0, Ko: 50, accel_limit: 1.0 }
}

三、仿真测试

首先运行lanuch,既可以看到rviz中的机器人:

roslaunch smartcar_description smartcar_display.rviz.launch
 

效果图:

请输入图片描述

发布一条动作的消息:

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}}'

效果图:

请输入图片描述

四、节点关系

运行rqt_graph:

$ rqt_graph

效果图:

请输入图片描述

参考:

  • http://wiki.ros.org/urdf/Tutorials
  • http://wiki.ros.org/xacro
  • http://blog.csdn.net/sunbibei/article/details/52297524
  • http://blog.csdn.net/sujun3304/article/details/18962719

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros探索总结, ros基础, ros新手, ros仿真