Robotics StackExchange | Archived questions

Gazebo slipping problem

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.4'>
    <model name="demo_cube">      
        <static>0</static>
        <link name='link'>
          <inertial>
            <mass>0.25</mass>
            <inertia>
              <ixx>0.001</ixx>
              <ixy>0.000000</ixy>
              <ixz>0.000000</ixz>
              <iyy>0.001</iyy>
              <iyz>0.000000</iyz>
              <izz>0.001</izz>
            </inertia>
          </inertial>
          <collision name='collision'>
            <geometry>
              <box>
                <size>0.060 0.060 0.060</size>
              </box>
            </geometry>
            <surface>
              <friction>
                <ode>
                  <mu>30.0</mu>
                  <mu2>30.0</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.060</size>
              </box>
            </geometry>
            <material>
              <script>
                <uri>file://media/materials/scripts/gazebo.material</uri>
                <name>Gazebo/Blue</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]

Asked by theevilone45 on 2020-03-26 08:14:23 UTC

Comments

Answers