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

Four-Wheeled Skid Steering in Gazebo and ROS using gazebo-ros-control

asked 2016-10-31 20:08:14 -0500

Mahmoud Abdul Galil gravatar image

updated 2016-10-31 20:09:05 -0500

I having an issue simulating skid steering on a four wheeled rover on gazebo. The issue is that at 90 degrees and multiplicates, the rover seems to get stuck at the axis .. Here's a video showing the issue: video

Here's also the URDF i'm using for the wheels:

  <?xml version="1.0"?>
  <robot name="wheel" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <property name="M_PI" value="3.1415926535897931" />
  <property name="M_PI_2" value="1.570796327" />
  <property name="DEG_TO_RAD" value="0.017453293" />
  <!-- Wheels -->
  <property name="wheel_radius" value="0.10" />
  <property name="wheel_height" value="0.07" />
  <property name="wheel_mass" value="0.5" /> <!-- in kg-->
  <property name="base_x_origin_to_wheel_origin" value="0.25" />
  <property name="base_y_origin_to_wheel_origin" value="0.3" />
  <property name="base_z_origin_to_wheel_origin" value="0.0" />
  <macro name="cylinder_inertia" params="m r h">
    <inertia  ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
              iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
              izz="${m*r*r/2}" />
  </macro>
  <xacro:macro name="wheel" params="fb lr parent translateX translateY flipY"> <!--fb : front, back ; lr: left, right -->
    <link name="${fb}_${lr}_wheel">
      <visual>
        <origin xyz="0 0 0" rpy="${flipY*M_PI/2} 0  0 " />
        <geometry>
          <cylinder length="${wheel_height}" radius="${wheel_radius}" />
        </geometry>
        <material name="DarkGray" />
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="${flipY*M_PI/2} 0 0 " />
        <geometry>
          <cylinder length="${wheel_height}" radius="${wheel_radius}" />
        </geometry>
      </collision>
      <inertial>
        <mass value="${wheel_mass}" />
        <origin xyz="0 0 0" />
        <cylinder_inertia  m="${wheel_mass}" r="${wheel_radius}" h="${wheel_height}" />
      </inertial>
    </link>
    <gazebo reference="${fb}_${lr}_wheel">
        <kp value="100000000.0"/>
        <kd value="1"/>
        <minDepth value="0.005"/>
        <mu1 value="1"/> <!-- 2.0 -->
        <mu2 value="1"/> <!-- 0.5 -->
        <fdir1 value="1 0 0"/>
        <material>Gazebo/Black</material>
        <turnGravityOff>false</turnGravityOff>
        <dampingFactor>0.01</dampingFactor>
    </gazebo>
    <joint name="${fb}_${lr}_wheel_joint" type="continuous">
      <parent link="${parent}"/>
      <child link="${fb}_${lr}_wheel"/>
      <origin xyz="${translateX} ${translateY} ${base_z_origin_to_wheel_origin}" rpy="0 0 0" />
      <axis xyz="0 1 0" rpy="0  0" />
      <limit effort="100" velocity="100"/>
    </joint>
    <!-- Transmission is important to link the joints and the controller -->
    <transmission name="${fb}_${lr}_wheel_joint_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${fb}_${lr}_wheel_joint">
           <hardwareInterface>VelocityJointInterface</hardwareInterface>
      </joint>
      <actuator name="${fb}_${lr}_wheel_joint_motor">
        <hardwareInterface>VelocityJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
        <motorTorqueConstant>1</motorTorqueConstant>
      </actuator>
    </transmission>
  </xacro:macro>
</robot>

Has anyone been able to get pass this issue? I have a guess that it is related to the friction coefficients, but i tried a lot of things and didn't seem to work out. Any ideas?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2016-11-01 11:14:12 -0500

lucasw gravatar image

An answer here http://answers.ros.org/question/10119... leads to http://gazebosim.org/tutorials?tut=ro... - you want to use the skid steering plugin rather than have gazebo do a 'raw' simulation of four wheels. Spinning wheels don't work that well in simulation, the various plugins get around that.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-10-31 20:08:14 -0500

Seen: 2,098 times

Last updated: Nov 01 '16