-
Notifications
You must be signed in to change notification settings - Fork 773
ROS 2 Migration: Diff drive
Leander Stephen D'Souza edited this page Jun 26, 2022
·
10 revisions
This pages describes the changes the diff drive plugin in gazebo_plugins
for ROS 2, including a migration guide.
-
<publishWheelJointState>
has been removed. Use thegazebo_ros_joint_state_publisher
plugin instead. - All SDF parameters are now
snake_cased
- Use remapping argument to change default topics (
cmd_vel
andodom
)
ROS 1 | ROS 2 |
---|---|
leftJoint |
left_joint |
rightJoint |
right_joint |
wheelSeparation |
wheel_separation |
wheelDiameter |
wheel_diameter |
odometryFrame |
odometry_frame |
udpateRate |
update_rate |
wheelTorque |
max_wheel_torque |
wheelAcceleration |
max_wheel_acceleration |
publishOdom |
publish_odom |
commandTopic |
<ros><remapping>cmd_vel:=custom_cmd_vel</remapping></ros> |
odometryTopic |
<ros><remapping>odom:=custom_odom</remapping></ros> |
publishWheelJointState |
❌ |
<model name='vehicle'>
...
<joint name='left_wheel_joint' type='revolute'>
...
</joint>
<joint name='right_wheel_joint' type='revolute'>
...
</joint>
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
<updateRate>500</updateRate>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>1.25</wheelSeparation>
<wheelDiameter>0.3</wheelDiameter>
<wheelTorque>20</wheelTorque>
<wheelAcceleration>1.0</wheelAcceleration>
<commandTopic>custom_cmd_vel</commandTopic>
<odometryTopic>custom_odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<publishWheelJointState>true</publishWheelJointState>
</plugin>
</model>
<model name='vehicle'>
...
<joint name='left_wheel_joint' type='revolute'>
...
</joint>
<joint name='right_wheel_joint' type='revolute'>
...
</joint>
<!-- Use gazebo_ros_joint_state_publisher instead of publishWheelJointState -->
<plugin name="joint_states" filename="libgazebo_ros_joint_state_publisher.so">
<joint_name>right_wheel_joint</joint_name>
<joint_name>left_wheel_joint</joint_name>
</plugin>
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
<ros>
<!-- Set namespace -->
<namespace>/demo</namespace>
<!-- Remap default topics -->
<remapping>cmd_vel:=cmd_demo</remapping>
<remapping>odom:=odom_demo</remapping>
</ros>
<!-- Replace camelCase elements with camel_case ones -->
<update_rate>500</update_rate>
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.25</wheel_separation>
<wheel_diameter>0.3</wheel_diameter>
<odometry_frame>odom</odometry_frame>
<!-- wheelTorque and wheelAcceleration now have max_ prefix -->
<max_wheel_torque>20</max_wheel_torque>
<max_acceleration>1.0</max_acceleration>
</plugin>
</model>