<robot xmlns:xacro="http://ros.org/wiki/xacro">
<!-- 定义传动实现宏 -->
<xacro:macro name="joint_trans" params="joint_name">
<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="joint_left_front" />
<xacro:joint_trans joint_name="joint_left_back" />
<xacro:joint_trans joint_name="joint_right_front" />
<xacro:joint_trans joint_name="joint_right_back" />
<!-- 添加差速驱动控制插件 -->
<gazebo>
<plugin name="differential_drive_controller_front" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>na</rosDebugLevel>
<publishWheelTF>false</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>true</publishTf>
<publishWheelJointState>false</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>joint_left_front</leftJoint>
<rightJoint>joint_right_front</rightJoint>
<wheelSeparation>${shaft_spacing_f + shaft_spacing_b}</wheelSeparation>
<wheelDiameter>0.254</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>50</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<odometrySource>world</odometrySource>
<robotBaseFrame>base_footprint</robotBaseFrame>
<publishOdomTF>true</publishOdomTF>
</plugin>
</gazebo>
<gazebo>
<plugin name="differential_drive_controller_back" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>na</rosDebugLevel>
<publishWheelTF>false</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>true</publishTf>
<publishWheelJointState>false</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>30.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>joint_left_back</leftJoint>
<rightJoint>joint_right_back</rightJoint>
<wheelSeparation>${shaft_spacing_f + shaft_spacing_b}</wheelSeparation>
<wheelDiameter>0.254</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>50</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<odometrySource>world</odometrySource>
<robotBaseFrame>base_footprint</robotBaseFrame>
<publishOdomTF>true</publishOdomTF>
</plugin>
</gazebo>
</robot>
为四轮驱动的机器人定义了前后两个差速驱动控制插件,会有这样的警告信息[ WARN] [1718978018.120461363, 41.720000000]: TF_REPEATED_DATA ignoring data with redundant timestamp for frame base_footprint (parent odom) at time 41.720000 according to authority unknown_publisher
我的测试中删除其中一个 <publishOdomTF>true</publishOdomTF> 标签似乎没有用,可能是因为即使标签未明确设置,默认行为仍会导致重复发布。需要将其中一个改为false,就不会再不停地刷上面的警告了
修改其中一个 <publishOdomTF>true</publishOdomTF>
标签不会影响 odom
坐标系的位置,因为里程计数据的发布只需要一个插件进行。只要有一个插件在正确发布 odom
坐标系的变换,机器人在仿真中的行为和里程计数据的计算不会受到影响。
-
前后两个差速驱动插件分别控制左右前后两侧的轮子,前后轮的左侧轮子用一个插件控制,右侧轮子由另一个插件控制。因此,实际运动上相当于将左侧的前后轮视为一个整体,右侧的前后轮视为一个整体。这样,小车实际上是在模拟通过左右两个虚拟轮子(左侧和右侧各一组)实现差速运动。
-
差速驱动系统的原理是通过控制左右两侧的轮子的速度差来实现前进、后退和转向。因此,即使四轮模型中使用了两个差速驱动插件(分别控制前后轮),从整体运动学角度来看,仍然符合经典的二轮差速驱动运动模型。
-
对于 Gazebo 仿真而言,这种配置会让左侧的两个轮子和右侧的两个轮子同步运转,实现与现实中二轮差速机器人类似的行为。在仿真中,可以认为小车通过差速控制左侧和右侧的“虚拟轮子”(即前后轮同步运动)来实现运动控制。