问题描述 在ROS Noetic中仿真两轮差速小车时,出现以下错误信息:
1 2 3 4 Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame omni_b_link (parent car_base_link) at time 1488.072000 according to authority unknown_publisher Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame omni_f_link (parent car_base_link) at time 1488.072000 according to authority unknown_publisher Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame wheel_l_link (parent car_base_link) at time 1488.072000 according to authority unknown_publisher Warning: TF_REPEATED_DATA ignoring data with redundant timestamp for frame wheel_r_link (parent car_base_link) at time 1488.072000 according to authority unknown_publisher
同时发现:
/gazebo
发布odom到base_footprint的频率为101.099Hz
/robot_state_publisher
发布后续tf的频率为1000.00Hz
问题根本原因 TF_REPEATED_DATA错误原因 该错误表明有多个发布者在相同时间戳为相同的tf变换发布数据,导致数据冲突。具体原因:
多个控制器冲突 :gazebo_ros_diff_drive
插件和gazebo_ros_control
插件同时控制相同的关节
重复的tf发布 :两个插件都在发布相同关节的tf变换
频率不匹配 :不同发布者的更新频率不一致
Transmission配置的作用 Transmission 是ROS控制系统中定义执行器与关节连接关系的配置:
1 2 3 4 5 6 7 8 9 10 <transmission name ="wheel_l_trans" > <type > transmission_interface/SimpleTransmission</type > <joint name ="wheel_l_joint" > <hardwareInterface > hardware_interface/VelocityJointInterface</hardwareInterface > </joint > <actuator name ="wheel_l_motor" > <hardwareInterface > hardware_interface/VelocityJointInterface</hardwareInterface > <mechanicalReduction > 1</mechanicalReduction > </actuator > </transmission >
工作流程 :
1 2 命令输入 → 控制器 → 传动系统 → 执行器 → 关节 → 链接运动 cmd_vel → diff_drive → transmission → motor → joint → link
解决方案 方案一:使用gazebo_ros_diff_drive(推荐用于简单差分驱动) 1. 删除gazebo_ros_control插件
在主URDF文件中注释或删除:
2. 优化gazebo_ros_diff_drive配置
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 <gazebo > <plugin filename ="libgazebo_ros_diff_drive.so" name ="differential_drive_controller" > <robotNamespace > /</robotNamespace > <rosDebugLevel > Error</rosDebugLevel > <publishWheelTF > false</publishWheelTF > <publishTf > 1</publishTf > <publishOdomTF > 1</publishOdomTF > <odometrySource > world</odometrySource > <publishWheelJointState > true</publishWheelJointState > <alwaysOn > true</alwaysOn > <updateRate > 50.0</updateRate > <legacyMode > true</legacyMode > <leftJoint > wheel_l_joint</leftJoint > <rightJoint > wheel_r_joint</rightJoint > <wheelSeparation > 0.33</wheelSeparation > <wheelDiameter > 0.125</wheelDiameter > <broadcastTF > 1</broadcastTF > <wheelTorque > 6.5</wheelTorque > <wheelAcceleration > 0.5</wheelAcceleration > <commandTopic > cmd_vel</commandTopic > <odometryFrame > odom</odometryFrame > <odometryTopic > odom</odometryTopic > <robotBaseFrame > base_footprint</robotBaseFrame > </plugin > </gazebo >
3. 删除wheel的transmission配置
在wheel_125mm.xacro中注释:
4. 调整robot_state_publisher频率
在launch文件中:
1 2 3 <node name ="robot_state_publisher" pkg ="robot_state_publisher" type ="robot_state_publisher" output ="screen" > <param name ="publish_frequency" type ="double" value ="50.0" /> </node >
方案二:使用gazebo_ros_control(适用于复杂控制需求) 1. 删除gazebo_ros_diff_drive插件
2. 修改gazebo_ros_control配置
1 2 3 4 5 6 7 8 9 <gazebo > <plugin name ="gazebo_ros_control" filename ="libgazebo_ros_control.so" > <robotNamespace > /</robotNamespace > <robotParam > robot_description</robotParam > <robotSimType > gazebo_ros_control/DefaultRobotHWSim</robotSimType > <legacyModeNS > true</legacyModeNS > <updateRate > 50.0</updateRate > </plugin > </gazebo >
3. 修正transmission配置
1 2 3 4 5 6 7 8 9 10 <transmission name ="${wheel_prefix}_wheel_trans" > <type > transmission_interface/SimpleTransmission</type > <joint name ="${wheel_prefix}_joint" > <hardwareInterface > hardware_interface/VelocityJointInterface</hardwareInterface > </joint > <actuator name ="${wheel_prefix}_wheel_motor" > <hardwareInterface > hardware_interface/VelocityJointInterface</hardwareInterface > <mechanicalReduction > 1</mechanicalReduction > </actuator > </transmission >
4. 添加控制器配置
在launch文件中:
1 2 3 <rosparam file ="$(find zeus_s1_description)/config/control.yaml" command ="load" /> <node name ="controller_spawner" pkg ="controller_manager" type ="spawner" respawn ="false" output ="screen" args ="joint_state_controller diff_drive_controller" />
control.yaml文件内容:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 diff_drive_controller: type: diff_drive_controller/DiffDriveController left_wheel: 'wheel_l_joint' right_wheel: 'wheel_r_joint' publish_rate: 50 pose_covariance_diagonal: [0.001 , 0.001 , 1000000.0 , 1000000.0 , 1000000.0 , 1000.0 ] twist_covariance_diagonal: [0.001 , 0.001 , 1000000.0 , 1000000.0 , 1000000.0 , 1000.0 ] wheel_separation: 0.33 wheel_radius: 0.0625 base_frame_id: base_footprint odom_frame_id: odom
调试和验证方法 检查TF发布状态 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 rosrun tf view_frames evince frames.pdf rosrun tf tf_monitor odom base_footprint rosrun tf tf_echo odom base_footprint rosnode list | grep -E "(robot_state_publisher|gazebo)" rostopic echo /tf | grep frame_id
验证关节状态发布 1 2 3 4 5 6 rostopic echo /joint_states rostopic hz /joint_states rostopic hz /tf
最佳实践建议 何时使用Transmission配置 需要使用的场景 :
复杂控制需求(PID调节、轨迹跟踪)
多种控制模式切换(位置、速度、力矩)
存在机械减速的真实情况
自定义控制器开发
多关节协调控制(如机械臂)
不需要使用的场景 :
频率同步建议
统一更新频率 :将所有相关组件设置为相同频率(推荐50-100Hz)
避免过高频率 :1000Hz通常不必要,会增加计算负担
渐进调试 :从低频率开始,逐步优化
总结 对于简单的差分驱动机器人仿真,推荐使用方案一 (gazebo_ros_diff_drive),因为:
配置简单 :无需复杂的transmission和控制器配置
功能完整 :自动处理差分驱动逻辑和里程计
稳定可靠 :减少配置冲突的可能性
易于调试 :问题定位更直接
TF_REPEATED_DATA错误的核心是避免多个发布者控制相同的关节,选择合适的控制架构是关键。
Reference