HI @pap-x
In the urdf: https://github.com/lihuang3/ur5_ROS-G...
Wrist3 is connected to EE with a fixed joint
<joint name="${prefix}ee_fixed_joint" type="fixed">
<parent link="${prefix}wrist_3_link" />
<child link = "${prefix}ee_link" />
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
</joint>
Vacuum gripper is connected to EE with a revolute joint
<joint name="gripper_joint" type="revolute">
<axis xyz="1 0 0" />
<parent link="ee_link" />
<child link="vacuum_gripper" />
<origin rpy="0 1.5708 0" xyz="0.01 0.0125 0" />
<limit effort="50" velocity="50" lower="0" upper="0" />
<dynamics damping="0.0" friction="10"/>
</joint>
The vacuum grippers are small cylinders attached to EE link.
A crude sketch:
EDIT:
Disregard this: If you want to modify the behaviour, you will need to modify the URDF
Looking at the plugin one can appreciate how the force for each link in contact:
ignition::math::Vector3d force = norm_force * diff.Pos().Normalize();
links[j]->AddForce(force);
The force direction applied by the cylinders vacuum won’t change with the EE rotation.
For more information, please check this thread discussion: https://github.com/ros-simulation/gaz...