-
Notifications
You must be signed in to change notification settings - Fork 773
ROS 2 Migration: Tricycle drive
Leander Stephen D'Souza edited this page Jun 26, 2022
·
3 revisions
This page describes the changes in the tricycle drive plugin in gazebo_plugins
for ROS 2, including a migration guide.
- All SDF parameters are now
snake_cased
- Use remapping argument to change default topics (
cmd_vel
,odom
,joint_states
)
ROS 1 | ROS 2 |
---|---|
actuatedWheelDiameter |
actuated_wheel_diameter |
encoderWheelDiameter |
encoder_wheel_diameter |
wheelTorque |
max_wheel_torque |
odometryFrame |
odometry_frame |
robotBaseFrame |
robot_base_frame |
updateRate |
update_rate |
wheelAcceleration |
max_wheel_acceleration |
wheelDeceleration |
max_wheel_deceleration |
wheelSpeedTolerance |
max_wheel_speed_tolerance |
steeringSpeed |
max_steering_speed |
steeringAngleTolerance |
max_steering_angle_tolerance |
encoderWheelSeparation |
wheel_separation |
publishWheelTF |
publish_wheel_tf |
publishWheelJointState |
publish_wheel_joint_state |
steeringJoint |
steering_joint |
actuatedWheelJoint |
actuated_wheel_joint |
encoderWheelLeftJoint |
encoder_wheel_left_joint |
encoderWheelRightJoint |
encoder_wheel_right_joint |
odometrySource |
odometry_source |
commandTopic |
<ros><remapping>cmd_vel:=custom_cmd_vel</remapping></ros> |
odometryTopic |
<ros><remapping>odom:=custom_odom</remapping></ros> |
<model name='tricycle'>
...
<joint name='front_steering_joint' type='revolute'>
...
</joint>
<joint name='front_wheel_joint' type='revolute'>
...
</joint>
<joint name='left_wheel_joint' type='revolute'>
...
</joint>
<joint name='right_wheel_joint' type='revolute'>
...
</joint>
<plugin name="tricycle_drive_controller" filename="libgazebo_ros_tricycle_drive.so">
<robotNamespace>demo</robotNamespace>
<commandTopic>cmd_demo</commandTopic>
<odometryTopic>odom_demo</odometryTopic>
<updateRate>10.0</updateRate>
<!-- joints -->
<steeringJoint>front_steering_joint</steeringJoint>
<actuatedWheelJoint>front_wheel_joint</actuatedWheelJoint>
<encoderWheelLeftJoint>left_wheel_joint</encoderWheelLeftJoint>
<encoderWheelRightJoint>right_wheel_joint</encoderWheelRightJoint>
<publishWheelTF>false</publishWheelTF>
<publishWheelJointState>true</publishWheelJointState>
<!-- kinematics -->
<actuatedWheelDiameter>0.135</actuatedWheelDiameter>
<encoderWheelDiameter>0.135</encoderWheelDiameter>
<encoderWheelSeparation>0.548</encoderWheelSeparation>
<odometryFrame>odom</odometryFrame>
<odometrySource>encoder</odometrySource>
<robotBaseFrame>base_link</robotBaseFrame>
<!-- limits -->
<wheelAcceleration>1.8</wheelAcceleration>
<wheelDeceleration>5.0</wheelDeceleration>
<wheelSpeedTolerance>0.05</wheelSpeedTolerance>
<wheelTorque>20</wheelTorque>
<steeringSpeed>0.4</steeringSpeed>
<steeringAngleTolerance>0.02</steeringAngleTolerance>
</plugin>
</model>
<model name='tricycle'>
...
<joint name='front_steering_joint' type='revolute'>
...
</joint>
<joint name='front_wheel_joint' type='revolute'>
...
</joint>
<joint name='left_wheel_joint' type='revolute'>
...
</joint>
<joint name='right_wheel_joint' type='revolute'>
...
</joint>
<plugin name='tricycle_drive_controller' filename='libgazebo_ros_tricycle_drive.so'>
<ros>
<!-- Set namespace -->
<namespace>/demo</namespace>
<!-- Remap default topics -->
<remapping>cmd_vel:=cmd_demo</remapping>
<remapping>odom:=odom_demo</remapping>
<remapping>joint_states:=joints_demo</remapping>
</ros>
<update_rate>10.0</update_rate>
<!-- Joints -->
<steering_joint>front_steering_joint</steering_joint>
<actuated_wheel_joint>front_wheel_joint</actuated_wheel_joint>
<encoder_wheel_left_joint>left_wheel_joint</encoder_wheel_left_joint>
<encoder_wheel_right_joint>right_wheel_joint</encoder_wheel_right_joint>
<publish_wheel_tf>false</publish_wheel_tf>
<publish_wheel_joint_state>true</publish_wheel_joint_state>
<!-- kinematics -->
<actuated_wheel_diameter>0.135</actuated_wheel_diameter>
<encoder_wheel_diameter>0.135</encoder_wheel_diameter>
<wheel_separation>0.548</wheel_separation>
<odometry_source>0</odometry_source>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<!-- limits -->
<max_wheel_acceleration>1.8</max_wheel_acceleration>
<max_wheel_deceleration>5.0</max_wheel_deceleration>
<max_wheel_speed_tolerance>0.05</max_wheel_speed_tolerance>
<max_wheel_torque>20</max_wheel_torque>
<max_steering_speed>0.4</max_steering_speed>
<max_steering_angle_tolerance>0.02</max_steering_angle_tolerance>
</plugin>
</model>