ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Gazebo slipping problem

asked 2020-03-25 09:53:17 -0500

Wasadim gravatar image

Hi,

we are working on pick and place project in ros melodic - using simulation on gazebo 9, and we encounter a problem with a slipping. Wideo of the behavior can be seen at this link: youtube

the settings for our gripper and object are as follows:

gripper.gazebo.urdf:

    <!-- LinkRightFinger -->
    <gazebo reference="${robot_name}_rightfinger">
        <material>Gazebo/Grey</material>
        <kp>10000000.0</kp>
        <kd>1000.0</kd>
        <mu1>100.0</mu1>
        <mu2>100.0</mu2>
        <maxVel>1.0</maxVel>
        <minDepth>0.003</minDepth>
    </gazebo>

    <!-- LinkLeftFinger -->
    <gazebo reference="${robot_name}_leftfinger">
        <material>Gazebo/Grey</material>
        <kp>10000000.0</kp>
        <kd>1000.0</kd>
        <mu1>100.0</mu1>
        <mu2>100.0</mu2>
        <maxVel>1.0</maxVel>
        <minDepth>0.003</minDepth>
    </gazebo>

model.sdf:

    <?xml version="1.0" ?>
    <sdf version='1.6'>
      <model name="cuboid">
        <static>0</static>
        <link name='link'>
          <inertial>
            <mass>0.10</mass>
            <inertia>
              <ixx>0.0002988</ixx>
              <ixy>0.000000</ixy>
              <ixz>0.000000</ixz>
              <iyy>0.0002988</iyy>
              <iyz>0.000000</iyz>
              <izz>0.00005976</izz>
            </inertia>
          </inertial>
          <collision name='collision'>
            <geometry>
              <box>
                <size>0.060 0.060 0.180</size>
              </box>
            </geometry>
            <surface>
              <friction>
                <ode>
                  <mu>100</mu>
                  <mu2>100</mu2>
                </ode>
              </friction>
              <contact>
                <ode>
                  <kp>1000000.0</kp>
                  <kd>100.0</kd>
                  <max_vel>1.0</max_vel>
                  <min_depth>0.002</min_depth>
                </ode>
              </contact>
            </surface>
          </collision>
          <visual name='visual'>
            <geometry>
              <box>
                <size>0.060 0.060 0.180</size>
              </box>
            </geometry>
            <material>
              <script>
                <uri>file://media/materials/scripts/gazebo.material</uri>
                <name>Gazebo/Red</name>
              </script>
            </material>
          </visual>
          <velocity_decay>
            <linear>0.000000</linear>
            <angular>0.000000</angular>
          </velocity_decay>
          <self_collide>0</self_collide>
          <kinematic>0</kinematic>
          <gravity>1</gravity>
        </link>
      </model>
    </sdf>

and controller settings - control.yaml:

    panda_hand_controller:
        type: position_controllers/JointTrajectoryController
        joints:
            - panda_finger_joint1
            - panda_finger_joint2
        constraints:
            goal_time: 0.6
            stopped_velocity_tolerance: 0
            panda_finger_joint1: {trajectory: 0.1, goal: 0.1}
            panda_finger_joint2: {trajectory: 0.1, goal: 0.1}


        stop_trajectory_duration: 1.0

        state_publish_rate: 100
    joint_position_controller:
        type: panda_simulation/JointPositionController
        arm_id: panda
        joint_names:
            - panda_joint1
            - panda_joint2
            - panda_joint3
            - panda_joint4
            - panda_joint5
            - panda_joint6
            - panda_joint7
        gains: [1, 1, 1, 1, 1, 1, 1]

i know of a JenniferBuehler/gazebo-pkgs grasping pluggin witch i implemented solving this issiue - but i dont like this approach and i want to do it in less cheaty way.

The physics engine we are using is ODE, and i didnt try to change it yet. Can it be a source of our problem?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-03-25 23:25:28 -0500

FadiAlladkani gravatar image

Based on what I know of gazebo, for pick and place operations you are better off using effort controllers rather than position controllers. Try switching the controllers to effort controllers and see if that helps the situation.

Other than that, you can also add some surface properties to the box and/or gripper to give them more realistic friction values to help gazebo better calculate the contact forces

edit flag offensive delete link more

Comments

1

I would add to this comment and mention that if this simulation is important enough to you, I think you are likely better off not using Gazebo_ros controllers. They often get the job done, but there is a lot of nonsense happening behind the scenes which can cause many difficulties. You will waste a lot of time trying to understand what is going on and even then it may not be entirely clear.

AdamGronewold gravatar image AdamGronewold  ( 2021-07-06 19:14:49 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2020-03-25 09:53:17 -0500

Seen: 2,216 times

Last updated: Mar 25 '20