6 legged robot slips on the ground, not able to move forward, what could be the problem?
I made a 6 legged robot using a fork of this repo: https://github.com/utra-robosoccer/Tu...
Here is my fork: https://github.com/dfszabo/Tutorials-...
I tried a lot of stuff like setting minDepth, specifying mu1 and mu2 and the friction vector etc but still it slips.
I leave some snippets here, but It might be better to just check the repo.
the leg which touches the ground: <link name="${prefix}_leg_link_3">
<collision>
<origin xyz="${leg_width/2 + axel_offset} 0 ${-leg_height/2 + leg_width/2}" rpy="0 0 0"/>
<geometry>
<box size="${leg_width} ${leg_width} ${leg_height}"/>
</geometry>
<surface>
<friction>
<ode><mu>100000.0</mu><mu2>100000.0</mu2></ode>
</friction>
<contact>
<ode><min_depth>0.003</min_depth></ode>
</contact>
</surface>
</collision>
<visual>
<origin xyz="${leg_width/2 + axel_offset} 0 ${-leg_height/2 + leg_width/2}" rpy="0 0 0"/>
<geometry>
<box size="${leg_width} ${leg_width} ${leg_height}"/>
</geometry>
<material name="orange"/>
</visual>
<inertial>
<origin xyz="${leg_width/2 + axel_offset} 0 ${-leg_height/2 + leg_width/2}" rpy="0 0 0"/>
<mass value="${mass}"/>
<inertia
ixx="${mass / 12.0 * (leg_width*leg_width + leg_height*leg_height)}" ixy="0.0" ixz="0.0"
iyy="${mass / 12.0 * (leg_height*leg_height + leg_width*leg_width)}" iyz="0.0"
izz="${mass / 12.0 * (leg_width*leg_width + leg_width*leg_width)}"/>
</inertial>
</link>
Another properties for the leg:
<gazebo reference="${prefix}_leg_link_3">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>10000.0</mu1>
<mu2>10000.0</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>1.0</maxVel>
<minDepth>0.0001</minDepth>
<material>Gazebo/Orange</material>
</gazebo>
To run it just use the launch command used in the README.md also you can find the command to run the program which moves the program here as well.