URDF(Unified Robot Description Format)统一机器人描述格式:是一种基于XML规范、用于机器人结构描述的格式。这一格式的目的在于提供一种尽可能通用(as general as possible)的机器人描述规范。
建立机器人模型必须了解几何建模坐标,这里坐标系遵循右手法则(食指X(向左)【红色】,中指Y(垂直纸面向外)【绿色】,拇指Z(向上)【蓝色】)。
建立的几何模型的坐标系原点放在模型质心。建立某个部件时<origin xyz="x y z" rpy="r p y"> 将坐标系相对质心坐标系进行移动和旋转相应值。(旋转同样遵循右手定则,加入要求沿 Y 轴旋转,则右手大拇指指向 Y 轴正方向,四指弯曲方向即为旋转方向)。
使用关节参数 joint 连接 link 时,<origin > 表示子 link 坐标系相对于父 link 坐标系的坐标位置变换。
关节类型表:
关节类型 | 描述 |
continuous | 旋转关节,可以围绕单轴无限旋转(如车轮) |
revolute | 旋转关节,类似continuous,但是有旋转的角度极限 |
prismatic | 滑动关节,沿某一轴线移动的关节,带有位置极限 |
planar | 平面关节,允许在平面正交方向上平移或者旋转 |
floating | 浮动关节,允许进行平移、旋转 |
fixed | 固定关节,不允许运动的特殊关节 |
<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Defining the colors used in this robot -->
<!-- material 用于定义颜色,纹理 -->
<material name="Red">
<color rgba="1 0 0 1"/>
</material>
<!-- Constants -->
<!-- 宏定义,定义 M_PI 的值为 3.14159;后边调用 ${M_PI} 表示值3.14159 -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- Inertial matrix 的宏定义,后边以 xacro:${name} 形式进行调用,mass 参数用于设置不同质量,例:<xcaro:inertial_matrix mass="100" /> -->
<xacro:macro name="inertial_matrix" params="mass"
<inertial>
<mass value="${mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="1.0" />
</inertial>
</xacro:macro>
<!-- /// bottom_joint // -->
<!-- 定义关节,name:关节名称,type:关节移动类型(其他类型参考文首表格) -->
<joint name="bottom_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" /> 关节位置相对于父连杆坐标系的位置(关节与子连杆重合)
<parent link="base_link"/> 父连杆
<child link="bottom_link"/> 子连杆
</joint>
<link name="bottom_link">
<visual>
<origin xyz=" 0 0 -0.02" rpy="0 0 0"/>
<geometry>
<box size="1 1 0.02" />
</geometry>
<material name="Brown" />
</visual>
<collision>
<origin xyz=" 0 0 -0.02" rpy="0 0 0"/>
<geometry>
<box size="1 1 0.02" />
</geometry>
</collision>
<xacro:inertial_matrix mass="500"/>
</link>
<!-- / BASE LINK // -->
<!-- 定义基本连杆,连杆名称 base_link -->
<link name="base_link">
<visual> 可视化属性,即连杆呈现的形状颜色等
<origin xyz="0 0 0" rpy="0 0 0" /> 坐标系相对于质心原点坐标,角度
<geometry> 几何形状
<box size="0.1 0.1 0.04" />
</geometry>
<material name="White" /> 颜色属性
</visual>
<collision> 碰撞属性
<origin xyz="0 0 0" rpy="0 0 0" /> 碰撞坐标系原点位置,旋转
<geometry> 碰撞几何形状
<box size="0.1 0.1 0.04" />
</geometry>
</collision>
<xacro:inertial_matrix mass="1"/> 惯性宏定义的例化
</link>
<!-- / 设置在 Gazebo 中颜色 // -->
<gazebo reference="bottom_link">
<material>Gazebo/White</material>
</gazebo>
<!-- Transmissions for ROS Control -->
<!-- 定义传动 -->
<xacro:macro name="transmission_block" params="joint_name">
<transmission name="tran1">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<!-- 为所有关节添加传动 -->
<xacro:transmission_block joint_name="joint1"/>
<xacro:transmission_block joint_name="joint2"/>
<xacro:transmission_block joint_name="joint3"/>
<xacro:transmission_block joint_name="joint4"/>
<xacro:transmission_block joint_name="joint5"/>
<xacro:transmission_block joint_name="joint6"/>
<xacro:transmission_block joint_name="finger_joint1"/>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/arm</robotNamespace>
</plugin>
</gazebo>
</robot>