最近需要使用URDF来搭建一个四轮差速小车,搭载双目相机和IMU,这里记录一下过程。
相关链接:
urdf标签格式:https://wiki.ros.org/urdf/XML
一些urdf的机器人例子:http://wiki.ros.org/urdf/Examples
urdf的使用教程:http://wiki.ros.org/urdf/Tutorials
xacro使用说明:https://wiki.ros.org/xacro
urdf的gazebo搭建例子:http://gazebosim.org/tutorials/?tut=ros_urdf
gazebo插件说明:http://gazebosim.org/tutorials?tut=ros_gzplugins
gazebo加载机器人:http://gazebosim.org/tutorials?tut=ros_roslaunch&cat=connect_ros


robot标签

这个被仍为是一个机器人所有标签的根标签,它包含其它的标签。
它有一个属性,name,这个属性我们可以随意设置为自己想要的命名。
还有一个值得注意的是:

也就是说如果我们需要使用xacro时我们需要加上

xmlns:xacro="http://www.ros.org/wiki/xacro"

综上,我的Header of a URDF File如下:


xacro使用

在我看来,它是一个用来命名和封装的工具,这可以减少许多重复的工作。
With xacro, you can construct shorter and more readable XML files by using macros that expand to larger XML expressions.


属性定义
定义方法为

<xacro:property name="my_name" value="0.05" ></xacro:property>

调用的时候将其写为${my_name},比如

<origin rpy="0 0 ${my_name}" xyz="0 0 0"/>

给Blocks命名
定义方法为

<xacro:property name="my_origin">
  <origin xyz="0.3 0 0" rpy="0 0 0" />
</xacro:property>

调用方法为

<xacro:insert_block name="front_left_origin" />

宏定义
类似于函数封装。
定义方法为

<xacro:macro name="default_inertial" params="mass">
  <inertial>
    <mass value="${mass}" />
    <inertia ixx="0.1" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1" />
  </inertial>
</xacro:macro>

params可以包含多个参数,用空格隔开就行。也可以设置默认值,加上:=即可。
调用方法为

<xacro:default_inertial mass="0.0001"/>

还有一些其它功能,可以按照wiki尝试我不一一说
(图片来自 https://www.askeynil.com/2019/3f08735f.html


link标签

The link element describes a rigid body with an inertia, visual features, and collision properties.
描述具有惯性、视觉特征和碰撞属性的刚体。
这里有张图
(图片来自 http://wiki.ros.org/urdf/XML/link
这里我需要一个车体、一个imu、一个camera、四个轮子,7个link标签。
然后,针对这几个刚体设置对应的标签和属性。
按照示例,其写法类似为:

 <link name="my_link">
   <inertial>
     <origin xyz="0 0 0.5" rpy="0 0 0"/>
     <mass value="1"/>
     <inertia ixx="100"  ixy="0"  ixz="0" iyy="100" iyz="0" izz="100" />
   </inertial>

   <visual>
     <origin xyz="0 0 0" rpy="0 0 0" />
     <geometry>
       <box size="1 1 1" />
     </geometry>
     <material name="Cyan">
       <color rgba="0 1.0 1.0 1.0"/>
     </material>
   </visual>

   <collision>
     <origin xyz="0 0 0" rpy="0 0 0"/>
     <geometry>
       <cylinder radius="1" length="0.5"/>
     </geometry>
   </collision>
 </link>

inertial标签是惯性相关参数设置
origin是惯性坐标系相对于这个link坐标系的位姿,也就是上面那个图的蓝色的箭头坐标系的位姿设置。最好设置为物体的重心(均匀材质就是其几何中心),关于这个重心,我们可以在gazebo界面clicking on the ‘’View’’ menu of Gazebo and selecting both ‘’Wireframe’’ and ‘’Center of Mass’’.就可以查看到重心的位置。一般设置为0,默认重心就在几何中心。

mass代表质量,For links to not be ignored in Gazebo, their mass must be greater than zero.。
inertia表示 3x3 转动惯量矩阵。我对这个没什么研究,只是平时都将ixx、iyy、izz设置为0.1或者0.001,如果仿真模型加载到gazebo里后原地乱飞就得想想这个是不是设置太小了。
Additionally, links with zero principal moment of inertia (ixx, iyy, izz) could lead to infinite acceleration under any finite torque application.。


visual是视觉与几何相关参数设置
origin代表几何元素的坐标系相对于这个link坐标系的位姿,也就是上面那个图的黑色的几个箭头表示的。最好设置为0。

geometry代表几何形状,有几个可选标签为box(立方体)、cylinder(圆柱)、sphere(球体)、mesh(自定义文件)。除了轮子设置为cylinder其它的link都为box。
material代表外观材料,有几个可选标签为color(颜色设置)、texture(从文件加载)。有一个属性name,使用这个name的好处是我之前设置了一个name属性,在其它地方可以直接使用这个name属性而不用重新设置其它标签。


collision是碰撞相关参数设置
origin代表碰撞元素的坐标系相对于这个link坐标系的位姿,也就是上面那个图的红色的箭头坐标系的位姿设置。这个设置的与visual一样就可。
geometry代表几何形状,也与visual一样就可。

然后创建了一个link后在进入gazebo界面时会出现警告

[ WARN] [1642234998.949279729]: The root link base_link has an inertia specified in the URDF, but KDL does not support a root link with an inertia.  As a workaround, you can add an extra dummy link to your URDF.

见链接 https://answers.ros.org/question/192817/error-msg-the-root-link_base-has-an-inertia-specified-in-the-urdf-but-kdl/
也就是我还需要创建一个没有mass和inertia属性(没有inertial标签)的link作为root link。

强烈建议link里所有的origin标签设置为0(或者不设置,默认为0)!
强烈建议link里所有的origin标签设置为0(或者不设置,默认为0)!
强烈建议link里所有的origin标签设置为0(或者不设置,默认为0)!


joint标签

它是链接link的关节。
The joint element describes the kinematics and dynamics of the joint and also specifies the safety limits of the joint.
(图片来自 http://wiki.ros.org/urdf/XML/joint
按照示例,其写法类似为:

 <joint name="my_joint" type="floating">
    <origin xyz="0 0 1" rpy="0 0 3.1416"/>
    <parent link="link1"/>
    <child link="link2"/>

    <calibration rising="0.0"/>
    <dynamics damping="0.0" friction="0.0"/>
    <limit effort="30" velocity="1.0" lower="-2.2" upper="0.7" />
    <safety_controller k_velocity="10" k_position="15" soft_lower_limit="-2.0" soft_upper_limit="0.5" />
 </joint>

name与type属性
name是这个关节的名称。
type可设置为revolute、continuous、prismatic、fixed、floating、planar

  • revolute、continuous为旋转关节,不同的是revolute有限位。
  • prismatic为滑动关节。
  • fixed为固定关节,关节不可运动。
  • floating为六自由度关节。
  • planar为平面关节。

在我想搭建的车上,轮子与车身是continuous关节,其它为fixed关节。


origin标签
它代表从父link到joint之间的一个转换,如上图的紫色箭头。而图上又表示child frame = joint frame。所以这里可以理解为这一个转换是父link到子link之间的一个TF关系。


parent与child标签
对应父link与子link的name。


axis关节轴
设置关节轴的方向,xyz为一个正交向量。对revolute、continuous旋转关节为旋转轴,对prismatic滑动关节为平移轴,对planar平面关节为平面的法线。这个轴向是相对于两个link的接触面的。


其它
还有标签dynamics、calibration、mimic、safety_controller都是可选的,我没用过,limit只在revolute和prismatic类上有用,限制范围和位置的。


gazebo标签

虽然 URDF 在 ROS 中是一种有用且标准化的格式,但它们缺乏许多功能,并且尚未更新以应对机器人技术不断发展的需求。 针对link与joint在gazebo里显示和使用的情况,gazebo提供了对应的标签来优化在gazebo环境下的仿真。


我只修改了对应的颜色和轮子的摩擦系数。

<gazebo reference="body_link">
    <material>Gazebo/Orange</material>
</gazebo>

<gazebo reference="wheel_1">
    <material>Gazebo/Red</material>
    <mu1>0.5</mu1>
    <mu2>0.5</mu2>
</gazebo>

添加插件Gazebo plugins

插件使机器人真正动起来/实现某种功能。
Gazebo plugins give your URDF models greater functionality and can tie in ROS messages and service calls for sensor output and motor input.


四轮差速,滑移转向驱动插件
如果车子一启动就翻,检查一下torque这个参数。


双目摄像头插件
左右摄像头的pose是相对于cameralink的,要仔细设置,确定好位置方向。


IMU插件


最终文件

<?xml version="1.0"?>

<robot name="robot" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!--          1、一些值的定义          -->
    <xacro:property name="PI" value="3.1415926"/>
    <xacro:property name="length_wheel" value="0.05" />
    <xacro:property name="radius_wheel" value="0.06" />
    <xacro:property name="body_x" value="0.2" />
    <xacro:property name="body_y" value="0.3" />
    <xacro:property name="body_z" value="0.1" />

    <xacro:macro name="set_inertial" params="mass:=1">
        <inertial>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <mass value="${mass}"/>
            <inertia ixx="0.1"  ixy="0"  ixz="0" iyy="0.1" iyz="0" izz="0.1" />
        </inertial>
    </xacro:macro>

    <xacro:macro name="cylinder_visual_collision" params="length:=${length_wheel} radius:=${radius_wheel}">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder length="${length}" radius="${radius}"/>
            </geometry>
            <material name="black"/>
        </visual>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <cylinder length="${length}" radius="${radius}"/>
            </geometry>
        </collision>
    </xacro:macro>


    <!--          2、link配置          -->
    <link name="body_link">
        <xacro:cylinder_visual_collision length="0" radius="0"/>
    </link>

    <link name="base_link">  
        <visual>
            <origin xyz="0 0 0.05" rpy="0 0 0" />
            <geometry>
            <box size="${body_x} ${body_y} ${body_z}" />
            </geometry>
            <material name="black">
                <color rgba="0 0 0 1"/>
            </material>
        </visual>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <box size="0.2 0.3 0.1" />
            </geometry>
        </collision>

        <xacro:set_inertial mass="1"/>
    </link>

    <link name="wheel_1">
        <xacro:cylinder_visual_collision />
        <xacro:set_inertial mass="0.5"/>
    </link>

    <link name="wheel_2">
        <xacro:cylinder_visual_collision />
        <xacro:set_inertial mass="0.5"/>
    </link>

    <link name="wheel_3">
        <xacro:cylinder_visual_collision />
        <xacro:set_inertial mass="0.5"/>
    </link>

    <link name="wheel_4">
        <xacro:cylinder_visual_collision />
        <xacro:set_inertial mass="0.5"/>
    </link>

    <link name="camera_link">
        <xacro:cylinder_visual_collision length="0.05" radius="0.05"/>
        <xacro:set_inertial mass="0.25"/>
    </link>

    <link name="imu_link">
        <xacro:cylinder_visual_collision length="0.01" radius="0.01"/>
        <xacro:set_inertial mass="0.05"/>
    </link>


    <!--          3、joint连接          -->
    <joint name="base_body_joint" type="fixed">
        <origin  xyz="0 0 0" rpy="0 0 0" />
        <parent link="body_link" />
        <child link="base_link" />
    </joint>

    <joint name="wheel_1_joint" type="continuous">
        <origin  xyz="-${body_x/2} ${body_y/2} 0" rpy="0 -${PI/2} 0" />
        <axis xyz="0 0 1" />
        <parent link="base_link" />
        <child link="wheel_1" />
    </joint>

    <joint name="wheel_2_joint" type="continuous">
        <origin  xyz="${body_x/2} ${body_y/2} 0" rpy="0 -${PI/2} 0" />
        <axis xyz="0 0 1" />
        <parent link="base_link" />
        <child link="wheel_2" />
    </joint>

    <joint name="wheel_3_joint" type="continuous">
        <origin  xyz="-${body_x/2} -${body_y/2} 0" rpy="0 -${PI/2} 0" />
        <axis xyz="0 0 1" />
        <parent link="base_link" />
        <child link="wheel_3" />
    </joint>

    <joint name="wheel_4_joint" type="continuous">
        <origin  xyz="${body_x/2} -${body_y/2} 0" rpy="0 -${PI/2} 0" />
        <axis xyz="0 0 1" />
        <parent link="base_link" />
        <child link="wheel_4" />
    </joint>

    <joint name="camera_joint" type="fixed">
        <origin  xyz="0 ${body_y/2 - 0.05} ${0.025 + 0.1}" rpy="0 0 0" />
        <parent link="base_link" />
        <child link="camera_link" />
    </joint>

    <joint name="imu_joint" type="fixed">
        <origin  xyz="0 0 ${0.01 + radius_wheel}" rpy="0 0 0" />
        <parent link="base_link" />
        <child link="imu_link" />
    </joint>


    <!--          4、gazebo标签设置          -->
    <gazebo reference="base_link">
        <material>Gazebo/Orange</material>
    </gazebo>

    <gazebo reference="wheel_1">
        <material>Gazebo/Red</material>
        <mu1>0.5</mu1>
        <mu2>0.5</mu2>
    </gazebo>

    <gazebo reference="wheel_2">
        <material>Gazebo/Black</material>
        <mu1>0.5</mu1>
        <mu2>0.5</mu2>
    </gazebo>

    <gazebo reference="wheel_3">
        <material>Gazebo/White</material>
        <mu1>0.5</mu1>
        <mu2>0.5</mu2>
    </gazebo>

    <gazebo reference="wheel_4">
        <material>Gazebo/Orange</material>
        <mu1>0.5</mu1>
        <mu2>0.5</mu2>
    </gazebo>

    <gazebo reference="camera_link">
        <material>Gazebo/Black</material>
    </gazebo>


    <!--          5、gazebo插件设置          -->
    <gazebo>
        <plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
          <updateRate>100.0</updateRate>
          <robotNamespace>/</robotNamespace>
          <leftFrontJoint>wheel_1_joint</leftFrontJoint>
          <rightFrontJoint>wheel_2_joint</rightFrontJoint>
          <leftRearJoint>wheel_3_joint</leftRearJoint>
          <rightRearJoint>wheel_4_joint</rightRearJoint>
          <wheelSeparation>${body_y}</wheelSeparation>
          <wheelDiameter>${radius_wheel*2}</wheelDiameter>
          <torque>0.5</torque>
          <commandTopic>cmd_vel</commandTopic>
          <odometryTopic>odom</odometryTopic>
          <odometryFrame>odom</odometryFrame>
          <robotBaseFrame>base_link</robotBaseFrame>
          <broadcastTF>1</broadcastTF>
        </plugin>
    </gazebo>


    <gazebo reference="imu_link">
        <material>Gazebo/Orange</material>
        <gravity>true</gravity>
        <sensor name="imu_sensor" type="imu">
            <always_on>true</always_on>
            <update_rate>100</update_rate>
            <visualize>true</visualize>
            <topic>__default_topic__</topic>
            <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
                <topicName>imu</topicName>
                <bodyName>imu_link</bodyName>
                <updateRateHZ>100.0</updateRateHZ>
                <gaussianNoise>0.0</gaussianNoise>
                <xyzOffset>0 0 0</xyzOffset>
                <rpyOffset>0 0 0</rpyOffset>
                <frameName>imu_link</frameName>
            </plugin>
            <pose>0 0 0 0 0 0</pose>
        </sensor>
    </gazebo>

    <gazebo reference="camera_link">
    <sensor type="multicamera" name="stereo_camera">
      <update_rate>10.0</update_rate>
      <camera name="left">
        <pose>-0.03 0.025 0 0 0 ${PI/2}</pose>
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
          <width>400</width>
          <height>400</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <camera name="right">
        <pose>0.03 0.025 0 0 0 ${PI/2}</pose>
        <horizontal_fov>1.3962634</horizontal_fov>
        <image>
          <width>400</width>
          <height>400</height>
          <format>R8G8B8</format>
        </image>
        <clip>
          <near>0.02</near>
          <far>300</far>
        </clip>
        <noise>
          <type>gaussian</type>
          <mean>0.0</mean>
          <stddev>0.007</stddev>
        </noise>
      </camera>
      <plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
        <alwaysOn>true</alwaysOn>
        <updateRate>0.0</updateRate>
        <cameraName>stereo</cameraName>
        <imageTopicName>image_raw</imageTopicName>
        <cameraInfoTopicName>camera_info</cameraInfoTopicName>
        <frameName>camera_link</frameName>
        <hackBaseline>0.07</hackBaseline>
        <distortionK1>0.0</distortionK1>
        <distortionK2>0.0</distortionK2>
        <distortionK3>0.0</distortionK3>
        <distortionT1>0.0</distortionT1>
        <distortionT2>0.0</distortionT2>
      </plugin>
    </sensor>
  </gazebo>
</robot>