ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The gazebo_ros_diff_drive plugin in the gazebo_ros_pkgs for ros2 allows you to control a robot with as many wheels as you want per side. Here is an example for a 8 wheeled vehicle:
<gazebo>
<plugin name='diff_drive' filename='libgazebo_ros_diff_drive_mod.so'>
<ros>
<namespace>/ARGJ801</namespace>
<!--<remapping>cmd_vel:=cmd_demo</remapping>-->
<remapping>odom:=odom_demo</remapping>
</ros>
<!-- wheels -->
<num_wheel_pairs>4</num_wheel_pairs>
<left_joint>jo_w1</left_joint>
<left_joint>jo_w2</left_joint>
<left_joint>jo_w3</left_joint>
<left_joint>jo_w4</left_joint>
<right_joint>jo_w5</right_joint>
<right_joint>jo_w6</right_joint>
<right_joint>jo_w7</right_joint>
<right_joint>jo_w8</right_joint>
<!-- kinematics -->
<wheel_separation>1.35</wheel_separation>
<wheel_diameter>0.64</wheel_diameter>
<!-- limits -->
<max_wheel_torque>500</max_wheel_torque>
<max_wheel_acceleration>2.0</max_wheel_acceleration>
<!-- output -->
<publish_odom>true</publish_odom>
<publish_odom_tf>false</publish_odom_tf>
<publish_wheel_tf>false</publish_wheel_tf>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
</plugin>
</gazebo>