-
Notifications
You must be signed in to change notification settings - Fork 775
ROS 2 Migration: Diff drive
chapulina edited this page Aug 29, 2018
·
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
:ROS 1 ROS 2 leftJoint
left_joint
rightJoint
right_joint
rightJoint
right_joint
rightJoint
right_joint
rightJoint
right_joint
<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'>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>0.5380</wheelSeparation>
<wheelDiameter>0.3</wheelDiameter>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>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'>
<!-- Replace camelCase elements with camel_case ones -->
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheelSeparation>0.5380</wheelSeparation>
<wheelDiameter>0.3</wheelDiameter>
<torque>20</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
</plugin>
</model>