Robotics StackExchange | Archived questions

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/Tutorials-2020

Here is my fork: https://github.com/dfszabo/Tutorials-2020

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: <!-- leg1link3 --> <link name="${prefix}leglink3">

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

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.

Asked by dfszabo on 2021-12-16 15:00:34 UTC

Comments

Answers

I met the same problem, no matter how I adjust the parameters mu1 and mu2, it doesn't work. Actually this is not a problem caused by the friction parameter setting, when I set the D parameter of the PID controller for each joint from 10 to 1, the problem disappeared. I used effort_controllers/JointPositionController, I think this will help you.

Asked by xiang on 2023-07-05 21:01:16 UTC

Comments