9. URDF 机器人建模与 robot_state_publisher
上一讲手写了每个坐标系变换,连杆长度散落在代码里。这一讲把机器人结构写进 URDF 文件,让 robot_state_publisher 自动发布 TF 树,改连杆长度只需改一个数字。
前言:手写 TF 的问题
上一讲我们手写了每个坐标系变换,代码量不小,而且有一个根本问题:
机器人结构定义散落在代码里。连杆长度 L1=1.0 既在运动学函数里,又在 TF 广播节点里,改一次要改多处。
真实工程的做法是:把机器人结构写在一个 XML 文件里(URDF),让专门的节点读取它。
手写 TF 方式:
代码里硬编码 L1, L2 → 手写 TransformStamped → 发布 /tf
(tf_broadcaster_node.py 约 80 行,改一次连杆长度要改代码)
URDF 方式:
URDF 文件定义结构 → robot_state_publisher 读取 → 自动发布 /tf
(改连杆长度只需改 URDF 里的一个数字,代码零改动)
后者不仅代码量少,还是 MoveIt 2、RViz2 机器人模型显示的前提条件。
上一讲手写 TF 不是走弯路——正是因为手写过,你才真正理解
robot_state_publisher背后在做什么。
9.1 URDF 基本结构
9.1.1 两个核心元素
URDF(Unified Robot Description Format)只有两个核心元素:
| 元素 | 含义 | 类比 |
|---|---|---|
<link> | 刚体部件 | 骨骼 |
<joint> | 连接两个 link 的运动关系 | 关节 |
机器人 = 若干 link + 若干 joint 组成的树状结构。
9.1.2 link 的结构
<link name="link1">
<!-- 可视化形状(RViz2 显示用) -->
<visual>
<origin xyz="0.5 0 0" rpy="0 0 0"/> <!-- 形状中心相对 link 原点的偏移 -->
<geometry>
<box size="1.0 0.05 0.05"/> <!-- 长方体:长 1m,宽高各 5cm -->
</geometry>
<material name="blue">
<color rgba="0.2 0.4 0.8 1.0"/>
</material>
</visual>
<!-- 碰撞形状(规划用,通常和 visual 一致或简化) -->
<collision>
<origin xyz="0.5 0 0" rpy="0 0 0"/>
<geometry>
<box size="1.0 0.05 0.05"/>
</geometry>
</collision>
</link>
注意:<visual> 的 origin 是形状中心相对 link 坐标系原点的偏移。对于一根长 1m 的连杆,link 原点在左端,形状中心在中间,所以 xyz="0.5 0 0"。
9.1.3 joint 的结构
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<origin xyz="0 0 0" rpy="0 0 0"/> <!-- 子 link 原点相对父 link 原点的初始位置 -->
<axis xyz="0 0 1"/> <!-- 旋转轴:绕 z 轴旋转(平面机械臂) -->
<limit lower="-1.5708" upper="1.5708" effort="10.0" velocity="1.0"/>
</joint>
9.1.4 常用 joint 类型
| 类型 | 说明 |
|---|---|
revolute | 旋转关节,有角度限制 |
continuous | 旋转关节,无角度限制(如轮子) |
prismatic | 直线关节 |
fixed | 固定连接,无自由度 |
9.2 完整的两连杆机械臂 URDF
9.2.1 创建描述包
机器人模型(URDF / Xacro、网格文件等)通常单独放在一个 描述包里,与写控制逻辑的 功能包分开,便于复用和同一份模型被仿真、RViz、MoveIt 等多处引用。这里用 **ament_cmake**:包内主要是资源文件与安装规则,不需要把节点写成 Python 包;colcon build 后通过 share/my_robot_description/... 被 get_package_share_directory 找到。
# 进入工作空间源码目录;新包必须建在这里,colcon 才会收录
cd $ROS_WS/src
# 生成包骨架:CMakeLists.txt、package.xml、include/ 等;包名一般带 _description 后缀表示「只放模型与 launch」
ros2 pkg create --build-type ament_cmake my_robot_description
# urdf/:存放 .urdf、.xacro;launch/:后面启动 robot_state_publisher、RViz 时用。-p 表示父目录不存在则创建,不报错
mkdir -p my_robot_description/urdf
mkdir -p my_robot_description/launch
9.2.2 编写 URDF 文件
vim $ROS_WS/src/my_robot_description/urdf/two_link_arm.urdf
<?xml version="1.0"?>
<!-- 根元素:一份 URDF 描述一棵树;name 仅作文档标识 -->
<robot name="two_link_arm">
<!-- ==================== Links ==================== -->
<!-- 约定:每根连杆的 link 原点放在「靠近父关节」的一端;长方体 visual 的 origin 把几何中心摆到杆件中段 -->
<!-- 基座:通常作为整机的根 link;是否「在世界中固定」由外层 joint 或仿真决定,URDF 里只描述形状 -->
<link name="base_link">
<visual>
<!-- 盒子尺寸 0.1×0.1×0.05(米);几何中心相对 link 原点抬高 0.025,使盒子底面落在 z=0 -->
<origin xyz="0 0 0.025" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.05"/>
</geometry>
<material name="gray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>
<collision>
<!-- 规划与碰撞检测用;常与 visual 同形,也可单独简化 -->
<origin xyz="0 0 0.025" rpy="0 0 0"/>
<geometry>
<box size="0.1 0.1 0.05"/>
</geometry>
</collision>
</link>
<!-- 连杆 1:杆长 1.0 m(x 方向);link 原点在父关节处(与 joint1 子端重合) -->
<link name="link1">
<visual>
<!-- 杆沿 +x 延伸:中心在 x=0.5,故 origin x=0.5,与 box 长度 1.0 一致 -->
<origin xyz="0.5 0 0" rpy="0 0 0"/>
<geometry>
<box size="1.0 0.05 0.05"/>
</geometry>
<material name="blue">
<color rgba="0.2 0.4 0.8 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.5 0 0" rpy="0 0 0"/>
<geometry>
<box size="1.0 0.05 0.05"/>
</geometry>
</collision>
</link>
<!-- 连杆 2:杆长 0.8 m;原点同样在靠近 joint2 的一端 -->
<link name="link2">
<visual>
<origin xyz="0.4 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.8 0.04 0.04"/>
</geometry>
<material name="green">
<color rgba="0.2 0.7 0.3 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.4 0 0" rpy="0 0 0"/>
<geometry>
<box size="0.8 0.04 0.04"/>
</geometry>
</collision>
</link>
<!-- 末端执行器:无碰撞模型也可(仅显示);球心与 link 原点重合 -->
<link name="end_effector">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="0.03"/>
</geometry>
<material name="red">
<color rgba="0.8 0.2 0.2 1.0"/>
</material>
</visual>
</link>
<!-- ==================== Joints ==================== -->
<!-- 平面臂:两关节轴均平行于 z,在 xy 平面内摆动 -->
<!-- joint1:子 link1 的原点贴在父 base_link 上;z=0.05 为基座顶面(台座高 0.05) -->
<joint name="joint1" type="revolute">
<parent link="base_link"/>
<child link="link1"/>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<!-- ±90°;effort/velocity 为占位,与 1.3 节 limit 说明一致 -->
<limit lower="-1.5708" upper="1.5708" effort="10.0" velocity="1.0"/>
</joint>
<!-- joint2:父为 link1;origin x=1.0 即 link1 几何末端(杆长 1.0),第二段从此处接出 -->
<joint name="joint2" type="revolute">
<parent link="link1"/>
<child link="link2"/>
<origin xyz="1.0 0 0" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<!-- 约 ±120° -->
<limit lower="-2.0944" upper="2.0944" effort="10.0" velocity="1.0"/>
</joint>
<!-- fixed:无自由度;用于安装法兰、工具或纯可视化标记 -->
<joint name="ee_joint" type="fixed">
<parent link="link2"/>
<child link="end_effector"/>
<!-- link2 杆长 0.8,末端在父系 +x=0.8;ee 的 link 原点即末端点 -->
<origin xyz="0.8 0 0" rpy="0 0 0"/>
</joint>
</robot>
9.2.3 验证 URDF 语法
# 安装验证工具
sudo apt install -y ros-jazzy-urdf
# 验证 URDF 文件
check_urdf $ROS_WS/src/my_robot_description/urdf/two_link_arm.urdf
预期输出:
robot name is: two_link_arm
---------- Successfully Parsed XML ---------------
root Link: base_link has 1 child(ren)
child(1): link1
child(1): link2
child(1): end_effector
9.3 配置描述包
9.3.1 CMakeLists.txt
vim $ROS_WS/src/my_robot_description/CMakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(my_robot_description)
find_package(ament_cmake REQUIRED)
# 安装 urdf 和 launch 目录
install(DIRECTORY urdf launch
DESTINATION share/${PROJECT_NAME}
)
ament_package()
9.3.2 package.xml
在 <buildtool_depend>ament_cmake</buildtool_depend> 后加入:
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>rviz2</exec_depend>
说明:这里的
<exec_depend>主要给**rosdep install** 或依赖解析使用,不会在你只执行colcon build时自动从 Ubuntu 仓库安装二进制包。若系统里从未装过joint_state_publisher_gui对应的 deb,Launch 仍会报「找不到该包」(见 9.8.4)。9.5 给出推荐安装方式。
9.4 Launch 文件——一键启动可视化
vim $ROS_WS/src/my_robot_description/launch/display.launch.py
# launch/display.launch.py
# 运行方式:ros2 launch my_robot_description display.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.substitutions import Command, LaunchConfiguration
def generate_launch_description():
pkg_dir = get_package_share_directory('my_robot_description')
urdf_file = os.path.join(pkg_dir, 'urdf', 'two_link_arm.urdf')
# 读取 URDF 文件内容为字符串
# robot_state_publisher 需要的是 robot_description 参数的字符串值,
# 而不是文件路径——它不会自己去读文件,必须把内容传给它
# 注意:第 10 讲 MoveIt Setup Assistant 生成的 launch 文件会用
# Command(['xacro ', urdf_xacro_file]) 的方式展开 xacro 模板,
# 两种方式等价,只是写法不同。纯 URDF 用 open() 读取即可。
with open(urdf_file, 'r') as f:
robot_description = f.read()
return LaunchDescription([
# robot_state_publisher:ROS2 官方节点
# 职责:读取 robot_description 参数(URDF 字符串)+ 订阅 /joint_states
# 根据 URDF 里的关节结构和收到的关节角,自动计算并发布整棵 TF 树
# 替代了第 8 讲里手写的 tf_broadcaster_node
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
# parameters 传字典:key 是参数名,value 是参数值
# robot_description 必须是 URDF 的完整 XML 字符串
parameters=[{'robot_description': robot_description}],
output='screen',
),
# joint_state_publisher_gui:ROS2 官方节点
# 职责:读取 robot_description,为每个可动关节生成一个滑块
# 拖动滑块时发布 /joint_states,驱动 robot_state_publisher 更新 TF
# 仅用于调试,真实系统里由控制器或算法节点发布 /joint_states
Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
output='screen',
),
# RViz2:可视化工具
# 职责:订阅 /robot_description、/tf、/joint_states 等 Topic
# 把机器人模型和坐标系树渲染出来
Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
),
])
9.5 构建并运行
9.5.1 安装系统软件包(joint_state_publisher_gui)
display.launch.py 会启动官方节点 **joint_state_publisher_gui**(滑块调关节)。它来自独立的 Ubuntu/Debian 软件包;若本机只装了 **ros-<发行版>-ros-base** 等精简环境,往往尚未安装该包,Launch 会报错:package 'joint_state_publisher_gui' not found。
在终端执行(将发行版名换成你本机的 ROS 2 版本,如 jazzy、humble):
sudo apt update
sudo apt install ros-jazzy-joint-state-publisher-gui
安装完成后,每次新开终端要先 source 系统 underlay,再 source 工作空间 overlay,例如:
source /opt/ros/jazzy/setup.bash
source $ROS_WS/install/setup.bash
自检是否已被 ROS 2 索引到:
ros2 pkg prefix joint_state_publisher_gui
若希望一次性安装桌面常用组件(含 RViz2、多种演示依赖,体积较大),也可选择安装 **ros-jazzy-desktop**,其中通常已包含 joint_state_publisher_gui。
9.5.2 编译描述包并启动
cd $ROS_WS
colcon build --packages-select my_robot_description
source install/setup.bash
ros2 launch my_robot_description display.launch.py
启动后会出现:
- 一个滑块界面(
joint_state_publisher_gui) - RViz2 窗口
9.5.3 配置 RViz2

第一次打开时 RViz2 可能是空白或报错,需要告诉它:以哪一帧为「世界参考」、从哪读机器人模型。按下面做即可。
1. 设置 Fixed Frame(固定参考系)
- 左侧
**Displays** 面板最上方**Global Options**展开,找到**Fixed Frame**。 - 默认常见为
map或odom,若 TF 树里没有这些坐标系,RViz 会提示**Fixed Frame ... does not exist**,模型也显示不出来。 - 本讲 Launch 里由
robot_state_publisher根据 URDF 广播 TF,根 link 是**base_link**,因此把**Fixed Frame改成base_link**。含义是:场景里所有显示(含 RobotModel)都先变换到这一帧下再画在屏幕上。 - 以后若接了
map→odom→base_link的移动机器人,再把 Fixed Frame 改回map/odom更合适;固定基座机械臂用base_link最省事。
2. 添加 RobotModel 显示项
- 左下角
**Add** → 在弹出列表里选**RobotModel**→**OK**。 **RobotModel**会订阅**/robot_description**(std_msgs/msg/String,内容为整份 URDF XML)以及**/tf**(与**/tf_static**),把各 link 的 mesh/简单几何画出来;关节角则来自**/joint_states**(由joint_state_publisher_gui发布)。因此**robot_state_publisher与滑块节点都要已启动**,缺一不可。
3. 指定 Description Topic
- 在
**Displays** 里选中**RobotModel**,右侧(或展开该项)找到**Description Topic**。 - 应填
**/robot_description**(与robot_state_publisher发布的 topic 一致,类型为std_msgs/msg/String)。 - 下拉列表里找不到
/robot_description很常见,不一定是 Launch 配错了:列表往往只收录已发现的 topic,或过滤方式导致不全。直接在输入框里手动输入/robot_description并回车即可。 - 若心里没底,另开终端执行
ros2 topic list | grep description:能看到/robot_description就说明节点已在发;若没有,先检查robot_state_publisher是否启动失败(例如 URDF 路径错误)。 - 说明:
robot_state_publisher会把参数里的 URDF 字符串再发布到robot_description这个 topic 上(文档里多为 transient local 的 QoS),方便 RViz 等订阅;与「只在参数里带一份robot_description」并不矛盾。
4. 自检
- 若仍无模型:看终端是否有 TF 报错;用
ros2 topic echo /joint_states --once确认有关节数据;用ros2 topic echo /robot_description --once确认能收到 XML 字符串。 - 坐标系是否连上:可
**Add→TF**,显示坐标轴,便于对照 URDF 里的 link 名。
完成上述配置后,拖动 joint_state_publisher_gui 里的滑块,RViz2 中的机械臂应随之运动。
9.5.4 同时验证 TF 树
# 新开终端
ros2 run tf2_tools view_frames
生成的 frames.pdf 应该显示:
base_link → link1 → link2 → end_effector
9.6 把 kinematics_publisher 接入 URDF 系统
上一讲的 kinematics_publisher 发布的 /joint_states 消息,关节名是 ['joint1', 'joint2'],和 URDF 里的关节名完全一致——这不是巧合,这就是 ROS2 的约定。
把 joint_state_publisher_gui 换成 kinematics_publisher,由算法独占发布 /joint_states,机械臂就会随程序动。
一定要先停掉之前带滑块的 Launch(在运行 display.launch.py 的终端里按 Ctrl+C)。若不停掉,joint_state_publisher_gui 与 kinematics_publisher 会同时往 /joint_states 发消息,robot_state_publisher 收到的是「打架」后的结果,模型可能乱跳或表现不符合预期。
9.6.1 编写 display_no_gui.launch.py
9.4 里的 display.launch.py 会同时启动 joint_state_publisher_gui。要让 kinematics_publisher 单独驱动关节,最干净的做法是再写一个 Launch:逻辑与 display.launch.py 相同(同样从安装共享目录读 two_link_arm.urdf,把字符串交给 robot_state_publisher,再开 RViz2),只是删掉 joint_state_publisher_gui 那个 Node 即可。
在描述包里新建文件(路径按你的工作空间调整,以下默认 $ROS_WS/src/...):
vim $ROS_WS/src/my_robot_description/launch/display_no_gui.launch.py
完整内容如下:
# launch/display_no_gui.launch.py
# 运行方式:ros2 launch my_robot_description display_no_gui.launch.py
# 与 display.launch.py 相比:不启动 joint_state_publisher_gui,便于其它节点独占 /joint_states
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
pkg_dir = get_package_share_directory('my_robot_description')
urdf_file = os.path.join(pkg_dir, 'urdf', 'two_link_arm.urdf')
with open(urdf_file, 'r') as f:
robot_description = f.read()
return LaunchDescription([
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
parameters=[{'robot_description': robot_description}],
output='screen',
),
Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
),
])
保存后若这是新文件,需要重新安装到 share(9.3 已用 install(DIRECTORY launch ...),会整目录安装):
cd $ROS_WS
colcon build --packages-select my_robot_description
source install/setup.bash
9.6.2 运行
# 终端 1:robot_state_publisher + RViz2(无滑块 GUI)
ros2 launch my_robot_description display_no_gui.launch.py
# 终端 2:用算法发布关节角(替代 gui 滑块)
ros2 run my_robot_basics kinematics_publisher
若你暂时仍想用 display.launch.py,必须先结束其中的 joint_state_publisher_gui 节点(否则仍会与 kinematics_publisher 争用同一 Topic),再运行 kinematics_publisher;实际操作不如直接使用上面的专用 Launch 简单。
此时 RViz2 里的机械臂会平滑摆动,这是第一次看到算法驱动模型运动。
RViz2 配置说明
RViz2 首次启动是空白界面,需要手动添加显示插件:
- 左侧
Global Options→Fixed Frame改为base_link - 点击左下角
Add→ 选择RobotModel→ OK RobotModel展开后,Description Topic确认为/robot_description
完成后 3D 视口里就能看到机械臂模型。如果模型不动,检查终端 2 的 kinematics_publisher 是否正在运行,以及终端 1 的 robot_state_publisher 日志里有没有报错。

9.7 xacro 简介
当 URDF 变复杂时,重复内容会很多。xacro 是 URDF 的模板语言,支持变量和宏:
<?xml version="1.0"?>
<robot name="two_link_arm" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- 定义变量 -->
<xacro:property name="L1" value="1.0"/>
<xacro:property name="L2" value="0.8"/>
<!-- 定义宏:可复用的连杆模板 -->
<xacro:macro name="arm_link" params="name length color">
<link name="${name}">
<visual>
<origin xyz="${length/2} 0 0" rpy="0 0 0"/>
<geometry>
<box size="${length} 0.05 0.05"/>
</geometry>
<material name="${color}">
<color rgba="0.2 0.4 0.8 1.0"/>
</material>
</visual>
</link>
</xacro:macro>
<!-- 使用宏 -->
<xacro:arm_link name="link1" length="${L1}" color="blue"/>
<xacro:arm_link name="link2" length="${L2}" color="green"/>
</robot>
xacro 文件用 .urdf.xacro 后缀,在 Launch 里用 Command 展开:
robot_description = Command(['xacro ', urdf_xacro_file])
入门阶段用纯 URDF 即可,遇到大量重复时再引入 xacro。
9.8 常见错误
9.8.1 错误一:模型显示方向不对
原因:<visual> 的 origin 写错,或者 <joint> 的 origin 写错。
排查:用 check_urdf 验证语法,再在 RViz2 里逐个关节检查位置。
9.8.2 错误二:机械臂不动
症状:RViz2 里模型显示了,但拖动滑块没有反应。
排查:
# 确认 /joint_states 在发布
ros2 topic echo /joint_states
# 确认关节名和 URDF 一致
ros2 topic echo /joint_states | grep name
URDF 里的 <joint name="joint1"> 必须和 JointState.name 里的 "joint1" 完全一致。
9.8.3 错误三:robot_description 参数为空
[robot_state_publisher]: No robot_description parameter
检查 Launch 文件里是否正确读取了 URDF 文件内容,路径是否正确。
9.8.4 错误四:package 'joint_state_publisher_gui' not found
症状:执行 ros2 launch my_robot_description display.launch.py 时,Launch 直接失败,日志类似:
[ERROR] [launch]: Caught exception in launch ...: "package 'joint_state_publisher_gui' not found, searching: [..., '/opt/ros/jazzy']"
原因:当前 shell 所 source 的 underlay(如 /opt/ros/jazzy)里没有名为 joint_state_publisher_gui 的已安装功能包。常见于只安装了 ros-base、未单独安装 GUI 相关 deb 的环境。
解决:按 9.5.1 用 apt 安装 ros-<发行版>-joint-state-publisher-gui(或安装 ros-<发行版>-desktop),然后重新执行:
source /opt/ros/<发行版>/setup.bash
source $ROS_WS/install/setup.bash
再启动 launch。也可用 ros2 pkg prefix joint_state_publisher_gui 确认包已可见。
9.9 练习题
9.9.1 练习 1:修改连杆颜色
把 link1 改为橙色(rgba="0.9 0.5 0.1 1.0"),重新构建后在 RViz2 里验证颜色变化。
9.9.2 练习 2:调整关节限位
把 joint1 的限位从 [-π/2, π/2] 改为 [-π, π],观察 joint_state_publisher_gui 的滑块范围变化。
<limit lower="-3.1416" upper="3.1416" effort="10.0" velocity="1.0"/>
9.9.3 练习 3:用 kinematics_publisher 驱动模型
按 9.6 的步骤,用 kinematics_publisher 替代 joint_state_publisher_gui,在 RViz2 里观察机械臂随算法自动运动。
本讲核心总结
| 概念 | 一句话理解 |
|---|---|
| URDF | XML 格式的机器人结构描述,link 是部件,joint 是连接关系 |
<visual> origin | 形状中心相对 link 坐标系原点的偏移,连杆中点在 x=L/2 |
<joint> origin | 子 link 原点相对父 link 原点的初始位置,关节 2 在 x=L1 |
robot_state_publisher | 读取 URDF + /joint_states,自动发布整棵 TF 树 |
joint_state_publisher_gui | 提供滑块界面,手动控制关节角,适合调试 |
check_urdf | 验证 URDF 语法并打印坐标系树结构 |
参考代码
本讲对应的完整参考代码位于:
ros_ws/reference/src/my_robot_description/
├── urdf/two_link_arm.urdf ← 9.2 完整 URDF(含 ros2_control 标签)
├── launch/display.launch.py ← 9.4 含滑块 GUI 的可视化 Launch
├── launch/display_no_gui.launch.py ← 9.6 不含 GUI,供算法节点驱动
├── CMakeLists.txt
└── package.xml
使用方式:完成 ros2 pkg create --build-type ament_cmake my_robot_description 后:
cp $ROS_WS/reference/src/my_robot_description/urdf/two_link_arm.urdf \
$ROS_WS/src/my_robot_description/urdf/
cp $ROS_WS/reference/src/my_robot_description/launch/display.launch.py \
$ROS_WS/src/my_robot_description/launch/
cp $ROS_WS/reference/src/my_robot_description/launch/display_no_gui.launch.py \
$ROS_WS/src/my_robot_description/launch/
URDF 文件注释中详细说明了每个 <link> 的 origin 偏移计算方式,以及 ros2_control 标签的作用。
下一讲预告
10. MoveIt 2 基础与运动规划
现在我们有了 URDF 模型,TF 树能自动发布,机械臂能在 RViz2 里动起来。这正是 MoveIt 2 需要的前置条件。
下一讲我们会:
- 用 MoveIt Setup Assistant 为两连杆机械臂生成配置包
- 理解 SRDF 是什么,和 URDF 有什么区别
- 启动 MoveIt 2 的 demo,在 RViz2 里拖动目标点触发规划
- 理解
move_group、Planning Scene、规划插件各自的职责