力传感器重力补偿工作流程(优化版)
本文档介绍了如何在基于 ROS 2 的机器人系统中,使用机器学习模型对力/力矩传感器进行重力补偿,并对整体启动体验进行了优化。
✅ 步骤 1:采集数据并训练补偿模型
1.1 采集数据
-
确保机械臂静止,无外力接触。
-
运行数据采集节点:
ros2 run cartesian_controllers_universal_robots record_bias_data.py
将创建文件
~/workspace/calibration_logs/recorded_bias_data.csv
1.2 建议采集多个姿态
-
手动移动机械臂到不同方向/角度。
-
多次运行采集节点,得到多个文件,如:
-
recorded_bias_data1.csv
-
recorded_bias_data2.csv
-
...
-
1.3 合并并训练模型
运行:
ros2 run cartesian_controllers_universal_robots merge_and_train_bias.py
输出模型:
~/workspace/calibration_logs/bias_model.pkl
✅ 步骤 2:启用重力补偿节点(优化版)
2.1 修改启动文件
在 robot.launch.py
中添加:
from launch.actions import TimerAction
force_bias_node = TimerAction(
period=5.0, # 延迟 5 秒启动,确保 TF 树稳定
actions=[
Node(
package="cartesian_controllers_universal_robots",
executable="force_republisher_with_bias.py",
name="force_bias_node",
output="screen",
parameters=[]
)
]
)
并在节点列表中加入 force_bias_node
:
nodes = [rviz, control_node, robot_state_publisher, flange_tf_node, force_bias_node] + active_spawners + inactive_spawners
2.2 验证话题是否发布成功
ros2 topic echo /ft_sensor_wrench_compensated
应看到已经补偿后的力数据。
✅ 步骤 3:更新控制器配置
编辑 controller_manager.yaml
:
cartesian_compliance_controller:
ros__parameters:
ft_sensor_topic: /ft_sensor_wrench_compensated
然后重启控制器或 launch 文件。
✅ 验证效果
对比前后数据:
ros2 topic echo /ft_sensor_wrench_raw
ros2 topic echo /ft_sensor_wrench_compensated
预期结果:
-
raw
包含重力分量 -
compensated
在静止时应接近零
📊 建议技巧
-
姿态越多,模型越准确。
-
使用
scikit-learn
的多项式回归提升拟合效果。 -
确保
base_link
与tool0
的 TF 始终可用且稳定。 -
建议在启动补偿节点时增加 3-5 秒延迟,避免 tf2 查询失败。
📂 文件说明
文件名 | 作用 |
---|---|
record_bias_data.py | 记录传感器数据与姿态 |
merge_and_train_bias.py | 合并 CSV 并训练模型 |
force_republisher_with_bias.py | 发布重力补偿后的力数据 |
bias_model.pkl | 已训练的补偿模型 |
使用本流程,你将获得实时的、经过重力补偿的六维力/力矩数据,可用于高精度的柔顺控制或力控任务!✨