136 lines
5.8 KiB
XML
136 lines
5.8 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<robot xmlns:xacro="http://wiki.ros.org/xacro">
|
|
<xacro:include filename="$(find rbs_gripper)/urdf/rbs_gripper_ros2_control.xacro" />
|
|
<xacro:macro name="rbs_gripper" params="prefix gripper_name *origin parent hardware">
|
|
|
|
<xacro:rbs_gripper_hardware prefix="${prefix}" gripper_name="${gripper_name}"
|
|
hardware="${hardware}" />
|
|
|
|
<joint name="${prefix}${gripper_name}_gripper_base_joint" type="fixed">
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<parent link="${parent}" />
|
|
<child link="${prefix}${gripper_name}_gripper_base_link" />
|
|
</joint>
|
|
<link name="${prefix}${gripper_name}_gripper_base_link">
|
|
<inertial>
|
|
<origin xyz="0.000364704367134063 0.0336387482840125 0.0593891203954369" rpy="0 0 0" />
|
|
<mass value="1.13983632906086" />
|
|
<inertia ixx="0.00107738806534129" ixy="-1.09841172461737E-05" ixz="2.62750043451545E-06"
|
|
iyy="0.000717388573992299" iyz="-2.95426438182787E-05" izz="0.00115777179755934" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/visual/Grip_Base.dae" />
|
|
</geometry>
|
|
<material name="${prefix}${gripper_name}_material">
|
|
<color rgba="0.752941176470588 0.752941176470588 0.752941176470588 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/collision/Grip_Base.stl" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<link name="${prefix}${gripper_name}_rot_base_link">
|
|
<inertial>
|
|
<origin xyz="6.79110135283868E-11 -3.80956832067611E-10 0.00775394473595793" rpy="0 0 0" />
|
|
<mass value="0.161003401535982" />
|
|
<inertia ixx="0.00011089089949771" ixy="5.01335040610636E-06" ixz="1.74608448389267E-14"
|
|
iyy="0.000105515893695012" iyz="-2.03282362854432E-14" izz="0.000206912001661452" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/visual/Grip_Rotator.dae" />
|
|
</geometry>
|
|
<material name="${prefix}${gripper_name}_material">
|
|
<color rgba="0.250980392156863 0.250980392156863 0.250980392156863 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/collision/Grip_Rotator.stl" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${prefix}${gripper_name}_rot_base_joint" type="revolute">
|
|
<origin xyz="0 0 0.10861" rpy="0 0 0" />
|
|
<parent link="${prefix}${gripper_name}_gripper_base_link" />
|
|
<child link="${prefix}${gripper_name}_rot_base_link" />
|
|
<axis xyz="0 0 1" />
|
|
<limit lower="0" upper="0" effort="0" velocity="0" />
|
|
</joint>
|
|
<link name="${prefix}${gripper_name}_l_finger_link">
|
|
<inertial>
|
|
<origin xyz="0.00399878118534129 0.0187296413885176 -0.0777776233934166" rpy="0 0 0" />
|
|
<mass value="0.0601996441483964" />
|
|
<inertia ixx="4.18533281165612E-05" ixy="-7.11657995951147E-06" ixz="1.81029223490065E-05"
|
|
iyy="7.89886367868258E-05" iyz="1.20542845942065E-05" izz="5.16740841307935E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/visual/Gripper_1.dae" />
|
|
</geometry>
|
|
<material name="${prefix}${gripper_name}_material">
|
|
<color rgba="0.752941176470588 0 0 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/collision/Gripper_1.stl" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${prefix}${gripper_name}_l_finger_joint" type="prismatic">
|
|
<origin xyz="0 0 0.1071" rpy="0 0 1.5708" />
|
|
<parent link="${prefix}${gripper_name}_rot_base_link" />
|
|
<child link="${prefix}${gripper_name}_l_finger_link" />
|
|
<axis xyz="-1 0 0" />
|
|
<limit lower="0" upper="0.064" effort="0" velocity="0" />
|
|
<mimic joint="${prefix}${gripper_name}_r_finger_joint" multiplier="1" />
|
|
</joint>
|
|
<link name="${prefix}${gripper_name}_r_finger_link">
|
|
<inertial>
|
|
<origin xyz="0.0039988 -0.077778 -0.01873" rpy="0 0 0" />
|
|
<mass value="0.0602" />
|
|
<inertia ixx="4.1853E-05" ixy="1.8103E-05" ixz="7.1166E-06" iyy="5.1674E-05"
|
|
iyz="-1.2054E-05"
|
|
izz="7.8989E-05" />
|
|
</inertial>
|
|
<visual>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/visual/Gripper_2.dae" />
|
|
</geometry>
|
|
<material name="${prefix}${gripper_name}_material">
|
|
<color rgba="0.75294 0 0 1" />
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<origin xyz="0 0 0" rpy="0 0 0" />
|
|
<geometry>
|
|
<mesh filename="file://$(find rbs_gripper)/meshes/collision/Gripper_2.stl" />
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="${prefix}${gripper_name}_r_finger_joint" type="prismatic">
|
|
<origin xyz="0 0 0.1071" rpy="1.5708 0 -1.5708" />
|
|
<parent link="${prefix}${gripper_name}_rot_base_link" />
|
|
<child link="${prefix}${gripper_name}_r_finger_link" />
|
|
<axis xyz="-1 0 0" />
|
|
<limit lower="0" upper="0.064" effort="0" velocity="0" />
|
|
</joint>
|
|
<link name="${prefix}gripper_grasp_point" />
|
|
<joint name="${prefix}${gripper_name}_gripper_tool0_joint" type="fixed">
|
|
<origin xyz="0 0 0.2" rpy="0 0 0" />
|
|
<parent link="${prefix}${parent}" />
|
|
<child link="${prefix}gripper_grasp_point" />
|
|
</joint>
|
|
</xacro:macro>
|
|
</robot>
|