环境:Ubuntu20.04 ROS-noetic
现象:打开Rviz与Gazebo加载机器人模型时,终端不停刷新警告TF_REPEATED_DATA ignoring data with redundant timestamp for frame
,且在未施加数据的情况下,Rviz中模型车轮有微小移动
ROS的roswtf
工具可以对系统进行安装检查和运行检查。安装完备的ROS系统在未启动roscore
前输出以下信息。
重点在于right_wheel_link
与left_wheel_link
的TF变换有两个发布者:
/gazebo
/robot_state_publisher
产生了冲突
ERROR TF re-parenting contention:
* reparenting of [right_wheel_link] to [base_footprint] by [/gazebo]
* reparenting of [left_wheel_link] to [base_footprint] by [/gazebo]
* reparenting of [left_wheel_link] to [base_link] by [/robot_state_publisher]
* reparenting of [right_wheel_link] to [base_link] by [/robot_state_publisher]
/robot_state_publisher
发布right_wheel_link
与left_wheel_link
TF变换的方式是在launch
文件中:
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
/gazebo
发布right_wheel_link
与left_wheel_link
TF变换的方式是在.xacro
文件中:
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
...
<publishWheelTF>truepublishWheelTF>
<publishWheelJointState>truepublishWheelJointState>
...
plugin>
gazebo>
所谓joint_state_publisher
和robot_state_publisher
是ROS系统中更新机器人状态的两个节点:
joint_state_publisher
:读取由robot_description
定义的URDF文件内的参数,找到所有非固定(non-fixed)关节并将当前关节信息转化为sensor_msgs/JointState
消息发布到话题joint_states
robot_state_publisher
:可以理解为一个tf广播器,订阅话题joint_states
,并根据消息内容计算更新当前机器人的运动学模型,通过tf广播器发布坐标系状态
如果不使用joint_state_publisher
和robot_state_publisher
,Rviz等组件就无法收到最新的机器人全体连杆TF树,因此考虑将差速控制器中的publishWheelTF
和publishWheelJointState
均设置为false
,即可消除冲突
本文收录于《告别Bug》专栏,该专栏记录人工智能领域中各类Bug以备复查,文章形式为:问题背景 + 问题探索 + 问题解决,订阅专栏+关注博主后可通过下方名片联系我进入AI技术交流群帮忙解决问题