入门 · 2周
项目七:URDF/Xacro机器人建模实践
学习用URDF和Xacro精确描述机器人结构——将SolidWorks建模经验转化为机器人描述语言,含参数化建模和RViz可视化。
学习用URDF和Xacro精确描述机器人结构——将SolidWorks建模经验转化为机器人描述语言,含参数化建模和RViz可视化。
你在SolidWorks里设计过装配体——定义零件几何、质量属性、装配约束。URDF就是机器人世界的"装配体文件格式":link就是零件,joint就是装配约束。这个项目让你用代码而非GUI来定义机器人结构,这是所有机器人仿真和控制的基础。
| URDF概念 | SolidWorks等价 | 机器人意义 |
|---|---|---|
<link> | 零件(.sldprt) | 刚体:质量、惯性、几何 |
<joint> | 配合(Mate) | 运动约束:转动/移动/固定 |
<visual> | 外观(Appearance) | 渲染用几何(可简化) |
<collision> | 干涉检查几何 | 碰撞检测用(比visual更简) |
<inertial> | 质量属性(Mass Props) | 物理仿真必需 |
<origin> | 配合参考(Reference) | 刚体变换:xyz+rpy |
urdf_practice/
├── urdf/
│ ├── 2dof_arm.urdf # 2轴臂(入门,手动写URDF)
│ ├── 3dof_scara.urdf.xacro # SCARA构型(中级,Xacro参数化)
│ └── 6dof_arm.urdf.xacro # 6轴臂(完整,宏定义+传感器)
├── launch/
│ ├── display_2dof.launch.py # RViz可视化启动
│ ├── display_scara.launch.py
│ └── display_6dof.launch.py
├── meshes/
│ ├── base_link.stl # 自定义网格
│ ├── link1.stl
│ └── link2.stl
├── config/
│ └── ros2_control.yaml # 控制器配置
├── rviz/
│ └── arm_display.rviz # RViz视角配置
└── README.md # 项目说明+截图
# 安装ROS 2 Humble (Ubuntu 22.04)
sudo apt install ros-humble-robot-state-publisher \
ros-humble-joint-state-publisher-gui \
ros-humble-rviz2 \
ros-humble-xacro
# 创建工作空间
mkdir -p ~/urdf_ws/src/urdf_practice
cd ~/urdf_ws/src/urdf_practice
mkdir -p urdf launch meshes config rviz
# 验证Xacro安装
ros2 run xacro xacro --version
<?xml version="1.0"?>
<robot name="2dof_arm">
<!-- ========== 基座 Link ========== -->
<link name="base_link">
<visual>
<geometry><cylinder radius="0.15" length="0.2"/></geometry>
<material name="gray"><color rgba="0.5 0.5 0.5 1"/></material>
</visual>
<collision>
<geometry><cylinder radius="0.15" length="0.2"/></geometry>
</collision>
<inertial>
<origin xyz="0 0 0.1" rpy="0 0 0"/>
<mass value="10.0"/>
<!-- 惯量矩阵:Ixx Ixy Ixz Iyy Iyz Izz -->
<inertia ixx="0.15" ixy="0" ixz="0" iyy="0.15" iyz="0" izz="0.1"/>
</inertial>
</link>
<!-- ========== 关节1:旋转 ========== -->
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<axis xyz="0 0 1"/> <!-- 绕Z轴旋转 -->
<limit lower="-2.7" upper="2.7" effort="50" velocity="3.14"/>
<dynamics damping="0.5" friction="0.1"/>
</joint>
<link name="link1">
<visual>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<geometry><box size="0.08 0.08 0.5"/></geometry>
<material name="blue"><color rgba="0.2 0.4 0.9 1"/></material>
</visual>
<collision>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<geometry><box size="0.08 0.08 0.5"/></geometry>
</collision>
<inertial>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<mass value="3.0"/>
<inertia ixx="0.07" ixy="0" ixz="0" iyy="0.07" iyz="0" izz="0.005"/>
</inertial>
</link>
<!-- ========== 关节2:旋转 ========== -->
<joint name="joint2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
<axis xyz="0 1 0"/> <!-- 绕Y轴旋转 -->
<limit lower="-2.0" upper="2.0" effort="30" velocity="3.14"/>
</joint>
<link name="link2">
<visual>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<geometry><box size="0.05 0.05 0.4"/></geometry>
<material name="red"><color rgba="0.9 0.2 0.2 1"/></material>
</visual>
<collision>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<geometry><box size="0.05 0.05 0.4"/></geometry>
</collision>
<inertial>
<origin xyz="0 0 0.2" rpy="0 0 0"/>
<mass value="1.5"/>
<inertia ixx="0.02" ixy="0" ixz="0" iyy="0.02" iyz="0" izz="0.001"/>
</inertial>
</link>
<!-- ========== 末端工具 ========== -->
<joint name="tool_joint" type="fixed">
<parent link="link2"/>
<child link="tool0"/>
<origin xyz="0 0 0.4" rpy="0 0 0"/>
</joint>
<link name="tool0">
<visual>
<geometry><sphere radius="0.03"/></geometry>
<material name="green"><color rgba="0 0.8 0 1"/></material>
</visual>
</link>
</robot>
直接写URDF的最大痛点:修改一个尺寸需要改多处。比如改连杆长度,你需要更新visual、collision、inertial中的origin、以及相邻joint的origin。Xacro用变量+宏+数学表达式解决这个问题——就像你在SolidWorks中定义了全局变量,改一个值就改整个模型。
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="scara_robot">
<!-- ====== 参数区:改这里=改整个机器人 ====== -->
<xacro:property name="base_radius" value="0.15"/>
<xacro:property name="base_height" value="0.20"/>
<xacro:property name="link1_length" value="0.30"/>
<xacro:property name="link2_length" value="0.25"/>
<xacro:property name="link_width" value="0.06"/>
<xacro:property name="link_height" value="0.04"/>
<xacro:property name="z_axis_stroke" value="0.15"/>
<xacro:property name="M_PI" value="3.141592653589793"/>
<!-- ====== 宏:可复用的Link模板 ====== -->
<xacro:macro name="box_link" params="name length width height mass color">
<link name="${name}">
<visual>
<origin xyz="${length/2} 0 0" rpy="0 0 0"/>
<geometry><box size="${length} ${width} ${height}"/></geometry>
<material name="${color}"><color rgba="${color}"/></material>
</visual>
<collision>
<origin xyz="${length/2} 0 0" rpy="0 0 0"/>
<geometry><box size="${length} ${width} ${height}"/></geometry>
</collision>
<inertial>
<mass value="${mass}"/>
<!-- 平行轴定理:I_about_end = I_cm + mass * (L/2)^2 -->
<inertia
ixx="${mass * (width*width + height*height) / 12}"
iyy="${mass * (length*length + height*height) / 12 + mass * (length/2)*(length/2)}"
izz="${mass * (length*length + width*width) / 12 + mass * (length/2)*(length/2)}"
ixy="0" ixz="0" iyz="0"/>
<origin xyz="${length/2} 0 0" rpy="0 0 0"/>
</inertial>
</link>
</xacro:macro>
<!-- ====== 使用宏:一条线定义一个Link ====== -->
<xacro:box_link name="link1" length="${link1_length}"
width="${link_width}" height="${link_height}" mass="3.0" color="0.2 0.4 0.9 1"/>
<xacro:box_link name="link2" length="${link2_length}"
width="${link_width}" height="${link_height}" mass="2.0" color="0.9 0.2 0.2 1"/>
<!-- ====== 关节定义 ====== -->
<joint name="joint1" type="revolute">
<parent link="base_link"/><child link="link1"/>
<origin xyz="0 0 ${base_height}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="${-150 * M_PI / 180}" upper="${150 * M_PI / 180}"
effort="30" velocity="3.14"/>
</joint>
<joint name="joint2" type="revolute">
<parent link="link1"/><child link="link2"/>
<origin xyz="${link1_length} 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit lower="${-150 * M_PI / 180}" upper="${150 * M_PI / 180}"
effort="20" velocity="3.14"/>
</joint>
<!-- 末端工具 -->
<joint name="tool_joint" type="fixed">
<parent link="link2"/><child link="tool0"/>
<origin xyz="${link2_length} 0 0" rpy="0 0 0"/>
</joint>
</robot>
<xacro:property>就是SolidWorks的"方程式"和"全局变量"。Xacro的<xacro:macro>就是"设计表(Design Table)"——定义一次、复用多次。平行轴定理I_end = I_cm + m·(L/2)²在惯性参数计算中关键:URDF的<inertial>的<origin>在关节处,惯量必须相对于该原点计算,不是质心。# display_2dof.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
pkg_share = FindPackageShare('urdf_practice')
# 1. Robot State Publisher: URDF → TF树
robot_state_pub = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{
'robot_description': Command([
'xacro ', PathJoinSubstitution([pkg_share, 'urdf', '2dof_arm.urdf'])
])
}]
)
# 2. Joint State Publisher GUI: 拖动关节
joint_state_pub = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
)
# 3. RViz: 3D可视化
rviz = Node(
package='rviz2',
executable='rviz2',
arguments=['-d', PathJoinSubstitution([pkg_share, 'rviz', 'arm_display.rviz'])]
)
return LaunchDescription([robot_state_pub, joint_state_pub, rviz])
| 检查项 | 命令/方法 | 预期结果 |
|---|---|---|
| URDF语法 | check_urdf 2dof_arm.urdf | "robot name is: 2dof_arm" success |
| Xacro编译 | ros2 run xacro xacro scara_robot.urdf.xacro | 输出完整URDF XML |
| TF树 | RViz中查看TF显示 | base_link→link1→link2→tool0 |
| 关节运动 | 拖动GUI滑块 | 机械臂平滑运动,无脱节 |
| 碰撞模型 | RViz显示collision几何 | 比visual更简化的包围盒 |
| 惯量参数 | Gazebo仿真中无"爆炸" | 接触力稳定不发散 |
# 方法1:sw2urdf插件(SolidWorks导出)
# 在SolidWorks中定义坐标系→关节轴→导出URDF
# 方法2:手动创建(推荐,理解更深)
# 从工程图中提取每个link的质量、质心、惯量
# 从装配图中提取joint的origin(配合面位置)
# 用Xacro宏定义6个相似的关节-link对
# ros2_control.yaml — 6轴臂的控制器配置
controller_manager:
ros__parameters:
update_rate: 100 # Hz
# 位置控制器(关节空间)
joint_trajectory_controller:
type: joint_trajectory_controller/JointTrajectoryController
# 关节状态广播
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
# 控制器参数
joint_trajectory_controller:
ros__parameters:
joints:
- joint1
- joint2
- joint3
- joint4
- joint5
- joint6
command_interfaces:
- position
state_interfaces:
- position
- velocity
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0