Omnidirectional robot simulation
Hello everyone.
I am trying to simulate an omnidirectional robot with 4 mecacum wheels. The problem starts when I move the robot and the wheels behavior is not the expected, since the rollers don't roll. The whole wheel is moving but the contact with the ground doesn't produce the roller to roll. I have realized that it may be like this because the contact points between one single roller and the ground are not in the robot movement movement direction.
This is the sdf file of one single wheel (l wrote here only one roller and its respective joint):
<?xml version="1.0"?>
<sdf version="1.7">
<model name="mecanumWheel">
<static>false</static>
<self_collide>false</self_collide>
<!-- Cover -->
<link name="cover">
<velocity_decay>
<linear>0.01</linear>
<angular>0.01</angular>
</velocity_decay>
<!-- Part1 -->
<inertial>
<mass>0.4</mass>
<ixx>0.00038</ixx>
<ixy>0.0</ixy>
<iyy>0.00038</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.00044</izz>
</inertial>
<collision name="collisionCover1">
<pose>0 0 -0.035 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.010</length>
</cylinder>
</geometry>
</collision>
<visual name="visualCover1">
<pose>0 0 -0.035 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.010</length>
</cylinder>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
</material>
</visual>
<!-- Part2 -->
<collision name="collisionCover2">
<pose>0 0 0.035 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.010</length>
</cylinder>
</geometry>
</collision>
<visual name="visualCover2">
<pose>0 0 0.035 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.07</radius>
<length>0.010</length>
</cylinder>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
</material>
</visual>
</link>
<!-- Rollers -->
<link name="roller1">
<pose>0.065 0 0 0.7854 0 0</pose>
<velocity_decay>
<linear>0.01</linear>
<angular>0.01</angular>
</velocity_decay>
<inertial>
<mass>0.05</mass>
<ixx>0.0002</ixx>
<ixy>0.00001</ixy>
<iyy>0.0002</iyy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
<izz>0.00002</izz>
</inertial>
<collision name="collisionRoller1">
<max_contacts>100</max_contacts>
<geometry>
<mesh>
<uri>model://mecanumWheel/meshes/roller.stl</uri>
<scale>3 3 5</scale>
</mesh>
</geometry>
<friction>
<torsional>
<coefficient>100.0</coefficient>
<use_patch_radius>true</use_patch_radius>
<patch_radius>0.005</patch_radius>
</torsional>
<ode>
<mu>0.8</mu>
<mu2>0.8</mu2>
<fdir1>0 0 1</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</collision>
<visual name="visualRoller1">
<geometry>
<mesh>
<uri>model://mecanumWheel/meshes/roller.stl</uri>
<scale>3 3 5</scale>
</mesh>
</geometry>
<material>
<ambient>0.1 0.1 0.5 1</ambient>
</material>
</visual>
</link>
<!-- JOINTS -->
<joint type="revolute" name="joint1">
<child>roller1</child>
<parent>cover</parent>
<axis>
<xyz>0 0 1</xyz>
<dynamics>
<friction>0.005</friction>
</dynamics>
</axis>
</joint>
</model>
</sdf>
Someone could help me, detecting what can I change to make the rollers roll when the touch the ground?
Thanks very much in advance.