Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ros2] Port skid_steer_drive to ROS2 #927

Merged
merged 5 commits into from
Jun 19, 2019

Conversation

shiveshkhaitan
Copy link

Differential drive plugin has been modified to integrate skid steer drive into it. Any number of wheel pairs (1: diff drive, 2: skid_steer_drive or greater than 2) can be specified in the sdf and accordingly the joint names, wheel separations, and wheel diameters have to be specified.
Example:

      <plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>

        <ros>
          <namespace>/demo</namespace>
          <argument>cmd_vel:=cmd_demo</argument>
          <argument>odom:=odom_demo</argument>
        </ros>

        <!-- Number of wheel pairs -->
        <num_wheel_pairs>2</num_wheel_pairs>
        
        <!-- wheels0 -->
        <left_joint0>left_wheel_joint0</left_joint0>
        <right_joint0>right_wheel_joint0</right_joint0>
        
        <!-- wheels1-->
        <left_joint1>left_wheel_joint1</left_joint1>
        <right_joint1>right_wheel_joint1</right_joint1>

        <!-- kinematics -->
        <wheel_separation0>1.25</wheel_separation0>
        <wheel_separation1>1.25</wheel_separation1>

        <wheel_diameter0>1.0</wheel_diameter0>
        <wheel_diameter1>0.6</wheel_diameter1>

        <!-- limits -->
        <max_wheel_torque>20</max_wheel_torque>
        <max_wheel_acceleration>1.0</max_wheel_acceleration>

        <!-- output -->
        <publish_odom>true</publish_odom>
        <publish_odom_tf>true</publish_odom_tf>
        <publish_wheel_tf>true</publish_wheel_tf>

        <odometry_frame>odom_demo</odometry_frame>
        <robot_base_frame>chassis</robot_base_frame>

      </plugin>

Here there are 2 wheel pairs specified. Thus it will behave as skid steer drive. Similarly any number can be specified for num_wheel_pairs. The joint names, wheel separations, and wheel diameter for each pair has to be specified with their index number appended to the base tag.

For example <wheel_separation3> specifies the spacing for <left_joint3> and <right_joint3> and so. The indexing starts from 0 to (num_wheel_pairs - 1).

Integrate skid steer drive into diff drive
@chapulina chapulina self-assigned this May 28, 2019
@chapulina chapulina added the ros2 label May 28, 2019
Copy link
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Works for me, and I love the demo vehicle!

skid

Mind adding a note to the wiki about migrating the skid steer plugin?

Also, don't forget to remove the skid steer files from .ros1_unported.

gazebo_plugins/src/gazebo_ros_diff_drive.cpp Show resolved Hide resolved
gazebo_plugins/worlds/gazebo_ros_diff_drive_demo.world Outdated Show resolved Hide resolved
@shiveshkhaitan
Copy link
Author

Migration guide is available at ROS 2 Migration: Skid Steer drive

Copy link
Contributor

@chapulina chapulina left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Works great for me, thanks for iterating 😄

@chapulina chapulina merged commit fa09083 into ros-simulation:ros2 Jun 19, 2019
@shiveshkhaitan shiveshkhaitan deleted the skid_steer_drive branch June 22, 2019 07:48
@LihanChen2004
Copy link

LihanChen2004 commented Jan 21, 2024

May I ask if the modified controller supports translational movement similar to the 4WD Mecanum?

I used the description file of nexus_4wd_mecanum_simulator and replace the original control plugin with the libgazebo_ros_diff_drive.so plugin in ROS2 Humble. However, it seems to have some directional issues.

When I send a clockwise rotation command, it actually moves forward.
Moreover, there is no movement at all when I issue left or right translation commands.

<gazebo>
<plugin name='skid_steer_drive' filename='libgazebo_ros_diff_drive.so'>
    <ros>
      <namespace>/</namespace>
      <remapping>cmd_vel:=cmd_vel</remapping>
      <remapping>odom:=odom</remapping>
    </ros>

    <num_wheel_pairs>2</num_wheel_pairs>

    <left_joint>lower_left_wheel_joint</left_joint>
    <right_joint>lower_right_wheel_joint</right_joint>

    <left_joint>upper_left_wheel_joint</left_joint>
    <right_joint>upper_right_wheel_joint</right_joint>

    <wheel_separation>0.6</wheel_separation>
    <wheel_separation>0.6</wheel_separation>

    <wheel_diameter>0.4</wheel_diameter>
    <wheel_diameter>0.4</wheel_diameter>

    <max_wheel_torque>3</max_wheel_torque>
    <max_wheel_acceleration>6.0</max_wheel_acceleration>

    <publish_odom>false</publish_odom>
    <publish_odom_tf>false</publish_odom_tf>
    <publish_wheel_tf>true</publish_wheel_tf>
    <odometry_frame>odom</odometry_frame>
    <robot_base_frame>base</robot_base_frame>

</plugin>
</gazebo>

4WD Mecanum

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants