Object slips out of the gripper after jitters
I am trying to make robot arm grasp a cylinder object but when ever the gets in the grasp and the gripper closes, it starts vibrating and the object appears to slip out of it. I am using a position_controller for gripper and the rest of the arm. The problem I can think of could be with the controller as it tries to reach a position which it cannot due to collision with the object so the pid controller starts shaking it.
Pls answer if you have any insight on this. Thanks
<joint name="${prefix}gripper_joint" type="prismatic"> <parent link="${prefix}wrist_roll"/> <child link="${prefix}gripper_finger1"/> <origin xyz="-0.01331 0.00485 0.137225" rpy="0 0 0"/> <limit lower="-0.08" upper="0.008" effort="20.0" velocity="5.0"/> <axis xyz="1 0 0"/> <dynamics damping="0.7" friction="0.0"/> </joint>
<link name="${prefix}gripper_finger1">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<!--box size="0.015 0.0229 0.0475"/-->
<mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger1.dae"/>
</geometry>
</visual>
<collision name="${prefix}gripper_finger1_collision">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.015 0.0229 0.1"/>
<mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger1.dae"/>
</geometry>
</collision>
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx=".0000027" iyy=".0000027" izz=".0000027"
ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<gazebo reference="${prefix}gripper_finger1">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>200.0</mu1>
<mu2>100.0</mu2>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="tran8">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}gripper_joint">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor8">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</actuator>
</transmission>
<joint name="${prefix}gripper_joint2" type="prismatic"> <parent link="${prefix}wrist_roll"/> <child link="${prefix}gripper_finger2"/> <origin xyz="0.0098 0.00485 0.137225" rpy="0 0 0"/> <limit lower="-0.008" upper="0.08" effort="20.0" velocity="5.0"/> <axis xyz="1 0 0"/> <dynamics damping="0.7" friction="0.0"/> </joint>
<link name="${prefix}gripper_finger2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<!--box size="0.015 0.0229 0.0475"/-->
<mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger2.dae"/>
</geometry>
</visual>
<collision name="${prefix}gripper_finger2_collision">
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.015 0.0229 0.1"/><!--0.0475-->
<!--mesh filename="package://cyton_gamma_1500_description/meshes/gripper_finger2.dae"/-->
</geometry>
</collision>
<inertial>
<mass value="0.01"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx=".0000027" iyy=".0000027" izz=".0000027"
ixy="0" ixz="0" iyz="0"/>
</inertial>
</link>
<gazebo reference="${prefix}gripper_finger2">
<kp>1000000.0</kp>
<kd>1.0</kd>
<mu1>200.0</mu1>
<mu2>100.0</mu2>
<minDepth>0.001</minDepth>
</gazebo>
<transmission name="tran9">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}gripper_joint2">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</joint>
<actuator name="motor9">
<hardwareInterface>EffortJointInterface</hardwareInterface>
</actuator>
This is the updated urdf of the gripper
<?xml version="1.0"?>
<robot name="mug">
<link name="coke_can">
<inertial>
<mass value="0.1 ...
please post your world file with your gripper demonstrating the issue so we can help