ROS探索总结(六)——使用smartcar进行仿真

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

一、模型完善

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

1、机器人主体

[plain]  view plain copy
  1. <?xml version="1.0"?>  
  2. <robot name="smartcar" xmlns:xacro="http://ros.org/wiki/xacro">  
  3.   <property name="M_PI" value="3.14159"/>  
  4.   
  5.   <!-- Macro for SmartCar body. Including Gazebo extensions, but does not include Kinect -->  
  6.   <include filename="$(find smartcar_description)/urdf/gazebo.urdf.xacro"/>  
  7.   
  8.   <property name="base_x" value="0.33" />  
  9.   <property name="base_y" value="0.33" />  
  10.   
  11.   <xacro:macro name="smartcar_body">  
  12.   
  13.   
  14.     <link name="base_link">  
  15.     <inertial>  
  16.       <origin xyz="0 0 0.055"/>  
  17.       <mass value="1.0" />  
  18.       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  19.     </inertial>  
  20.     <visual>  
  21.       <geometry>  
  22.         <box size="0.25 .16 .05"/>  
  23.       </geometry>  
  24.       <origin rpy="0 0 0" xyz="0 0 0.055"/>  
  25.       <material name="blue">  
  26.       <color rgba="0 0 .8 1"/>  
  27.       </material>  
  28.    </visual>  
  29.    <collision>  
  30.       <origin rpy="0 0 0" xyz="0 0 0.055"/>  
  31.       <geometry>  
  32.         <box size="0.25 .16 .05" />  
  33.       </geometry>  
  34.     </collision>  
  35.   </link>  
  36.   
  37.   
  38.  <link name="left_front_wheel">  
  39.     <inertial>  
  40.       <origin  xyz="0.08 0.08 0.025"/>  
  41.       <mass value="0.1" />  
  42.        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  43.     </inertial>  
  44.     <visual>  
  45.       <geometry>  
  46.         <cylinder length=".02" radius="0.025"/>  
  47.       </geometry>  
  48.       <material name="black">  
  49.         <color rgba="0 0 0 1"/>  
  50.       </material>  
  51.     </visual>  
  52.     <collision>  
  53.       <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>  
  54.       <geometry>  
  55.          <cylinder length=".02" radius="0.025"/>  
  56.       </geometry>  
  57.     </collision>  
  58.   </link>  
  59.   
  60.   <joint name="left_front_wheel_joint" type="continuous">  
  61.     <axis xyz="0 0 1"/>  
  62.     <parent link="base_link"/>  
  63.     <child link="left_front_wheel"/>  
  64.     <origin rpy="0 1.57075 1.57075" xyz="0.08 0.08 0.025"/>  
  65.     <limit effort="100" velocity="100"/>  
  66.     <joint_properties damping="0.0" friction="0.0"/>  
  67.   </joint>  
  68.   
  69.   <link name="right_front_wheel">  
  70.     <inertial>  
  71.       <origin xyz="0.08 -0.08 0.025"/>  
  72.       <mass value="0.1" />  
  73.        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  74.     </inertial>  
  75.     <visual>  
  76.       <geometry>  
  77.         <cylinder length=".02" radius="0.025"/>  
  78.       </geometry>  
  79.       <material name="black">  
  80.         <color rgba="0 0 0 1"/>  
  81.       </material>  
  82.     </visual>  
  83.     <collision>  
  84.       <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>  
  85.       <geometry>  
  86.          <cylinder length=".02" radius="0.025"/>  
  87.       </geometry>  
  88.     </collision>  
  89.   </link>  
  90.   
  91.   <joint name="right_front_wheel_joint" type="continuous">  
  92.     <axis xyz="0 0 1"/>  
  93.     <parent link="base_link"/>  
  94.     <child link="right_front_wheel"/>  
  95.     <origin rpy="0 1.57075 1.57075" xyz="0.08 -0.08 0.025"/>  
  96.     <limit effort="100" velocity="100"/>  
  97.     <joint_properties damping="0.0" friction="0.0"/>  
  98.  </joint>  
  99.   
  100.  <link name="left_back_wheel">  
  101.     <inertial>  
  102.       <origin xyz="-0.08 0.08 0.025"/>  
  103.       <mass value="0.1" />  
  104.        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  105.     </inertial>  
  106.     <visual>  
  107.       <geometry>  
  108.         <cylinder length=".02" radius="0.025"/>  
  109.       </geometry>  
  110.       <material name="black">  
  111.         <color rgba="0 0 0 1"/>  
  112.       </material>  
  113.    </visual>  
  114.    <collision>  
  115.        <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>  
  116.       <geometry>  
  117.          <cylinder length=".02" radius="0.025"/>  
  118.       </geometry>  
  119.     </collision>  
  120.   </link>  
  121.   
  122.   <joint name="left_back_wheel_joint" type="continuous">  
  123.     <axis xyz="0 0 1"/>  
  124.     <parent link="base_link"/>  
  125.     <child link="left_back_wheel"/>  
  126.     <origin rpy="0 1.57075 1.57075" xyz="-0.08 0.08 0.025"/>  
  127.     <limit effort="100" velocity="100"/>  
  128.     <joint_properties damping="0.0" friction="0.0"/>  
  129.   </joint>  
  130.   
  131.   <link name="right_back_wheel">  
  132.     <inertial>  
  133.        <origin xyz="-0.08 -0.08 0.025"/>  
  134.        <mass value="0.1" />  
  135.        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  136.     </inertial>  
  137.     <visual>  
  138.       <geometry>  
  139.         <cylinder length=".02" radius="0.025"/>  
  140.       </geometry>  
  141.       <material name="black">  
  142.         <color rgba="0 0 0 1"/>  
  143.       </material>  
  144.    </visual>  
  145.    <collision>  
  146.       <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>  
  147.       <geometry>  
  148.          <cylinder length=".02" radius="0.025"/>  
  149.       </geometry>  
  150.     </collision>  
  151.   </link>  
  152.   
  153.   
  154.   <joint name="right_back_wheel_joint" type="continuous">  
  155.     <axis xyz="0 0 1"/>  
  156.     <parent link="base_link"/>  
  157.     <child link="right_back_wheel"/>  
  158.     <origin rpy="0 1.57075 1.57075" xyz="-0.08 -0.08 0.025"/>  
  159.     <limit effort="100" velocity="100"/>  
  160.     <joint_properties damping="0.0" friction="0.0"/>  
  161.   </joint>  
  162.   
  163.   <link name="head">  
  164.     <inertial>  
  165.       <origin xyz="0.08 0 0.08"/>  
  166.       <mass value="0.1" />  
  167.       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  168.     </inertial>  
  169.     <visual>  
  170.       <geometry>  
  171.         <box size=".02 .03 .03"/>  
  172.       </geometry>  
  173.       <material name="white">  
  174.         <color rgba="1 1 1 1"/>  
  175.       </material>  
  176.      </visual>  
  177.      <collision>  
  178.       <origin xyz="0.08 0 0.08"/>  
  179.       <geometry>  
  180.          <cylinder length=".02" radius="0.025"/>  
  181.       </geometry>  
  182.     </collision>  
  183.   </link>  
  184.   
  185.   <joint name="tobox" type="fixed">  
  186.     <parent link="base_link"/>  
  187.     <child link="head"/>  
  188.     <origin xyz="0.08 0 0.08"/>  
  189.   </joint>  
  190.   </xacro:macro>  
  191.   
  192. </robot>  

2、gazebo属性部分

[plain]  view plain copy
  1. <?xml version="1.0"?>  
  2.   
  3. <robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"   
  4.     xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"   
  5.     xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"   
  6.     xmlns:xacro="http://ros.org/wiki/xacro"   
  7.     name="smartcar_gazebo">  
  8.   
  9. <!-- ASUS Xtion PRO camera for simulation -->  
  10. <!-- gazebo_ros_wge100 plugin is in kt2_gazebo_plugins package -->  
  11. <xacro:macro name="smartcar_sim">  
  12.     <gazebo reference="base_link">  
  13.         <material>Gazebo/Blue</material>  
  14.     </gazebo>  
  15.   
  16.     <gazebo reference="right_front_wheel">  
  17.         <material>Gazebo/FlatBlack</material>  
  18.     </gazebo>  
  19.   
  20.     <gazebo reference="right_back_wheel">  
  21.         <material>Gazebo/FlatBlack</material>  
  22.     </gazebo>  
  23.   
  24.     <gazebo reference="left_front_wheel">  
  25.         <material>Gazebo/FlatBlack</material>  
  26.     </gazebo>  
  27.   
  28.     <gazebo reference="left_back_wheel">  
  29.         <material>Gazebo/FlatBlack</material>  
  30.     </gazebo>  
  31.   
  32.     <gazebo reference="head">  
  33.         <material>Gazebo/White</material>  
  34.     </gazebo>  
  35.   
  36. </xacro:macro>  
  37.   
  38. </robot>  

3、主文件

[cpp]  view plain copy
  1. <span style="font-size:14px;"><?xml version="1.0"?>  
  2.   
  3. <robot name="smartcar"    
  4.     xmlns:xi="http://www.w3.org/2001/XInclude"  
  5.     xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"  
  6.     xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"  
  7.     xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"  
  8.     xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"  
  9.     xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"  
  10.     xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"  
  11.     xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"  
  12.     xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"  
  13.     xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"  
  14.     xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"  
  15.     xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics"  
  16.     xmlns:xacro="http://ros.org/wiki/xacro">  
  17.   
  18.   <include filename="$(find smartcar_description)/urdf/smartcar_body.urdf.xacro" />  
  19.   
  20.   <!-- Body of SmartCar, with plates, standoffs and Create (including sim sensors) -->  
  21.   <smartcar_body/>  
  22.   
  23.   <smartcar_sim/>  
  24.   
  25. </robot></span>  



二、lanuch文件

        在launch文件中要启动节点和模拟器。
[plain]  view plain copy
  1. <launch>  
  2.     <param name="/use_sim_time" value="false" />  
  3.       
  4.     <!-- Load the URDF/Xacro model of our robot -->  
  5.     <arg name="urdf_file" default="$(find xacro)/xacro.py '$(find smartcar_description)/urdf/smartcar.urdf.xacro'" />  
  6.     <arg name="gui" default="false" />  
  7.   
  8.     <param name="robot_description" command="$(arg urdf_file)" />  
  9.     <param name="use_gui" value="$(arg gui)"/>  
  10.   
  11.     <node name="arbotix" pkg="arbotix_python" type="driver.py" output="screen">  
  12.         <rosparam file="$(find smartcar_description)/config/smartcar_arbotix.yaml" command="load" />  
  13.         <param name="sim" value="true"/>  
  14.     </node>  
  15.   
  16.     <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" >  
  17.     </node>  
  18.   
  19.     <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher">  
  20.         <param name="publish_frequency" type="double" value="20.0" />  
  21.     </node>  
  22.   
  23.      <!-- We need a static transforms for the wheels -->  
  24.     <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" />  
  25.     <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" />  
  26.   
  27.     <node name="rviz" pkg="rviz" type="rviz" args="-d $(find smartcar_description)/urdf.vcg" />  
  28. </launch>  

三、仿真测试

        首先运行lanuch,既可以看到rviz中的机器人:
[plain]  view plain copy
  1. roslaunch smartcar_description smartcar_display.rviz.launch  

        
         发布一条动作的消息。
[plain]  view plain copy
  1. 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

欢迎继续关注我的博客

  • 0
    点赞
  • 0
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值