ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Gazebo Diff drive can make the robot stay immobile

asked 2020-06-18 08:05:51 -0600

jGany gravatar image

Hi, I'm trying to build a robot in gazebo9 with Ros2-dashing. I'm using the libgazebo_ros_diff_drive plugin to control the wheels and give instructions to the robot.

The controls work greats and I can move the robot around in the virtual world, but when I don't give cmd_vel (or 0 in all directions) diff drive make the wheels turn slowly, moving the robot. I am almost certain that's diff drive who does the moving, as it won't happen if I remove the plugin (The robot don't slide otherwise ).

  <gazebo>
<plugin name="robot_diff_drive" filename="libgazebo_ros_diff_drive.so">

  <ros>
    <namespace>/drive</namespace>
    <!--<argument>cmd_vel:=cmd_vel</argument>
    <argument>odom:=odom</argument>-->
  </ros>

  <update_rate>30</update_rate>

  <!-- wheels -->
  <left_joint>wheel_left_joint</left_joint>
  <right_joint>wheel_right_joint</right_joint>

  <!-- kinematics -->
  <wheel_separation>0.434</wheel_separation>
  <wheel_diameter>0.2</wheel_diameter>

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

  <command_topic>cmd_vel</command_topic>

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

  <odometry_topic>odom</odometry_topic>
  <odometry_frame>odom</odometry_frame>
  <robot_base_frame>base_footprint</robot_base_frame>

</plugin>

</gazebo>

Here the config of the diff drive, they are mostly the same as the turtlebot3. And the wheels :

    <xacro:macro name="origin_wheel">
        <origin rpy="${rpy}" xyz="${xyz}"/>
    </xacro:macro>

    <link name="wheel_${name}_link">
        <inertial>
            <xacro:origin_base />
            <mass value="${wheel_mass}" />
            <inertia ixx="0.0016" ixy="0" ixz="0" iyy="0.0016" iyz="0" izz="0.003" /><!-- Good value of inertia -->
        </inertial>

        <collision>
            <xacro:origin_base />
            <geometry>
                <cylinder radius="${wheel_radius}" length="${wheel_length}"/>
            </geometry>
        </collision>

        <visual>
            <xacro:origin_base />
            <geometry>
                    <cylinder radius="${wheel_radius}" length="${wheel_length}"/>
            </geometry>
            <material name="green"/>
        </visual>
    </link>
    <gazebo reference="wheel_${name}_link">
        <turnGravityOff>false</turnGravityOff>
        <mu1>10000.0</mu1>
        <mu2>10000.5</mu2>
        <kp value="${kp}" />
        <kd value="${kd}" />
        <material>Gazebo/Gold </material>
    </gazebo>

    <joint name="wheel_${name}_joint" type="continuous">
        <parent link="reverse_footprint_link"/>
        <child link="wheel_${name}_link"/>
        <xacro:origin_wheel />
        <axis xyz="0 0 1"/>
    </joint>

Does anyone know where I can look to found a solution, or what to do to make it work as I need? (Also, I don't know if it's a question better suited to ros answers or gazebo answers :/ )

Thank :)

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-06-18 14:31:14 -0600

Weasfas gravatar image

Hi @jGany,

I am sure this is not a problem of the plugin but you Gazebo contacts. The wheel contacts parameters need to be properly adjusted for Gazebo to produce consistent contact and friction values. Have you checked this tutorials? this and this.

To be more precisse: mu1 and mu2 values are too high. As stated in the SDF specification, those parameters are ratios, hence their values are in between [0,1]. Furthemore, the values kp and kd are used to calculate the ODE inner params called ERP and CFM used to balance the inestability of the simulation. Since I do not know what values are you passing to the the xacro macro I will say try to be consistent with those values. You can learn more about that here.

Usually, you can leave all these values as the defaullt ones, try a simulation iteration and then adjusted them as you may see fit.

Hope that can help you to solve the problem.

Cheers.

edit flag offensive delete link more

Comments

Hi, You were right, when putting back defaults value this problem seems to disappear :) I thought I had tried with this before, but I shifted all the value a lot because of problems at every step, I may not have checked again with this version :/

Anyway, thank you for your help :D

jGany gravatar image jGany  ( 2020-06-19 02:33:06 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2020-06-18 08:05:51 -0600

Seen: 1,021 times

Last updated: Jun 18 '20