differential drive caster wheel problem
Hello, I am trying to build a sdf model of a differential drive, but I am having some issues. The problems are caused by the caster wheel joint.
Here is the sdf code:
<link name="caster_wheel">
<pose>0.045 0 -0.0528 0 -0 0</pose>
<gravity>1</gravity>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0</ixx>
<ixy>0</ixy>
<ixy>0</ixy>
<iyy>0</iyy>
<iyz>0</iyz>
<izz>0</izz>
</inertia>
</inertial>
<collision name="caster_wheel_geom">
<laser_retro>0</laser_retro>
<geometry>
<sphere>
<radius>0.01</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0.01</mu>
<mu2>0.01</mu2>
<fdir1> 0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>100000</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1000000000000</kp>
<kd>1</kd>
<max_vel>100</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="caster_wheel_geom_visual">
<cast_shadows>1</cast_shadows>
<laser_retro>0</laser_retro>
<transparency>0</transparency>
<pose> 0 0 0 0 -0 0</pose>
<geometry>
<sphere>
<radius>0.01</radius>
</sphere>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Yellow</name>
</script>
</material>
</visual>
</link>
<joint name="caster_joint" type="revolute">
<pose>0 0 0 0 -0 0</pose>
<parent>chassis_link</parent>
<child>caster_wheel</child>
<axis>
<xyz>0 1 0</xyz>
<dynamics>
<damping>0</damping>
<friction>0</friction>
</dynamics>
<limit>
<lower>-10000000000000000</lower>
<upper>10000000000000000</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
</axis>
</joint>
before starting the simulation, everything looks normal:
the caster wheel is the front yellow sphere. Right after clicking on the play button of gazebo this happens:
I tried to understand what is wrong, but I can't see any problem.
Thank you
Andrea