DiffDrive plugin steering issue

Hi everyone,
I currently have a problem with angular rotation when using the gz::sim::systems::DiffDrive plugin.
The gz.msgs.Twist msg looks fine and I have tried different wheel friction values. However, it doesnt look like friction is the issue since linear motion is fine.

Here is the video

and the model.sdf file

<?xml version="1.0" encoding="utf-8"?>
<sdf version='1.9'>
  <model name='scout_mini'>
    <static>false</static>
    <pose>0 0 0.182 0 0 0</pose>
    <link name='base_link'>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>60</mass>
        <inertia>
          <ixx>2.28864</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>5.10398</iyy>
          <iyz>0</iyz>
          <izz>3.43147</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'>
        <pose>0 0 0 1.57 -0 -1.57</pose>
        <geometry>
            <box>
              <size>0.5 0.3 0.2</size>
            </box>
        </geometry>
      </collision>
      <visual name='base_link_visual'>
        <pose>0 0 0 1.57 -0 -1.57</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/scout_mini_base_link2.dae</uri>
          </mesh>
        </geometry>
      </visual>
      <!-- IMU/MAG {-->
      <sensor name='imu_sensor' type='imu'>
        <always_on>true</always_on>
        <update_rate>250</update_rate>
        <gyroscopeNoiseDensity>0.00018665</gyroscopeNoiseDensity>
        <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
        <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
        <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
        <accelerometerNoiseDensity>0.00186</accelerometerNoiseDensity>
        <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
        <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
        <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
      </sensor>
      <sensor name='magnetometer_sensor' type='magnetometer'>
        <always_on>true</always_on>
        <update_rate>100</update_rate>
        <visualize>false</visualize>
        <enable_metrics>false</enable_metrics>
        <magnetometer>
          <x>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>0.1</stddev>
            </noise>
          </x>
          <y>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>0.1</stddev>
            </noise>
          </y>
          <z>
            <noise type="gaussian">
              <mean>0.0</mean>
              <stddev>0.1</stddev>
            </noise>
          </z>
        </magnetometer>
      </sensor>
      <!--} END IMU/MAG -->
    </link>
    <joint name='front_left_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>0.231976 0.208252 -0.100998 -1.57 0 0</pose>
      <parent>base_link</parent>
      <child>front_left_wheel_link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='front_left_wheel_link'>
      <pose relative_to='front_left_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>3</mass>
        <inertia>
          <ixx>0.7171</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.7171</iyy>
          <iyz>0</iyz>
          <izz>0.1361</izz>
        </inertia>
      </inertial>
      <collision name='front_left_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.0775</radius>
          </sphere>
        </geometry>
        <max_contacts>1</max_contacts>
        <surface>
          <friction>
            <ode>
              <mu>0.5</mu>
              <mu2>0.5</mu2>
              <slip1>0.0016</slip1>
              <slip2>0</slip2>
              <fdir1>0 0 1</fdir1>
            </ode>
          </friction>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0.0</max_vel>
              <kp>1.0e7</kp>
              <kd>1.0</kd>
            </ode>
          </contact>
        </surface>
      </collision>
      <visual name='front_left_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='front_right_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>0.231976 -0.208252 -0.099998 1.57 -0 0</pose>
      <parent>base_link</parent>
      <child>front_right_wheel_link</child>
      <axis>
        <xyz>0 0 -1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='front_right_wheel_link'>
      <pose relative_to='front_right_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>3</mass>
        <inertia>
          <ixx>0.7171</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.7171</iyy>
          <iyz>0</iyz>
          <izz>0.1361</izz>
        </inertia>
      </inertial>
      <collision name='front_right_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.0775</radius>
          </sphere>
        </geometry>
        <max_contacts>1</max_contacts>
        <surface>
          <friction>
            <ode>
              <mu>0.5</mu>
              <mu2>0.5</mu2>
              <slip1>0.0016</slip1>
              <slip2>0</slip2>
              <fdir1>0 0 1</fdir1>
            </ode>
          </friction>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0.0</max_vel>
              <kp>1.0e7</kp>
              <kd>1.0</kd>
            </ode>
          </contact>
        </surface>
      </collision>
      <visual name='front_right_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='rear_left_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>-0.231976 0.208252 -0.100998 -1.57 0 0</pose>
      <parent>base_link</parent>
      <child>rear_left_wheel_link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='rear_left_wheel_link'>
      <pose relative_to='rear_left_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>3</mass>
        <inertia>
          <ixx>0.7171</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.7171</iyy>
          <iyz>0</iyz>
          <izz>0.1361</izz>
        </inertia>
      </inertial>
      <collision name='rear_left_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.0775</radius>
          </sphere>
        </geometry>
        <max_contacts>1</max_contacts>
        <surface>
          <friction>
            <ode>
              <mu>0.5</mu>
              <mu2>0.5</mu2>
              <slip1>0.0016</slip1>
              <slip2>0</slip2>
              <fdir1>0 0 1</fdir1>
            </ode>
          </friction>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0.0</max_vel>
              <kp>1.0e7</kp>
              <kd>1.0</kd>
            </ode>
          </contact>
        </surface>
      </collision>
      <visual name='rear_left_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='rear_right_wheel_joint' type='revolute'>
      <pose relative_to='base_link'>-0.231976 -0.208252 -0.099998 1.57 -0 0</pose>
      <parent>base_link</parent>
      <child>rear_right_wheel_link</child>
      <axis>
        <xyz>0 0 -1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='rear_right_wheel_link'>
      <pose relative_to='rear_right_wheel_joint'>0 0 0 0 -0 0</pose>
      <inertial>
        <pose>0 0 0 0 -0 0</pose>
        <mass>3</mass>
        <inertia>
          <ixx>0.7171</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.7171</iyy>
          <iyz>0</iyz>
          <izz>0.1361</izz>
        </inertia>
      </inertial>
      <collision name='rear_right_wheel_link_collision'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <sphere>
            <radius>0.0775</radius>
          </sphere>
        </geometry>
        <max_contacts>1</max_contacts>
        <surface>
          <friction>
            <ode>
              <mu>0.5</mu>
              <mu2>0.5</mu2>
              <slip1>0.0016</slip1>
              <slip2>0</slip2>
              <fdir1>0 0 1</fdir1>
            </ode>
          </friction>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0.0</max_vel>
              <kp>1.0e7</kp>
              <kd>1.0</kd>
            </ode>
          </contact>
        </surface>
      </collision>
      <visual name='rear_right_wheel_link_visual'>
        <pose>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/wheel.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <static>0</static>

    <!-- GPS {-->
    <link name='gps1_link'>
      <pose>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0 0 0 0 0 0</pose>
        <mass>0.01</mass>
        <inertia>
          <ixx>2.1733e-06</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>2.1733e-06</iyy>
          <iyz>0</iyz>
          <izz>1.8e-07</izz>
        </inertia>
      </inertial>
      <visual name='visual'>
        <geometry>
          <cylinder>
            <radius>0.01</radius>
            <length>0.002</length>
          </cylinder>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Black</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <sensor name='gps' type='navsat'>
        <pose>0 0 0 0 0 0</pose>
        <always_on>true</always_on>
        <update_rate>10</update_rate>
        <gpsNoise>1</gpsNoise>
        <gpsXYRandomWalk>2.0</gpsXYRandomWalk>
      </sensor>
    </link>
    <joint name='gps1_joint' type='fixed'>
      <parent>base_link</parent>
      <child>gps1_link</child>
    </joint>
    <!--} END GPS -->

    <!-- RP Lidar {-->
    <link name="2d_scanner_link">
      <pose>0 0 0.089 0 0 0</pose>
      <inertial>
        <mass>0.01</mass>
        <inertia>
          <ixx>0.000166667</ixx>
          <iyy>0.000166667</iyy>
          <izz>0.000166667</izz>
        </inertia>
      </inertial>
      <sensor name='rplidar' type='gpu_lidar'>
        <always_on>true</always_on>
        <update_rate>20</update_rate>
        <visualize>false</visualize>
        <lidar>
          <scan>
            <horizontal>
              <samples>720</samples>
              <resolution>1</resolution>
              <min_angle>-3.1241390751</min_angle>
              <max_angle>3.1241390751</max_angle>
            </horizontal>
            <vertical>
              <samples>1</samples>
              <resolution>1</resolution>
              <min_angle>0.0</min_angle>
              <max_angle>0.0</max_angle>
            </vertical>
          </scan>
          <range>
            <min>0.15</min>
            <max>14</max>
            <resolution>0.01</resolution>
          </range>
        </lidar>
      </sensor>
      <visual name='rplidar_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>meshes/rplidar.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <joint name='2d_scanner_joint' type='fixed'>
      <child>2d_scanner_link</child>
      <parent>base_link</parent>
    </joint>
    <!--} END RP Lidar -->

    <!-- CAMERA {-->
    <link name="camera_link">
      <inertial>
        <mass>0.01</mass>
        <inertia>
          <ixx>0.000166667</ixx>
          <iyy>0.000166667</iyy>
          <izz>0.000166667</izz>
        </inertia>
      </inertial>
      <collision name="collision">
        <geometry>
          <box>
            <size>0.01 0.01 0.01</size>
          </box>
        </geometry>
      </collision>
      <visual name="visual">
        <geometry>
          <box>
            <size>0.01 0.01 0.01</size>
          </box>
        </geometry>
      </visual>
      <sensor name="ugv-camera" type="camera">
        <camera>
          <horizontal_fov>1.047</horizontal_fov>
          <image>
            <width>1280</width>
            <height>720</height>
          </image>
          <clip>
            <near>0.1</near>
            <far>100</far>
          </clip>
        </camera>
        <always_on>true</always_on>
        <update_rate>30</update_rate>
        <visualize>true</visualize>
      </sensor>
    </link>
    <joint name='camera_joint' type='fixed'>
      <child>camera_link</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
          <effort>0</effort>
          <velocity>0</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <!--} END CAMERA -->

    <!-- Plugins {-->
    <!-- diff drive plugin :
    1. drive the robot with cmd_vel (PX4 mode: throttle and steering from PX4
      via gz_bridge masqueraded as cmd_vel from PX4 via gz_bridge)
    2. publish odom /robot_name/odom -> /robot_name (PX4 mode: not used since
      PX4 publishes odom)
    -->
    <plugin
      filename="gz-sim-diff-drive-system"
      name="gz::sim::systems::DiffDrive">
      <left_joint>front_left_wheel_joint</left_joint>
      <left_joint>rear_left_wheel_joint</left_joint>
      <right_joint>front_right_wheel_joint</right_joint>
      <right_joint>rear_right_wheel_joint</right_joint>
      <wheel_separation>0.49</wheel_separation>
      <wheel_radius>0.0775</wheel_radius>
      <max_linear_acceleration>1</max_linear_acceleration>
      <min_linear_acceleration>-1</min_linear_acceleration>
      <max_angular_acceleration>2</max_angular_acceleration>
      <min_angular_acceleration>-2</min_angular_acceleration>
      <max_linear_velocity>0.5</max_linear_velocity>
      <min_linear_velocity>-0.5</min_linear_velocity>
      <max_angular_velocity>1</max_angular_velocity>
      <min_angular_velocity>-1</min_angular_velocity>
      <frame_id>scout_mini/odom</frame_id>
      <child_frame_id>scout_mini/base_link</child_frame_id>
    </plugin>
    <plugin
      filename="gz-sim-joint-state-publisher-system"
      name="gz::sim::systems::JointStatePublisher">
    </plugin>
    <!-- <plugin
      filename="gz-sim-pose-publisher-system"
      name="gz::sim::systems::PosePublisher">
      <publish_link_pose>true</publish_link_pose>
      <publish_nested_model_pose>true</publish_nested_model_pose>
      <use_pose_vector_msg>true</use_pose_vector_msg>
      <static_publisher>true</static_publisher>
      <static_update_frequency>1</static_update_frequency>
    </plugin>
    <plugin
      filename="gz-sim-odometry-publisher-system"
      name="gz::sim::systems::OdometryPublisher">
      <dimensions>3</dimensions>
    </plugin> -->
  </model>
</sdf>

Appreciate any help!

It’s weird your wheel collisions are spheres. I’d try switching them to cylinders. That might help.

I just changed that. It still couldnt rotate. But now it moves back or forward when I give steering commands.

the same issue is also present in the Ackerman drive plugin in the case of Gazebo Classic. Try to make mesh file simpler, this has solved my issue.

thanks for all replies. It turned out that it works with gz-garden in ubuntu 22.04 but not the one in 20.04. Maybe there were some new patches to the physics or diffdrive plugin in the 22.04 debs idk…