Robotics StackExchange | Archived questions

Simple mobile base simulation not working in Gazebo

Hi all,

I am working on setting up a simulation environment in Gazebo. I have a basic mobile base robot with two wheels at the back and a caster wheel at the front.
image description

Then, when I give velocities to the two wheels using turtlesim turtleteleopkey (assume forward velocities), two wheels rotate in the correct direction but the robot does not move accordingly (remains stationary) and after some time, the robot starts rotating very slowly although both the wheels are still rotating in the forward direction. I think it might have to do something with physical properties but I am not able to figure it out.

Hope I have made myself clear. The relevant code is shown.

drsim.xacro

        <link name='base_link'>
    <collision>
        <origin xyz="0 0 ${2*casterRadius + chassisHeight/2}" rpy="0 0 0" />
        <geometry>
            <box size="${chassisLength} ${chassisWidth} ${chassisHeight}" />
        </geometry>
    </collision>
    <visual>
        <origin xyz="0 0 ${2*casterRadius + chassisHeight/2}" rpy="0 0 0" />
        <geometry>
            <box size="${chassisLength} ${chassisWidth} ${chassisHeight}" />
        </geometry>
        <material name="orange" />
    </visual>
</link>

<joint name="base_caster_joint" type="fixed">
    <parent link="base_link" />
    <child link="caster_wheel" />
</joint>

<link name="caster_wheel">
    <collision>
        <origin xyz="${chassisLength/2 - casterRadius} 0 ${casterRadius}" rpy="0 0 0"/>
        <geometry>
            <sphere radius="${casterRadius}" />
        </geometry>
    </collision>
    <visual>
        <origin xyz="${chassisLength/2 - casterRadius} 0 ${casterRadius}" rpy="0 0 0"/>
        <geometry>
            <sphere radius="${casterRadius}" />
        </geometry>
        <material name="red" />
    </visual>
    <inertial>
        <origin xyz="${chassisLength/2 - casterRadius} 0 ${casterRadius}" rpy="0 0 0"/>
        <mass value="${casterMass}"/>
        <sphere_inertia m="${casterMass}" r="${casterRadius}"/>
    </inertial>
</link>

<wheel lr="left" tY="1"/>
<wheel lr="right" tY="-1"/>

macros.xacro

<macro name="wheel" params="lr tY">

 <link name="${lr}_wheel">
 <collision>
   <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
   <geometry>
     <cylinder length="${wheelWidth}" radius="${wheelRadius}"/>
   </geometry>
 </collision>

<visual>
  <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
  <geometry>
    <cylinder length="${wheelWidth}" radius="${wheelRadius}"/>
  </geometry>
  <material name="black"/>
</visual>

<inertial>
  <origin xyz="0 0 0" rpy="0 ${PI/2} ${PI/2}" />
  <mass value="${wheelMass}"/>
  <cylinder_inertia m="${wheelMass}" r="${wheelRadius}" h="${wheelWidth}"/>
</inertial>

<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>

<joint name="${lr}_wheel_hinge" type="continuous">
<parent link="base_link"/>
<child link="${lr}_wheel"/>
<origin xyz="${wheelPos - chassisLength/2} ${tY*wheelWidth/2+tY*chassisWidth/2} ${wheelRadius}" rpy="0 0 0" />
<axis xyz="0 1 0" rpy="0 0 0" />
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>   </joint>


<transmission name="${lr}_trans">
 <type>transmission_interface/SimpleTransmission</type>
<joint name="${lr}_wheel_hinge">
  <hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${lr}Motor">
  <hardwareInterface>EffortJointInterface</hardwareInterface>
  <mechanicalReduction>10</mechanicalReduction>
</actuator>   </transmission>

Gazebo/Black

Does anyone have some experience about such an issue? Any help will be appreciated.

Thanks. Naman

Asked by Naman91 on 2015-03-11 18:53:54 UTC

Comments

Answers

base_caster_joint is fixed, so caster_wheel cannot rotate. The friction between it and the ground probably is keeping the robot from moving. You can try setting caster_wheel's friction to zero. Alternatively, you can add a gazebo element and set base_caster_joint's type to "ball". See http://answers.ros.org/question/138736/urdf-alternative-of-sdf-revolute2-joint-type.

Asked by Jim Rothrock on 2015-03-17 19:28:32 UTC

Comments