ros urdf 文件格式描述

----ROS机器人模型urdf简明笔记----

ros urdf 文件格式描述

ROS库--URDF

  1. 使用URDF从头开始构建可视机器人模型

    了解如何构建一个可以在Rviz中查看的机器人的视觉模型

  2. 使用URDF构建可移动机器人模型

    了解如何在URDF中定义活动关节

  3. 向URDF模型添加物理和冲突属性

    了解如何向链接添加碰撞和惯性属性,以及如何为关节添加关节动力学。

  4. 使用Xacro清理URDF文件

    学习一些技巧,以减少使用Xacro URDF文件中的代码量


----

全部源码:http://download.csdn.net/detail/zhangrelay/9775629

ros urdf 文件格式描述


1 简单的几何形状

这里包括形状,大小,位置,角度和材质等。以下面代码为例,简单介绍一下:

  1. <?xml version="1.0"?>  
  2. <robot name="visual">  
  3.   
  4.   <material name="red">  
  5.     <color rgba="0.8 0 0 1"/>  
  6.   </material>    
  7.   <material name="green">  
  8.     <color rgba="0 0.8 0 1"/>  
  9.   </material>  
  10.   <material name="blue">  
  11.     <color rgba="0 0 0.8 1"/>  
  12.   </material>  
  13.   <material name="black">  
  14.     <color rgba="0 0 0 1"/>  
  15.   </material>  
  16.   <material name="white">  
  17.     <color rgba="1 1 1 1"/>  
  18.   </material>  
  19.   
  20.   <link name="base_link">  
  21.     <visual>  
  22.       <geometry>  
  23.         <cylinder length="0.6" radius="0.2"/>  
  24.       </geometry>  
  25.       <material name="red"/>  
  26.     </visual>  
  27.   </link>  
  28.   
  29.   <link name="right_leg">  
  30.     <visual>  
  31.       <geometry>  
  32.         <box size="0.6 .1 .2"/>  
  33.       </geometry>  
  34.       <origin rpy="0 1.57075 0" xyz="0 0 -0.3"/>  
  35.       <material name="blue"/>  
  36.     </visual>  
  37.   </link>  
  38.   
  39.   <joint name="base_to_right_leg" type="fixed">  
  40.     <parent link="base_link"/>  
  41.     <child link="right_leg"/>  
  42.     <origin xyz="0 -0.22 .25"/>  
  43.   </joint>  
  44.   
  45.   <link name="right_base">  
  46.     <visual>  
  47.       <geometry>  
  48.         <box size="0.4 .1 .1"/>  
  49.       </geometry>  
  50.       <material name="white"/>  
  51.     </visual>  
  52.   </link>  
  53.   
  54.   <joint name="right_base_joint" type="fixed">  
  55.     <parent link="right_leg"/>  
  56.     <child link="right_base"/>  
  57.     <origin xyz="0 0 -0.6"/>  
  58.   </joint>  
  59.   
  60.   <link name="right_front_wheel">  
  61.     <visual>  
  62.       <origin rpy="1.57075 0 0" xyz="0 0 0"/>  
  63.       <geometry>  
  64.         <cylinder length="0.1" radius="0.035"/>  
  65.       </geometry>  
  66.       <material name="black"/>  
  67.       <origin rpy="0 0 0" xyz="0 0 0"/>  
  68.     </visual>  
  69.   </link>  
  70.   <joint name="right_front_wheel_joint" type="fixed">  
  71.     <axis rpy="0 0 0" xyz="0 1 0"/>  
  72.     <parent link="right_base"/>  
  73.     <child link="right_front_wheel"/>  
  74.     <origin rpy="0 0 0" xyz="0.133333333333 0 -0.085"/>  
  75.   </joint>  
  76.   
  77. ...............  
  78.   
  79.   <link name="head">  
  80.     <visual>  
  81.       <geometry>  
  82.         <sphere radius="0.2"/>  
  83.       </geometry>  
  84.       <material name="white"/>  
  85.     </visual>  
  86.   </link>  
  87.   <joint name="head_swivel" type="fixed">  
  88.     <parent link="base_link"/>  
  89.     <child link="head"/>  
  90.     <origin xyz="0 0 0.3"/>  
  91.   </joint>  
  92.   
  93.   <link name="box">  
  94.     <visual>  
  95.       <geometry>  
  96.         <box size=".08 .08 .08"/>  
  97.       </geometry>  
  98.       <material name="green"/>  
  99.     </visual>  
  100.   </link>  
  101.   
  102.   <joint name="tobox" type="fixed">  
  103.     <parent link="head"/>  
  104.     <child link="box"/>  
  105.     <origin xyz="0.1814 0 0.1414"/>  
  106.   </joint>  
  107. </robot>  

----

其中,geometry中包含形状和大小,如cylinder box,大小依据形状不同采用不同表示,如length radius size等;

原点是origin;相对于该点的位置和角度分别用xyz rpy表示;parent link是父节点,child link是子节点。fixed frame固定坐标;

当然,还有颜色等其他配置属性。

使用下面命令查看效果,注意model路径:

  1. roslaunch urdf_tutorial display.launch model:=/home/relaybot/ROS_tutorial/src/urdf_tutorial-kinetic/urdf/05-visual.urdf  

----

ros urdf 文件格式描述

----

2 由静到动让模型运动起来

这里只需要注意一个要点,就是关节joint,上节一般是fixed,这里可以有continuous,revolute,prismatic。

还需要补充的是robot_state_publisherjoint_state_publisher。分别如下图所示:

ros urdf 文件格式描述  ros urdf 文件格式描述


运行下面命令,注意模型路径:

  1. roslaunch urdf_tutorial display.launch model:=/home/relaybot/ROS_tutorial/src/urdf_tutorial-kinetic/urdf/06-flexible.urdf gui:=True  

----

ros urdf 文件格式描述

----

3 添加物理和碰撞属性

需要注意亮点即可,碰撞collision,物理inertial。

  1. <link name="base_link">  
  2.   <visual>  
  3.     <geometry>  
  4.       <cylinder length="0.6" radius="0.2"/>  
  5.     </geometry>  
  6.     <material name="blue"/>  
  7.   </visual>  
  8.   <collision>  
  9.     <geometry>  
  10.       <cylinder length="0.6" radius="0.2"/>  
  11.     </geometry>  
  12.   </collision>  
  13.   <inertial>  
  14.     <mass value="10"/>  
  15.     <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>  
  16.   </inertial>  
  17. </link>  

----
  1. roslaunch urdf_tutorial display.launch model:=/home/relaybot/ROS_tutorial/src/urdf_tutorial-kinetic/urdf/07-physics.urdf  

----

ros urdf 文件格式描述

----

4 使用xacro简化urdf文件

这里给出两个参考网址:xacro在urdf中使用xacro

  1. roslaunch urdf_tutorial display.launch model:=/home/relaybot/ROS_tutorial/src/urdf_tutorial-kinetic/urdf/08-macroed.urdf.xacro  

----

ros urdf 文件格式描述

----

5 在Gazebo中使用urdf

参考网址:http://gazebosim.org/tutorials?tut=ros_urdf

完成配置后,启动命令:

  1. roslaunch urdf_tutorial gazebo.launch  

----

ros urdf 文件格式描述

----

6 rviz和Gazebo中实现同步控制

运行下面命令:

  1. roslaunch urdf_tutorial control.launch  

----

ros urdf 文件格式描述  ros urdf 文件格式描述

----

附录:

TF:

ros urdf 文件格式描述

Graph:

ros urdf 文件格式描述

display.launch

  1. <launch>  
  2.   
  3.   <arg name="model" default="$(find urdf_tutorial)/urdf/r2d2.xacro"/>  
  4.   <arg name="gui" default="true" />  
  5.   <arg name="rvizconfig" default="$(find urdf_tutorial)/rviz/urdf.rviz" />  
  6.   
  7.   <param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />  
  8.   <param name="use_gui" value="$(arg gui)"/>  
  9.   
  10.   <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />  
  11.   <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" />  
  12.   <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />  
  13.   
  14. </launch>  


gazebo.launch

  1. <launch>  
  2.   
  3.   <!-- these are the arguments you can pass this launch file, for example paused:=true -->  
  4.   <arg name="paused" default="false"/>  
  5.   <arg name="use_sim_time" default="true"/>  
  6.   <arg name="gui" default="true"/>  
  7.   <arg name="headless" default="false"/>  
  8.   <arg name="debug" default="false"/>  
  9.   <arg name="model" default="$(find urdf_tutorial)/urdf/r2d2.xacro"/>  
  10.   
  11.   <!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->  
  12.   <include file="$(find gazebo_ros)/launch/empty_world.launch">  
  13.     <arg name="debug" value="$(arg debug)" />  
  14.     <arg name="gui" value="$(arg gui)" />  
  15.     <arg name="paused" value="$(arg paused)"/>  
  16.     <arg name="use_sim_time" value="$(arg use_sim_time)"/>  
  17.     <arg name="headless" value="$(arg headless)"/>  
  18.   </include>  
  19.   
  20.   <param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />  
  21.   
  22.   <!-- push robot_description to factory and spawn robot in gazebo -->  
  23.   <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model"  
  24.         args="-z 1.0 -unpause -urdf -model robot -param robot_description" respawn="false" output="screen" />  
  25.   
  26.   <node pkg="robot_state_publisher" type="robot_state_publisher"  name="robot_state_publisher">  
  27.     <param name="publish_frequency" type="double" value="30.0" />  
  28.   </node>  
  29.   
  30. </launch>  


control.launch

  1. <launch>  
  2.   
  3.   <arg name="model" default="$(find urdf_tutorial)/urdf/r2d2.xacro"/>  
  4.   <arg name="rvizconfig" default="$(find urdf_tutorial)/urdf.rviz" />  
  5.   
  6.   <include file="$(find urdf_tutorial)/launch/gazebo.launch">  
  7.     <arg name="model" value="$(arg model)" />  
  8.   </include>  
  9.   
  10.   <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" />  
  11.   
  12.   <!-- This param file is where any environment-agnostic (live or simulation)  
  13.   configuration should be loaded, including controllers -->  
  14.   <rosparam command="load" file="$(find urdf_tutorial)/config/control.yaml" />  
  15.   
  16.   <!-- This node loads the two controllers into a controller manager (real or simulated). The  
  17.   controllers are defined in config/control.yaml -->  
  18.   <node name="r2d2_controller_spawner" pkg="controller_manager" type="spawner"  
  19.     args="r2d2_joint_state_controller  
  20.           r2d2_diff_drive_controller  
  21.           r2d2_head_controller  
  22.           r2d2_gripper_controller  
  23.           --shutdown-timeout 3"/>  
  24.   
  25.   <node name="rqt_robot_steering" pkg="rqt_robot_steering" type="rqt_robot_steering">  
  26.   
  27.     <param name="default_topic" value="/r2d2_diff_drive_controller/cmd_vel"/>  
  28.   </node>  
  29.   
  30. </launch>  


r2d2.xacro

  1. <?xml version="1.0"?>  
  2. <robot name="r2d2" xmlns:xacro="http://ros.org/wiki/xacro">  
  3.   
  4.   <xacro:property name="width" value=".2" />  
  5.   <xacro:property name="leglen" value=".6" />  
  6.   <xacro:property name="polelen" value=".2" />  
  7.   <xacro:property name="bodylen" value=".6" />  
  8.   <xacro:property name="baselen" value=".4" />  
  9.   <xacro:property name="wheeldiam" value=".07" />  
  10.   <xacro:property name="pi" value="3.1415" />  
  11.   
  12.   <material name="red">  
  13.     <color rgba="0.8 0 0 1"/>  
  14.   </material>    
  15.   <material name="green">  
  16.     <color rgba="0 0.8 0 1"/>  
  17.   </material>  
  18.   <material name="blue">  
  19.     <color rgba="0 0 0.8 1"/>  
  20.   </material>  
  21.   <material name="black">  
  22.     <color rgba="0 0 0 1"/>  
  23.   </material>  
  24.   <material name="white">  
  25.     <color rgba="1 1 1 1"/>  
  26.   </material>  
  27.   
  28.   <xacro:macro name="default_inertial" params="mass">  
  29.     <inertial>  
  30.       <mass value="${mass}" />  
  31.       <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />  
  32.     </inertial>  
  33.   </xacro:macro>  
  34.   
  35.   <link name="base_link">  
  36.     <visual>  
  37.       <geometry>  
  38.         <cylinder radius="${width}" length="${bodylen}"/>  
  39.       </geometry>  
  40.       <material name="red"/>  
  41.     </visual>  
  42.     <collision>  
  43.       <geometry>  
  44.         <cylinder radius="${width}" length="${bodylen}"/>  
  45.       </geometry>  
  46.     </collision>  
  47.     <xacro:default_inertial mass="10"/>  
  48.   </link>  
  49.     <!-- This block provides the simulator (Gazebo) with information on a few additional  
  50.     physical properties. See http://gazebosim.org/tutorials/?tut=ros_urdf for more-->  
  51.     <gazebo reference="base_link">  
  52.       <material>Gazebo/Red</material>  
  53.     </gazebo>  
  54.   
  55.   <xacro:macro name="wheel" params="prefix suffix reflect">  
  56.   
  57.     <link name="${prefix}_${suffix}_wheel">  
  58.       <visual>  
  59.         <origin xyz="0 0 0" rpy="${pi/2} 0 0" />  
  60.         <geometry>  
  61.           <cylinder radius="${wheeldiam/2}" length="0.1"/>  
  62.         </geometry>  
  63.         <material name="black"/>  
  64.         <origin xyz="0 0 0" rpy="0 0 0" />  
  65.       </visual>  
  66.       <collision>  
  67.         <origin xyz="0 0 0" rpy="${pi/2} 0 0" />  
  68.         <geometry>  
  69.           <cylinder radius="${wheeldiam/2}" length="0.1"/>  
  70.         </geometry>  
  71.         <origin xyz="0 0 0" rpy="0 0 0" />  
  72.       </collision>  
  73.       <xacro:default_inertial mass="1"/>  
  74.     </link>  
  75.     <joint name="${prefix}_${suffix}_wheel_joint" type="continuous">  
  76.       <axis xyz="0 1 0" rpy="0 0 0" />  
  77.       <parent link="${prefix}_base"/>  
  78.       <child link="${prefix}_${suffix}_wheel"/>  
  79.       <origin xyz="${baselen*reflect/3} 0 -${wheeldiam/2+.05}" rpy="0 0 0"/>  
  80.     </joint>  
  81.   
  82.     <!-- This block provides the simulator (Gazebo) with information on a few additional  
  83.     physical properties. See http://gazebosim.org/tutorials/?tut=ros_urdf for more-->  
  84.     <gazebo reference="${prefix}_${suffix}_wheel">  
  85.       <mu1 value="200.0"/>  
  86.       <mu2 value="100.0"/>  
  87.       <kp value="10000000.0" />  
  88.       <kd value="1.0" />  
  89.       <material>Gazebo/Black</material>  
  90.     </gazebo>  
  91.   
  92.     <!-- This block connects the wheel joint to an actuator (motor), which informs both  
  93.     simulation and visualization of the robot -->  
  94.     <transmission name="${prefix}_${suffix}_wheel_trans" type="SimpleTransmission">  
  95.       <type>transmission_interface/SimpleTransmission</type>  
  96.       <actuator name="${prefix}_${suffix}_wheel_motor">  
  97.         <mechanicalReduction>1</mechanicalReduction>  
  98.       </actuator>  
  99.       <joint name="${prefix}_${suffix}_wheel_joint">  
  100.         <hardwareInterface>VelocityJointInterface</hardwareInterface>  
  101.       </joint>  
  102.     </transmission>  
  103.   
  104.   </xacro:macro>  
  105.   
  106.   <xacro:macro name="leg" params="prefix reflect">  
  107.     <link name="${prefix}_leg">  
  108.       <visual>  
  109.         <geometry>  
  110.           <box size="${leglen} .1 .2"/>  
  111.         </geometry>  
  112.         <origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>  
  113.         <material name="blue"/>  
  114.       </visual>  
  115.       <collision>  
  116.         <geometry>  
  117.           <box size="${leglen} .1 .2"/>  
  118.         </geometry>  
  119.         <origin xyz="0 0 -${leglen/2}" rpy="0 ${pi/2} 0"/>  
  120.       </collision>  
  121.       <xacro:default_inertial mass="10"/>  
  122.     </link>  
  123.     <!-- This block provides the simulator (Gazebo) with information on a few additional  
  124.     physical properties. See http://gazebosim.org/tutorials/?tut=ros_urdf for more-->  
  125.     <gazebo reference="${prefix}_leg">  
  126.       <material>Gazebo/Blue</material>  
  127.     </gazebo>  
  128.   
  129.     <joint name="base_to_${prefix}_leg" type="fixed">  
  130.       <parent link="base_link"/>  
  131.       <child link="${prefix}_leg"/>  
  132.       <origin xyz="0 ${reflect*(width+.02)} .25" />  
  133.     </joint>  
  134.   
  135.     <link name="${prefix}_base">  
  136.       <visual>  
  137.         <geometry>  
  138.           <box size="${baselen} .1 .1"/>  
  139.         </geometry>  
  140.         <material name="white"/>  
  141.       </visual>  
  142.       <collision>  
  143.         <geometry>  
  144.           <box size="${baselen} .1 .1"/>  
  145.         </geometry>  
  146.       </collision>  
  147.       <xacro:default_inertial mass="10"/>  
  148.     </link>  
  149.   
  150.     <joint name="${prefix}_base_joint" type="fixed">  
  151.       <parent link="${prefix}_leg"/>  
  152.       <child link="${prefix}_base"/>  
  153.       <origin xyz="0 0 ${-leglen}" />  
  154.     </joint>  
  155.     <xacro:wheel prefix="${prefix}" suffix="front" reflect="1"/>  
  156.     <xacro:wheel prefix="${prefix}" suffix="back" reflect="-1"/>  
  157.   </xacro:macro>  
  158.   <xacro:leg prefix="right" reflect="-1" />  
  159.   <xacro:leg prefix="left" reflect="1" />  
  160.   
  161.   <joint name="gripper_extension" type="prismatic">  
  162.     <parent link="base_link"/>  
  163.     <child link="gripper_pole"/>  
  164.     <limit effort="1000.0" lower="-${width*2-.02}" upper="0" velocity="0.5"/>  
  165.     <origin rpy="0 0 0" xyz="${width-.01} 0 .2"/>  
  166.     <limit effort="30" velocity="0.2"/>  
  167.     <dynamics damping="0.0" friction="0.0"/>  
  168.   </joint>  
  169.   
  170.   <link name="gripper_pole">  
  171.     <visual>  
  172.       <geometry>  
  173.         <cylinder length="${polelen}" radius=".01"/>  
  174.       </geometry>  
  175.       <origin xyz="${polelen/2} 0 0" rpy="0 ${pi/2} 0 "/>  
  176.     </visual>  
  177.     <collision>  
  178.       <geometry>  
  179.         <cylinder length="${polelen}" radius=".01"/>  
  180.       </geometry>  
  181.       <origin xyz="${polelen/2} 0 0" rpy="0 ${pi/2} 0 "/>  
  182.     </collision>  
  183.     <xacro:default_inertial mass=".05"/>  
  184.   </link>  
  185.   
  186.   <transmission name="gripper_extension_trans" type="SimpleTransmission">  
  187.     <type>transmission_interface/SimpleTransmission</type>  
  188.     <actuator name="gripper_extension_motor">  
  189.       <mechanicalReduction>1</mechanicalReduction>  
  190.     </actuator>  
  191.     <joint name="gripper_extension">  
  192.       <hardwareInterface>PositionJointInterface</hardwareInterface>  
  193.     </joint>  
  194.   </transmission>  
  195.   
  196.   <xacro:macro name="gripper" params="prefix reflect">  
  197.     <joint name="${prefix}_gripper_joint" type="revolute">  
  198.       <axis xyz="0 0 ${reflect}"/>  
  199.       <limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>  
  200.       <origin rpy="0 0 0" xyz="${polelen} ${reflect*0.01} 0"/>  
  201.       <parent link="gripper_pole"/>  
  202.       <child link="${prefix}_gripper"/>  
  203.       <limit effort="30" velocity="1.0"/>  
  204.       <dynamics damping="0.0" friction="0.0"/>  
  205.     </joint>  
  206.     <link name="${prefix}_gripper">  
  207.       <visual>  
  208.         <origin rpy="${(reflect-1)/2*pi} 0 0" xyz="0 0 0"/>  
  209.         <geometry>  
  210.           <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger.dae"/>  
  211.         </geometry>  
  212.       </visual>  
  213.       <collision>  
  214.         <geometry>  
  215.           <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger.dae"/>  
  216.         </geometry>  
  217.         <origin rpy="${(reflect-1)/2*pi} 0 0" xyz="0 0 0"/>  
  218.       </collision>  
  219.       <xacro:default_inertial mass=".05"/>  
  220.     </link>  
  221.     <transmission name="${prefix}_gripper_trans" type="SimpleTransmission">  
  222.       <type>transmission_interface/SimpleTransmission</type>  
  223.       <actuator name="${prefix}_gripper_motor">  
  224.         <mechanicalReduction>1</mechanicalReduction>  
  225.       </actuator>  
  226.       <joint name="${prefix}_gripper_joint">  
  227.         <hardwareInterface>PositionJointInterface</hardwareInterface>  
  228.       </joint>  
  229.     </transmission>  
  230.   
  231.     <joint name="${prefix}_tip_joint" type="fixed">  
  232.       <parent link="${prefix}_gripper"/>  
  233.       <child link="${prefix}_tip"/>  
  234.     </joint>  
  235.     <link name="${prefix}_tip">  
  236.       <visual>  
  237.         <origin rpy="${(reflect-1)/2*pi} 0 0" xyz="0.09137 0.00495 0"/>  
  238.         <geometry>  
  239.           <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger_tip.dae"/>  
  240.         </geometry>  
  241.       </visual>  
  242.       <collision>  
  243.         <geometry>  
  244.           <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger_tip.dae"/>  
  245.         </geometry>  
  246.         <origin rpy="${(reflect-1)/2*pi} 0 0" xyz="0.09137 0.00495 0"/>  
  247.       </collision>  
  248.       <xacro:default_inertial mass=".05"/>  
  249.     </link>  
  250.   </xacro:macro>  
  251.   
  252.   <xacro:gripper prefix="left" reflect="1" />  
  253.   <xacro:gripper prefix="right" reflect="-1" />  
  254.   
  255.   <link name="head">  
  256.     <visual>  
  257.       <geometry>  
  258.         <sphere radius="${width}"/>  
  259.       </geometry>  
  260.       <material name="green"/>  
  261.     </visual>  
  262.     <collision>  
  263.       <geometry>  
  264.         <sphere radius="${width}"/>  
  265.       </geometry>  
  266.     </collision>  
  267.     <xacro:default_inertial mass="2"/>  
  268.   </link>  
  269.   
  270.   <joint name="head_swivel" type="continuous">  
  271.     <parent link="base_link"/>  
  272.     <child link="head"/>  
  273.     <axis xyz="0 0 1"/>  
  274.     <origin xyz="0 0 ${bodylen/2}"/>  
  275.     <limit effort="30" velocity="1.0"/>  
  276.     <dynamics damping="0.0" friction="0.0"/>  
  277.   </joint>  
  278.     <!-- This block provides the simulator (Gazebo) with information on a few additional  
  279.     physical properties. See http://gazebosim.org/tutorials/?tut=ros_urdf for more-->  
  280.     <gazebo reference="head">  
  281.       <material>Gazebo/Orange</material>  
  282.     </gazebo>  
  283.   <!-- This block connects the head_swivel joint to an actuator (motor), which informs both  
  284.   simulation and visualization of the robot -->  
  285.   <transmission name="head_swivel_trans" type="SimpleTransmission">  
  286.     <type>transmission_interface/SimpleTransmission</type>  
  287.     <actuator name="$head_swivel_motor">  
  288.       <mechanicalReduction>1</mechanicalReduction>  
  289.     </actuator>  
  290.     <joint name="head_swivel">  
  291.       <hardwareInterface>PositionJointInterface</hardwareInterface>  
  292.     </joint>  
  293.   </transmission>  
  294.   
  295.   <link name="box">  
  296.     <visual>  
  297.       <geometry>  
  298.         <box size=".08 .08 .08"/>  
  299.       </geometry>  
  300.       <material name="blue"/>  
  301.       <origin xyz="-0.04 0 0"/>  
  302.     </visual>  
  303.     <collision>  
  304.       <geometry>  
  305.         <box size=".08 .08 .08"/>  
  306.       </geometry>  
  307.     </collision>  
  308.     <xacro:default_inertial mass="1"/>  
  309.   </link>  
  310.   
  311.   <joint name="tobox" type="fixed">  
  312.     <parent link="head"/>  
  313.     <child link="box"/>  
  314.     <origin xyz="${.707*width+0.04} 0 ${.707*width}"/>  
  315.   </joint>  
  316.   
  317.   <!-- Gazebo plugin for ROS Control -->  
  318.   <gazebo>  
  319.     <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">  
  320.       <robotNamespace>/</robotNamespace>  
  321.     </plugin>  
  322.   </gazebo>  
  323.   
  324. </robot>  


补充链接与资料:

1urdf http://wiki.ros.org/urdf

2xacro http://wiki.ros.org/xacro

----

End

----