Toggling contact of wheel
I have created a model by using the URDF export plugin for SolidWorks and converted it into the SDF format. In Gazebo some joints start moving. The problem appears to be a toggling contact of the wheel with the ground. Please watch the youtube video to understand what I am refering to.
3 wheel robotic platform in gazebeo
The video is x10 times the normal speed, as the movement is very small. Unfortunately I cannot upload the SDF file in lack of Karma.
so here is a sniplet of the wheel
<link name='rad'>
<pose>0.0724995 0 -0.435 -1.57079 0 0</pose>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.54391</mass>
<inertia>
<ixx>0.0034711</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0034739</iyy>
<iyz>0</iyz>
<izz>0.0061305</izz>
</inertia>
</inertial>
<collision name='rad_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.130</radius>
<length>0.09</length>
</cylinder>
<!-- <mesh>
<scale>1 1 1</scale>
<uri>file://rad.dae</uri>
</mesh> -->
</geometry>
<surface>
<friction>
<ode>
<mu>10.0</mu>
<mu2>10.0</mu2>
<slip1>10</slip1>
<slip2>10</slip2>
</ode>
<bullet>
<friction>10.0</friction>
<friction2>10.0</friction2>
<fdir1>1 1 0</fdir1>
<rolling_friction>1.0</rolling_friction>
</bullet>
</friction>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.1</soft_erp>
<kp>1e+10</kp>
<kd>10</kd>
<max_vel>0.01</max_vel>
<min_depth>1</min_depth>
</ode>
</contact>
</surface>
And thats the sniplet for the corresponding joint
<joint name='Jrad' type='revolute'>
<child>rad</child>
<parent>gabel</parent>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<damping>0.8</damping>
<friction>0.0001</friction>
</dynamics>
</axis>
</joint>
I have tried different values for mu, friction friction etc. with limited success. Maybe someone sees the error in my approach.
The system i am working on:
OS: Ubuntu 3.8.0-35-generic #50~precise1-Ubuntu SMP Wed Dec 4 17:25:51 UTC 2013 x8664 x8664 x86_64 GNU/Linux
Gazebo: version 2.1.0
ROS: Furete
BR and thanks for any help in advance!