4. ROS2 工程基础
上一讲的 FK/IK 函数是独立的 Python 脚本,这一讲把它们放进 ROS2 工程。从创建工作空间、写 package.xml,到第一次 ros2 run,完整走一遍。
前言:从脚本到工程
上一讲我们写好了 FK 和 IK 函数,可以直接用 python3 two_link_kinematics.py 运行。
这一讲的任务是:把这些函数放进 ROS2 工程。
"独立脚本"和"ROS2 节点"的区别在于:
| 独立脚本 | ROS2 节点 |
|---|---|
python3 xxx.py 直接运行 | ros2 run pkg_name node_name 启动 |
| 只能单机单进程 | 可以多节点分布式协作 |
| 没有标准通信接口 | 通过 Topic / Service / Action 通信 |
| 无法被参数系统控制 | 支持运行时参数修改 |
| 无法被 RViz2 可视化 | 发布标准消息即可可视化 |
这些能力从现在开始逐步建立,后面接入 URDF 和 MoveIt 2 时会省很多麻烦。
4.1 工作空间与功能包结构
4.1.1 工作空间目录结构
ROS2 工程以**工作空间(workspace)**为单位组织,典型结构如下:
$ROS_WS/ ← 工作空间根目录
├── src/ ← 所有功能包的源码放这里
│ └── my_robot_basics/ ← 一个功能包
│ ├── package.xml ← 包的元信息和依赖声明
│ ├── setup.py ← Python 安装配置(入口点)
│ ├── setup.cfg ← 构建工具配置
│ └── my_robot_basics/ ← Python 模块目录(同名)
│ ├── __init__.py ← 标记为 Python 包
│ └── hello_node.py ← 节点源码
├── build/ ← 构建中间产物(自动生成)
├── install/ ← 安装结果(自动生成)
│ └── my_robot_basics/
│ └── lib/
│ └── my_robot_basics/
│ └── hello_node ← 可执行入口(由 setup.py 生成)
└── log/ ← 构建和运行日志(自动生成)
关键点:src/ 是你手动维护的,build/、install/、log/ 都是 colcon build 自动生成的,不要手动修改。
4.1.2 colcon build 做了什么
colcon build
↓
读取 src/ 下每个包的 package.xml
↓
按依赖顺序构建每个包
↓
把可执行文件和模块安装到 install/
↓
生成 install/setup.bash(环境变量配置)
source install/setup.bash 的作用是把 install/ 里的路径加入 PATH 和 PYTHONPATH,这样 ros2 run 才能找到你的节点。
4.1.3 推荐的多包划分思路
一个真实机器人项目通常会拆成多个包:
src/
├── my_robot_description/ ← URDF 模型文件
├── my_robot_kinematics/ ← FK / IK 算法
├── my_robot_bringup/ ← 启动文件(launch)
└── my_robot_moveit_config/ ← MoveIt 2 配置
本讲只创建一个最小包,但从一开始就建立清晰分工意识,后面扩展时会更顺。
4.2 package.xml 逐行解析
创建包后,package.xml 的完整内容如下:
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd"
schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<!-- 包名,必须和目录名一致 -->
<name>my_robot_basics</name>
<!-- 版本号,遵循语义化版本 -->
<version>0.0.1</version>
<!-- 简短描述 -->
<description>ROS2 工程基础示例包</description>
<!-- 维护者信息,必填 -->
<maintainer email="you@example.com">Your Name</maintainer>
<!-- 开源协议 -->
<license>Apache-2.0</license>
<!-- 构建工具依赖:Python 包用 ament_python -->
<buildtool_depend>ament_python</buildtool_depend>
<!-- 运行时依赖:节点用到的 ROS2 库 -->
<exec_depend>rclpy</exec_depend>
<!-- 如果用到标准消息类型,也要在这里声明 -->
<!-- <exec_depend>std_msgs</exec_depend> -->
<export>
<build_type>ament_python</build_type>
</export>
</package>
常见错误:用到了某个消息类型(比如 std_msgs)但忘记在 package.xml 里声明 <exec_depend>,构建时不报错,但在其他机器上安装后运行会找不到依赖。
4.3 setup.py 逐行解析
from setuptools import find_packages, setup
package_name = 'my_robot_basics'
setup(
# 包名,必须和 package.xml 里的 <name> 一致
name=package_name,
version='0.0.1',
packages=find_packages(exclude=['test']), # 自动找到所有 Python 子包
# 安装非 Python 文件(如 launch 文件、配置文件)
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='Your Name',
maintainer_email='you@example.com',
description='ROS2 工程基础示例包',
license='Apache-2.0',
tests_require=['pytest'],
# 入口点:告诉 ROS2 "ros2 run my_robot_basics hello_node" 对应哪个函数
# 格式:'节点名 = 模块路径:函数名'
entry_points={
'console_scripts': [
'hello_node = my_robot_basics.hello_node:main',
# ↑ ros2 run 时用的名字
# ↑ Python 模块路径(包名.文件名)
# ↑ 入口函数名
],
},
)
类比:entry_points 就像 Python 的 if __name__ == '__main__',但它让 ROS2 知道从哪里启动节点。每新增一个节点,就在 console_scripts 里加一行。
4.4 节点结构逐行解析
4.4.1 最小节点代码
# my_robot_basics/hello_node.py
# 运行方式:ros2 run my_robot_basics hello_node
#
# ============================================================
# 节点目标:最小 ROS2 节点示例,验证工程环境是否搭建正确
# 执行逻辑:
# 1. rclpy.init() 初始化 ROS2 运行时
# 2. 创建节点实例,节点名注册到 ROS2 系统
# 3. __init__ 里打印一条日志
# 4. rclpy.spin() 进入事件循环,节点持续存活
# 5. Ctrl+C 后清理退出
# ============================================================
import rclpy # ROS2 Python 客户端库,提供 init/spin/shutdown 等全局函数
from rclpy.node import Node # 所有节点的基类,提供日志、定时器、发布/订阅等能力
class HelloNode(Node):
def __init__(self):
# 向 ROS2 系统注册节点,传入的字符串就是节点名
# 节点名决定了 ros2 node list 里显示的名字,以及日志前缀
# 同一系统里节点名必须唯一,否则会有警告
super().__init__('hello_node')
# get_logger() 返回该节点专属的日志器
# 日志会带上时间戳和节点名,比 print() 更适合 ROS2 调试
# 级别从低到高:debug < info < warn < error < fatal
self.get_logger().info('Hello from ROS2!')
def main(args=None):
# 初始化 rclpy 运行时,必须在创建任何节点之前调用
# args=args 允许从命令行传入 ROS2 参数(如 --ros-args -p key:=value)
rclpy.init(args=args)
# 创建节点实例,__init__ 在这里执行
node = HelloNode()
# 进入事件循环:rclpy.spin() 会阻塞在这里,持续监听并分发回调
# 包括:订阅回调、定时器回调、服务请求回调等
# 没有 spin(),节点虽然创建了,但所有回调都不会被执行
# 按 Ctrl+C 会触发 KeyboardInterrupt,spin() 随之返回
rclpy.spin(node)
# spin() 返回后执行清理:注销节点、释放资源
node.destroy_node()
# 关闭 rclpy 运行时,释放底层 DDS 通信资源
rclpy.shutdown()
4.4.2 节点生命周期
rclpy.init()
↓
Node.__init__() ← 注册节点名、创建订阅/发布/定时器
↓
rclpy.spin() ← 进入事件循环,等待并处理回调
↓
Ctrl+C / 程序结束
↓
node.destroy_node() ← 注销节点,释放资源
↓
rclpy.shutdown() ← 关闭运行时
4.4.3 spin 的两种用法
| 用法 | 说明 | 适用场景 |
|---|---|---|
rclpy.spin(node) | 阻塞,持续处理所有回调 | 大多数节点 |
rclpy.spin_once(node) | 处理一次回调后立即返回 | 需要手动控制循环节奏 |
4.5 完整上机演示
4.5.1 创建工作空间
# 新建工作空间目录
mkdir -p $ROS_WS/src
cd $ROS_WS
# source ROS2 环境(把 <distro> 替换为你的版本,如 humble 或 jazzy)
source /opt/ros/<distro>/setup.bash
# 第一次构建(src 为空也没关系,验证环境正常)
colcon build
预期输出:
Summary: 0 packages finished [0.3s]
4.5.2 创建 Python 功能包
cd $ROS_WS/src
ros2 pkg create --build-type ament_python my_robot_basics
预期输出:
going to create a new package
package name: my_robot_basics
destination directory: /home/user/ros2_ws/src
package format: 3
...
creating folder ./my_robot_basics/my_robot_basics
creating ./my_robot_basics/my_robot_basics/__init__.py
4.5.3 写节点文件
# 在包的 Python 模块目录下创建节点文件
vim $ROS_WS/src/my_robot_basics/my_robot_basics/hello_node.py
把 4.4 节的代码粘贴进去,保存退出。
4.5.4 注册入口点
编辑 $ROS_WS/src/my_robot_basics/setup.py,在 entry_points 里加入:
entry_points={
'console_scripts': [
'hello_node = my_robot_basics.hello_node:main',
],
},
4.5.5 构建并运行
# 回到工作空间根目录构建
cd $ROS_WS
colcon build --packages-select my_robot_basics
预期输出:
Starting >>> my_robot_basics
Finished <<< my_robot_basics [1.2s]
Summary: 1 package finished [1.5s]
# source 安装环境(每次新开终端都要执行)
source install/setup.bash
# 运行节点
ros2 run my_robot_basics hello_node
预期输出:
[INFO] [1234567890.123] [hello_node]: Hello from ROS2!
节点会持续运行(spin 阻塞),按 Ctrl+C 退出。
4.5.6 用 CLI 验证节点状态
新开一个终端,source 环境后执行:
# 查看当前运行的所有节点
ros2 node list
# 输出:/hello_node
# 查看节点详细信息
ros2 node info /hello_node
# 输出:节点名、命名空间、订阅、发布、服务等
# 查看当前所有 topic
ros2 topic list
# 查看当前所有 service
ros2 service list
4.6 把 FK/IK 接入 ROS2 节点
4.6.1 把运动学模块放进包里
在包的模块目录下创建 two_link_kinematics.py,内容如下(如果你已经在上一讲动手写过,也可以直接从那里复制过来):
vim $ROS_WS/src/my_robot_basics/my_robot_basics/two_link_kinematics.py
# two_link_kinematics.py
import math
def forward_kinematics(theta1_deg, theta2_deg, L1=1.0, L2=1.0):
"""
两连杆平面机械臂正运动学
参数:
theta1_deg: 关节1角度(度),相对 base 坐标系
theta2_deg: 关节2角度(度),相对连杆1坐标系
L1: 连杆1长度(米),默认 1.0
L2: 连杆2长度(米),默认 1.0
返回:
(x, y): 末端位置(米)
"""
theta1 = math.radians(theta1_deg)
theta2 = math.radians(theta2_deg)
x = L1 * math.cos(theta1) + L2 * math.cos(theta1 + theta2)
y = L1 * math.sin(theta1) + L2 * math.sin(theta1 + theta2)
return x, y
def inverse_kinematics(x, y, L1=1.0, L2=1.0):
"""
两连杆平面机械臂逆运动学
参数:
x, y: 目标末端位置(米)
L1: 连杆1长度(米),默认 1.0
L2: 连杆2长度(米),默认 1.0
返回:
dict,包含两组解:
{
"elbow_down": (theta1_deg, theta2_deg), # 肘下解,theta2 > 0
"elbow_up": (theta1_deg, theta2_deg), # 肘上解,theta2 < 0
}
如果目标不可达,抛出 ValueError
注意:
返回角度单位为度
"""
r_sq = x**2 + y**2
r = math.sqrt(r_sq)
# 可达性检查
r_max = L1 + L2
r_min = abs(L1 - L2)
if r > r_max:
raise ValueError(
f"目标点 ({x:.3f}, {y:.3f}) 超出工作空间:"
f"距离 {r:.3f} m > 最大可达 {r_max:.3f} m"
)
if r < r_min:
raise ValueError(
f"目标点 ({x:.3f}, {y:.3f}) 在死区内:"
f"距离 {r:.3f} m < 最小可达 {r_min:.3f} m"
)
# 用余弦定理求 θ2
cos_theta2 = (r_sq - L1**2 - L2**2) / (2 * L1 * L2)
# 防止浮点误差导致 acos 输入略微超出 [-1, 1]
cos_theta2 = max(-1.0, min(1.0, cos_theta2))
theta2_down = math.acos(cos_theta2) # 肘下解:θ2 > 0
theta2_up = -theta2_down # 肘上解:θ2 < 0
def solve_theta1(theta2):
k1 = L1 + L2 * math.cos(theta2)
k2 = L2 * math.sin(theta2)
return math.atan2(y, x) - math.atan2(k2, k1)
theta1_down = solve_theta1(theta2_down)
theta1_up = solve_theta1(theta2_up)
return {
"elbow_down": (math.degrees(theta1_down), math.degrees(theta2_down)),
"elbow_up": (math.degrees(theta1_up), math.degrees(theta2_up)),
}
目录结构变为:
my_robot_basics/
└── my_robot_basics/
├── __init__.py
├── hello_node.py
└── two_link_kinematics.py ← 新增
4.6.2 在节点中调用 FK/IK
# my_robot_basics/kinematics_node.py
# 运行方式:ros2 run my_robot_basics kinematics_node
#
# ============================================================
# 节点目标:把第 3 讲的 FK/IK 函数接入 ROS2,验证运动学计算
# 在 ROS2 节点环境下能正常运行
# 执行逻辑:
# 1. 节点启动时(__init__)用固定关节角计算一次 FK
# 2. 把 FK 结果传给 IK,做 round-trip 验证
# 3. 把结果打印到日志
# 4. 之后节点进入 spin() 等待状态(本讲暂无定时器/订阅)
# 注意:本节点只在启动时计算一次,不持续发布数据
# 第 5 讲会升级为持续发布关节角到 Topic
# ============================================================
import rclpy
from rclpy.node import Node
# 用完整包路径导入,不要用相对导入(.two_link_kinematics)
# 原因:ROS2 通过 entry_points 启动节点时,相对导入可能失效
from my_robot_basics.two_link_kinematics import forward_kinematics, inverse_kinematics
class KinematicsNode(Node):
def __init__(self):
# 'kinematics_node' 是节点名,会出现在 ros2 node list 的输出里
super().__init__('kinematics_node')
# 连杆长度暂时硬编码,第 7 讲会改为从参数系统读取
# 这样改连杆长度时不需要重新编译,只需修改参数文件
self.L1 = 1.0
self.L2 = 0.8
# 节点启动时计算一次 FK 并打印
# __init__ 里的代码在节点创建时立即执行,不需要等 spin()
theta1, theta2 = 30.0, 45.0
x, y = forward_kinematics(theta1, theta2, self.L1, self.L2)
self.get_logger().info(
f'FK: θ1={theta1}°, θ2={theta2}° → 末端=({x:.4f}, {y:.4f})'
)
# 把 FK 结果传给 IK,验证 round-trip 是否正确
# inverse_kinematics 返回字典:{'elbow_down': (t1, t2), 'elbow_up': (t1, t2)}
solutions = inverse_kinematics(x, y, self.L1, self.L2)
for name, (t1, t2) in solutions.items():
self.get_logger().info(
f'IK {name}: θ1={t1:.2f}°, θ2={t2:.2f}°'
)
def main(args=None):
rclpy.init(args=args)
node = KinematicsNode()
# spin() 让节点持续存活,即使本节点没有定时器/订阅
# 没有 spin(),节点会在 __init__ 执行完后立即退出
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
在 setup.py 的 entry_points 里追加:
'console_scripts': [
'hello_node = my_robot_basics.hello_node:main',
'kinematics_node = my_robot_basics.kinematics_node:main', # 新增
],
重新构建并运行:
cd $ROS_WS
colcon build --packages-select my_robot_basics
source install/setup.bash
ros2 run my_robot_basics kinematics_node
预期输出:
[INFO] [...] [kinematics_node]: FK: θ1=30.0°, θ2=45.0° → 末端=(1.0731, 1.2727)
[INFO] [...] [kinematics_node]: IK elbow_down: θ1=30.00°, θ2=45.00°
[INFO] [...] [kinematics_node]: IK elbow_up: θ1=75.00°, θ2=-45.00°
4.7 常见错误
4.7.1 错误一:忘记 source 安装环境
# 错误:构建完直接运行
colcon build
ros2 run my_robot_basics hello_node
# 报错:Package 'my_robot_basics' not found
# 正确:构建后先 source
colcon build
source install/setup.bash
ros2 run my_robot_basics hello_node
原因:colcon build 把节点安装到 install/ 目录,但系统不知道这个目录的存在,source install/setup.bash 才会把它加入 PATH。
建议:把 source $ROS_WS/install/setup.bash 加入 ~/.bashrc,避免每次手动执行。
4.7.2 错误二:setup.py 入口点写错
# 错误:模块路径写错(文件名拼错)
'hello_node = my_robot_basics.helo_node:main',
# 错误:函数名写错
'hello_node = my_robot_basics.hello_node:Main',
# 正确
'hello_node = my_robot_basics.hello_node:main',
报错信息:ros2 run 时提示 No executable found,或运行时抛出 ImportError。
排查方法:检查 src/my_robot_basics/my_robot_basics/ 目录下的文件名,和 setup.py 里的模块路径是否完全一致(大小写敏感)。
4.7.3 错误三:package.xml 漏写依赖
<!-- 错误:用了 std_msgs 但没有声明 -->
<exec_depend>rclpy</exec_depend>
<!-- 正确:用到什么就声明什么 -->
<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
后果:本机构建可能成功(因为系统已安装),但在其他机器上用 rosdep install 安装依赖时会漏掉,导致运行时 ImportError。
4.7.4 错误四:节点名冲突
# 如果同时运行两个同名节点,ROS2 会警告
# 节点1
super().__init__('my_node')
# 节点2(同名)
super().__init__('my_node')
# 警告:两个节点名相同,行为未定义
正确做法:每个节点用唯一的名字,或者通过 launch 文件的 name 参数重命名:
ros2 run my_robot_basics hello_node --ros-args -r __node:=hello_node_2
4.7.5 错误五:Python 模块导入路径错误
# 错误:用相对导入(在 ROS2 节点里不可靠)
from .two_link_kinematics import forward_kinematics
# 正确:用完整包路径导入
from my_robot_basics.two_link_kinematics import forward_kinematics
原因:ROS2 节点通过 entry_points 启动,Python 的相对导入依赖包的 __package__ 属性,在这种启动方式下可能不正确。
4.8 常用 CLI 工具
在后续所有章节里,CLI 都是最重要的排查手段。建议尽早熟悉:
# 节点相关
ros2 node list # 列出所有运行中的节点
ros2 node info /node_name # 查看节点的订阅、发布、服务
# Topic 相关
ros2 topic list # 列出所有 topic
ros2 topic echo /topic_name # 实时打印 topic 消息
ros2 topic info /topic_name # 查看 topic 类型和发布者/订阅者数量
ros2 topic hz /topic_name # 测量 topic 发布频率
# Service 相关
ros2 service list # 列出所有 service
ros2 service call /srv_name ... # 手动调用 service
# 参数相关
ros2 param list # 列出所有节点的参数
ros2 param get /node_name param # 读取参数值
ros2 param set /node_name param v # 运行时修改参数
# 包相关
ros2 pkg list # 列出所有已安装的包
ros2 pkg executables pkg_name # 列出包里所有可执行节点
这些命令能帮助你从"黑盒运行"转向"可观测系统"。
4.9 练习题
4.9.1 练习 1:追踪构建产物
构建 my_robot_basics 后,在 install/ 目录里找到以下文件,理解它们的作用:
install/my_robot_basics/lib/my_robot_basics/hello_node(可执行入口)install/my_robot_basics/lib/python3.x/site-packages/my_robot_basics/hello_node.py(Python 源码)
参考答案:
# 查看可执行入口内容(它其实是个 Python 脚本)
cat install/my_robot_basics/lib/my_robot_basics/hello_node
输出类似:
#!/usr/bin/env python3
# 自动生成的入口脚本
from my_robot_basics.hello_node import main
main()
这就是 ros2 run 实际执行的文件,它调用了 setup.py 里 entry_points 指定的 main 函数。
4.9.2 练习 2:修改节点名并用 CLI 验证
修改 hello_node.py,把节点名从 'hello_node' 改为 'my_first_node',重新构建并运行,用 ros2 node list 验证节点名已更改。
参考答案:
# 修改这一行
super().__init__('my_first_node')
colcon build --packages-select my_robot_basics
source install/setup.bash
ros2 run my_robot_basics hello_node & # 后台运行
ros2 node list
# 预期输出:/my_first_node
4.9.3 练习 3:把 FK 函数集成进节点
在 hello_node.py 里导入 forward_kinematics,节点启动时计算 θ1=45°、θ2=90°、L1=1.0、L2=1.0 的末端位置并打印。
参考答案:
import rclpy
from rclpy.node import Node
from my_robot_basics.two_link_kinematics import forward_kinematics
class HelloNode(Node):
def __init__(self):
super().__init__('hello_node')
x, y = forward_kinematics(45.0, 90.0, L1=1.0, L2=1.0)
self.get_logger().info(f'FK 结果: ({x:.4f}, {y:.4f})')
def main(args=None):
rclpy.init(args=args)
node = HelloNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
预期输出:
[INFO] [...] [hello_node]: FK 结果: (-0.7071, 1.7071)
Python 验证:
from two_link_kinematics import forward_kinematics
x, y = forward_kinematics(45.0, 90.0, 1.0, 1.0)
print(f"({x:.4f}, {y:.4f})")
# 预期输出: (-0.7071, 1.7071)
4.9.4 练习 4:添加定时器,每秒打印一次
修改 kinematics_node.py,用 create_timer 创建一个 1 秒定时器,每次触发时随机生成一组关节角(θ1 在 [-90°, 90°],θ2 在 [-120°, 120°]),计算 FK 并打印。
参考答案:
import random
import rclpy
from rclpy.node import Node
from my_robot_basics.two_link_kinematics import forward_kinematics
class KinematicsNode(Node):
def __init__(self):
super().__init__('kinematics_node')
self.L1 = 1.0
self.L2 = 0.8
# create_timer(周期秒数, 回调函数)
# 每隔 1.0 秒,rclpy 事件循环会自动调用一次 timer_callback
# 定时器在 spin() 运行期间才会触发,__init__ 里只是注册,不会立即执行
self.timer = self.create_timer(1.0, self.timer_callback)
self.get_logger().info('节点启动,每秒计算一次 FK...')
def timer_callback(self):
# 每次定时器触发时执行:生成随机关节角,计算 FK,打印结果
theta1 = random.uniform(-90.0, 90.0)
theta2 = random.uniform(-120.0, 120.0)
x, y = forward_kinematics(theta1, theta2, self.L1, self.L2)
self.get_logger().info(
f'θ1={theta1:6.1f}°, θ2={theta2:6.1f}° → ({x:.4f}, {y:.4f})'
)
def main(args=None):
rclpy.init(args=args)
node = KinematicsNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
预期输出(每秒一行,数值随机):
[INFO] [...] [kinematics_node]: 节点启动,每秒计算一次 FK...
[INFO] [...] [kinematics_node]: θ1= 23.4°, θ2= -67.8° → (1.2341, 0.5678)
[INFO] [...] [kinematics_node]: θ1= -45.1°, θ2= 112.3° → (-0.3456, 0.9012)
本讲核心总结
| 概念 | 一句话理解 |
|---|---|
| 工作空间 | src/ 放源码,colcon build 生成 install/,source install/setup.bash 激活环境 |
| 功能包 | ROS2 的基本组织单元,package.xml 声明依赖,setup.py 声明入口点 |
| 节点 | 继承 Node,__init__ 里注册资源,spin 进入事件循环 |
| entry_points | setup.py 里的映射表,决定 ros2 run 能找到哪些节点 |
| source 环境 | 每次新开终端都要执行,否则 ros2 run 找不到节点 |
| CLI 工具 | ros2 node/topic/service/param 是排查问题的第一手段 |
参考代码
本讲对应的完整参考代码位于:
ros_ws/reference/src/my_robot_basics/
├── my_robot_basics/
│ ├── hello_node.py ← 4.4 最小节点
│ ├── kinematics_node.py ← 4.6 FK/IK 接入 ROS2
│ └── two_link_kinematics.py ← 4.6 运动学算法模块
├── package.xml
└── setup.py
使用方式:完成 ros2 pkg create 后,可将参考文件 cp 到你的包中:
# cp 单个文件
cp $ROS_WS/reference/src/my_robot_basics/my_robot_basics/hello_node.py \
$ROS_WS/src/my_robot_basics/my_robot_basics/
# 或直接参考 setup.py 的 entry_points 写法
参考代码中的注释标注了 [原理]、[注意]、[对比] 等关键说明,与本讲教程内容互补。
下一讲预告
5. Topic 通信
本讲的节点只会打印日志,还不能和其他节点通信。下一讲我们会:
- 让
kinematics_publisher把关节角持续发布到/kinematics/joint_statesTopic - 写一个订阅节点,接收关节角并做 FK + round-trip 验证
- 用
ros2 topic echo、ros2 topic hz等 CLI 工具实时观察消息流 - 理解
JointState消息结构和 QoS 基础
从这里开始,节点之间真正开始"说话"。