Robotics StackExchange | Archived questions

Robot slips on ground while moving arm

I have a WidowX arm in Gazebo. I control the arm using moveit package. In the moveit package, I provide a goal configuration and then plan and execute planned trajectory. The problem now is that when the robot performs the arm movement in Gazebo, the base of the robots slips on the ground plane. It seems as if there is no friction at all between robot base and the ground plane.

Robot Slipping

To solve the slipping problem, I referred to gazebo documentation, where it said to create a virtual joint between the base and ground.Link That did not resolve the problem. Since, I am training a learning algorithm on the robot, I don't want the robot to move. Please let me know how I can prevent the slipping problem.

Asked by Stark on 2019-03-06 01:28:57 UTC

Comments

Your link worked for me. I just added

to my urdf and then spawned it like normal. Now my base_link is frozen where I spawned it, but I can still manipulate my arm.

Asked by mogumbo on 2019-03-19 15:54:09 UTC

@Stark, did you ever solve this problem? This is the last thing I need to do before I get my real arm moving and I am totally stuck. I have tried to add the world link at @mogumbo has suggested with no luck...

Asked by matthewmarkey on 2020-05-18 13:32:00 UTC

Answers

You can put static tags to the base link. It might cause problems with the simulation as it introduces more constraints. You have to try and see

<link name="base_link">
    <static>true</static>
    ...
</link>

Asked by kumpakri on 2019-03-15 04:33:14 UTC

Comments

Make sure you're setting the virtual joint with the correct robot base link. Assuming you're using the WidowX arm from RobotnikAutomation, you should be using base_footprint as the child frame name. You can check the root link for a robot URDF/Xacro using e.g.

check_urdf <(xacro --inorder $(rospack find widowx_arm_description)/robots/widowx_arm.urdf.xacro)

Source

Often, Gazebo-specific code is placed in a separate .xacro file that incorporates the original URDF. Such a file might look like:

<?xml version="1.0" ?>
<robot name="widowx_arm" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:include filename="$(find widowx_arm_description)/robots/widowx_arm.urdf.xacro"/>

  <!-- Used for fixing robot to Gazebo 'base_link' -->
  <link name="world"/>
  <joint name="fixed" type="fixed">
    <parent link="world"/>
    <child link="base_footprint"/>
  </joint>
</robot>

Asked by arprice on 2019-03-26 13:59:46 UTC

Comments