ROS TF_REPEATED_DATA ignoring data with redundant timestamp for frame base_footprint at tim

<1>问题描述
遇到TF_REPEATED_DATA ignoring data with redundant timestamp for frame base_footprint at time 406.616000 according to authority unknown_publisher
警告

map odom base_footprint这些坐标系发布的频率不一致导致的,比如odom更新快,base_footprint还没更新就会获取不到相对位姿的情况,解决方案如下。

<2>解决方案:

关键步骤1:launch中增加下段代码,保持频率10000hz一致

<node pkg="tf" type="static_transform_publisher" name="odom_to_base_footprint" args="0.0 0.0 0.0 0 0 0.0 /odom /base_footprint 10000"/>

关键步骤2:其次 move.xacro文件修改下面三行

        <publishWheelTF>false</publishWheelTF>

        <publishWheelJointState>false</publishWheelJointState>

        <updateRate>10</updateRate>

完整代码段如下:

<!-- 传动实现:用于连接控制器与关节 -->
<xacro:macro name="joint_trans" params="joint_name">
    <!-- Transmission is important to link the joints and the controller -->
    <transmission name="${joint_name}_trans">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${joint_name}">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
        </joint>
        <actuator name="${joint_name}_motor">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
</xacro:macro>

<!-- 每一个驱动轮都需要配置传动装置 -->
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" />

<!-- 控制器 -->
<gazebo>
    <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
        <rosDebugLevel>Debug</rosDebugLevel>
        <publishWheelTF>false</publishWheelTF>
        <robotNamespace>/</robotNamespace>
        <publishTf>1</publishTf>
        <publishWheelJointState>false</publishWheelJointState>
        <publishOdomTF>true</publishOdomTF>
        <alwaysOn>true</alwaysOn>
        <updateRate>10.0</updateRate>
        <legacyMode>true</legacyMode>
        <leftJoint>left_wheel2base_link</leftJoint> <!-- 左轮 -->
        <rightJoint>right_wheel2base_link</rightJoint> <!-- 右轮 -->
        <wheelSeparation>${base_link_radius * 2}</wheelSeparation> <!-- 车轮间距 -->
        <wheelDiameter>${wheel_radius * 2}</wheelDiameter> <!-- 车轮直径 -->
        <broadcastTF>1</broadcastTF>
        <wheelTorque>30</wheelTorque>
        <wheelAcceleration>1.8</wheelAcceleration>
        <commandTopic>cmd_vel</commandTopic> <!-- 运动控制话题 -->
        <odometryFrame>odom</odometryFrame> 
        <odometryTopic>odom</odometryTopic> <!-- 里程计话题 -->
        <odometrySource>world</odometrySource>
        <robotBaseFrame>base_footprint</robotBaseFrame> <!-- 根坐标系 -->
    </plugin>
</gazebo>
<node pkg="joint_state_publisher" type="joint_state_publisher"name="joint_state_publisher" output="screen" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" output="screen" />

注意:因为启动rviz中已经启动了两个发布节点所以将次两项设为false

        <publishWheelJointState>false</publishWheelJointState>

        <publishWheelTF>false</publishWheelTF>
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值