Hello, I am currently trying to set up an environment in gazebo 11.11 in which objects are being pushed by a robot arm+gripper. For now my objects are simple cubes that I load from a urdf file. It works fine at first, but after a few pushes the cube will simply stick to the fingers of the gripper as if it was glued onto it. I cannot consistently reproduce it, sometimes it works fine, but often it happens within a few interactions. This only seems to happen if the cube is pushed with the fingertips, other parts of the gripper seem to push just fine. Below are the important part of the 2 urdf files, for Gazebo I use the basic empty_world.launch with ode as the engine.
Gripper:
<link name="${prefix}robotiq_85_left_finger_tip_link">
<visual>
<geometry>
<mesh filename="package://robotiq_description/meshes/visual/robotiq_85_finger_tip_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.02 0.0 0.0" />
<geometry>
<!--mesh filename="package://robotiq_description/meshes/collision/robotiq_85_finger_tip_link.stl"/-->
<box size="0.05 0.015 0.01" />
</geometry>
</collision>
<inertial>
<mass value="0.019555" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx = "0.000002" ixy = "0.000000" ixz = "0.000000"
iyx = "0.000000" iyy = "0.000005" iyz = "0.000000"
izx = "0.000000" izy = "0.000000" izz = "0.000006" />
</inertial>
</link>
<link name="${prefix}robotiq_85_right_finger_tip_link">
<visual>
<geometry>
<mesh filename="package://robotiq_description/meshes/visual/robotiq_85_finger_tip_link.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0.02 0.008 0.0" />
<geometry>
<!--mesh filename="package://robotiq_description/meshes/collision/robotiq_85_finger_tip_link.stl"/-->
<box size="0.05 0.04 0.025" />
</geometry>
</collision>
<inertial>
<mass value="0.019555" />
<origin xyz="0.0 0.0 0.0" />
<inertia ixx = "0.000002" ixy = "0.000000" ixz = "0.000000"
iyx = "0.000000" iyy = "0.000005" iyz = "0.000000"
izx = "0.000000" izy = "0.000000" izz = "0.000006" />
</inertial>
</link>
<!-- Improving physics -->
<!-- <gazebo reference="${prefix}robotiq_85_left_finger_tip_link">
<kp>1000000000.0</kp>
<kd>1</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<minDepth>0.001</minDepth>
</gazebo>
<gazebo reference="${prefix}robotiq_85_right_finger_tip_link">
<kp>1000000000.0</kp>
<kd>1</kd>
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<minDepth>0.001</minDepth>
</gazebo> -->
Cube:
<robot name="green_cube">
<link name="green_cube">
<inertial>
<origin xyz="0 0 0" />
<mass value="1" />
<inertia ixx="0.00041666667" ixy="0" ixz="0" iyy="0.00041666667" iyz="0" izz="0.00041666667"/>
</inertial>
<visual>
<origin xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05" />
</geometry>
</visual>
<collision name="green_cube_collision">
<origin xyz="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05" />
</geometry>
</collision>
</link>
<gazebo reference="green_cube">
<material>Gazebo/Green</material>
<!-- <kp>1000000000</kp>
<kd>1</kd>
<mu1>0.4</mu1>
<mu2>0.4</mu2> -->
</gazebo>
What I tried so far:
- default parameters for everything
- different values between 1000 and 1,000,000,000 for kp / kd
- different min_depth values
- replacing the 2 fingers collisions with a single collision box
- lower speed and acceleration during pushing
- different heights
Does anyone have any idea, why the cubes get stuck or what else I should try to fix this?