2025-02-07 09:22:54 +00:00
|
|
|
<?xml version="1.0" ?>
|
|
|
|
|
<robot name="openarm_grip" xmlns:xacro="http://www.ros.org/wiki/xacro">
|
|
|
|
|
|
2025-02-18 06:47:08 +00:00
|
|
|
<xacro:include filename="package://openarm_grip_description/urdf/materials.xacro" />
|
|
|
|
|
<xacro:include filename="package://openarm_grip_description/urdf/openarm_grip.trans" />
|
|
|
|
|
<xacro:include filename="package://openarm_grip_description/urdf/openarm_grip.gazebo" />
|
|
|
|
|
<link name="world"/>
|
|
|
|
|
<joint name="world_joint" type="fixed">
|
|
|
|
|
<parent link="world"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
<child link="base_link"/>
|
|
|
|
|
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
|
|
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<link name="base_link">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="1.659663993709495e-08 0.00015470291788827239 -0.03159176823669262" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.9159780860248254"/>
|
|
|
|
|
<inertia ixx="0.000802" iyy="0.000799" izz="0.001037" ixy="-0.0" iyz="-0.0" ixz="0.0"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="0 0 0" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/base_link.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J2_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="0.002300730781673588 -0.00021691236314287158 0.02760602616888808" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.49220952328993495"/>
|
|
|
|
|
<inertia ixx="0.000316" iyy="0.000717" izz="0.00059" ixy="0.0" iyz="-3e-06" ixz="-2.2e-05"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="-0.0 -0.0 0.00225" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="-0.0 -0.0 0.00225" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J2_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J3_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="-0.029725947365562236 0.014084733811091961 0.002458883521108013" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.6372830939810512"/>
|
|
|
|
|
<inertia ixx="0.000647" iyy="0.000437" izz="0.00075" ixy="4e-06" iyz="-5.2e-05" ixz="2e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="-0.02975 0.0 -0.0425" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="-0.02975 0.0 -0.0425" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J3_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J4_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="8.405076184644401e-05 0.1358717615053826 0.018429965102241944" rpy="0 0 0"/>
|
|
|
|
|
<mass value="1.1025467379280594"/>
|
|
|
|
|
<inertia ixx="0.011905" iyy="0.00114" izz="0.011791" ixy="-1e-06" iyz="-0.001657" ixz="-4e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="0.0 -0.06041 -0.052607" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="0.0 -0.06041 -0.052607" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J4_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J5_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="-0.028086778609557873 -0.06237848032279486 0.015103464347573828" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.7296865736952145"/>
|
|
|
|
|
<inertia ixx="0.002473" iyy="0.000853" izz="0.002847" ixy="-7e-05" iyz="0.00038" ixz="1.8e-05"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="-0.029755 -0.298846 -0.0925" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="-0.029755 -0.298846 -0.0925" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J5_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J6_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="0.016428123043712856 -0.04271549352047854 0.009023923091251038" rpy="0 0 0"/>
|
|
|
|
|
<mass value="1.0339114396114095"/>
|
|
|
|
|
<inertia ixx="0.000881" iyy="0.000614" izz="0.001054" ixy="0.000136" iyz="0.000102" ixz="-1.1e-05"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="0.0 -0.167496 -0.118765" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="0.0 -0.167496 -0.118765" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J6_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="J7_v1_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="-0.03510690863628159 0.0004066264284608781 0.001093657345024951" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.33288025570396623"/>
|
|
|
|
|
<inertia ixx="0.00014" iyy="0.000179" izz="0.000207" ixy="-0.0" iyz="7e-06" ixz="2e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="-0.0355 -0.048796 -0.1425" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="-0.0355 -0.048796 -0.1425" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/J7_v1_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="grip_attach_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="-3.544262443517109e-05 -0.08091067772872827 0.004061313352520662" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.8188472642682024"/>
|
|
|
|
|
<inertia ixx="0.001113" iyy="0.00061" izz="0.001556" ixy="1e-06" iyz="-2.2e-05" ixz="2e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="0.0 -0.051826 -0.15765" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="0.0 -0.051826 -0.15765" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/grip_attach_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="left_jaw_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="0.01737096632831872 -0.017398412728963003 0.004062150876211923" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.2869555939898112"/>
|
|
|
|
|
<inertia ixx="0.000209" iyy="9.7e-05" izz="0.000185" ixy="1.6e-05" iyz="3e-06" ixz="-4e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="0.0775 0.069829 -0.169736" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="0.0775 0.069829 -0.169736" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/left_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<link name="right_jaw_1">
|
|
|
|
|
<inertial>
|
|
|
|
|
<origin xyz="-0.0173972747583793 -0.018685385724924758 -0.0017497641003002828" rpy="0 0 0"/>
|
|
|
|
|
<mass value="0.285094009790996"/>
|
|
|
|
|
<inertia ixx="0.000211" iyy="0.000115" izz="0.000169" ixy="-1.6e-05" iyz="3.9e-05" ixz="4e-06"/>
|
|
|
|
|
</inertial>
|
|
|
|
|
<visual>
|
|
|
|
|
<origin xyz="-0.0775 0.069829 -0.169736" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
<material name="silver"/>
|
|
|
|
|
</visual>
|
|
|
|
|
<collision>
|
|
|
|
|
<origin xyz="-0.0775 0.069829 -0.169736" rpy="0 0 0"/>
|
|
|
|
|
<geometry>
|
|
|
|
|
<mesh filename="package://openarm_grip_description/meshes/right_jaw_1.stl" scale="0.001 0.001 0.001"/>
|
|
|
|
|
</geometry>
|
|
|
|
|
</collision>
|
|
|
|
|
</link>
|
|
|
|
|
|
|
|
|
|
<joint name="rev1" type="revolute">
|
|
|
|
|
<origin xyz="0.0 0.0 -0.00225" rpy="0 0 0"/>
|
|
|
|
|
<parent link="base_link"/>
|
|
|
|
|
<child link="J2_v1_1"/>
|
|
|
|
|
<axis xyz="0.0 0.0 1.0"/>
|
|
|
|
|
<limit upper="2.356194" lower="-2.356194" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev2" type="revolute">
|
|
|
|
|
<origin xyz="0.02975 -0.0 0.04475" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J2_v1_1"/>
|
|
|
|
|
<child link="J3_v1_1"/>
|
|
|
|
|
<axis xyz="-1.0 -0.0 0.0"/>
|
|
|
|
|
<limit upper="0.0" lower="-3.054326" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev3" type="revolute">
|
|
|
|
|
<origin xyz="-0.02975 0.06041 0.010107" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J3_v1_1"/>
|
|
|
|
|
<child link="J4_v1_1"/>
|
|
|
|
|
<axis xyz="-0.0 0.986291 0.165017"/>
|
|
|
|
|
<limit upper="2.094395" lower="-2.094395" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev4" type="revolute">
|
|
|
|
|
<origin xyz="0.029755 0.238436 0.039893" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J4_v1_1"/>
|
|
|
|
|
<child link="J5_v1_1"/>
|
|
|
|
|
<axis xyz="1.0 0.0 0.0"/>
|
|
|
|
|
<limit upper="0.0" lower="-3.141593" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev5" type="revolute">
|
|
|
|
|
<origin xyz="-0.029755 -0.13135 0.026265" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J5_v1_1"/>
|
|
|
|
|
<child link="J6_v1_1"/>
|
|
|
|
|
<axis xyz="0.0 -0.980588 0.196078"/>
|
|
|
|
|
<limit upper="2.094395" lower="-2.094395" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev6" type="revolute">
|
|
|
|
|
<origin xyz="0.0355 -0.1187 0.023735" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J6_v1_1"/>
|
|
|
|
|
<child link="J7_v1_1"/>
|
|
|
|
|
<axis xyz="-1.0 0.0 -0.0"/>
|
|
|
|
|
<limit upper="1.570796" lower="-1.570796" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="rev7" type="continuous">
|
|
|
|
|
<origin xyz="-0.0355 0.00303 0.01515" rpy="0 0 0"/>
|
|
|
|
|
<parent link="J7_v1_1"/>
|
|
|
|
|
<child link="grip_attach_1"/>
|
|
|
|
|
<axis xyz="0.0 0.196078 0.980588"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
<joint name="slider_left" type="prismatic">
|
|
|
|
|
<origin xyz="-0.0775 -0.121655 0.012086" rpy="0 0 0"/>
|
|
|
|
|
<parent link="grip_attach_1"/>
|
|
|
|
|
<child link="left_jaw_1"/>
|
|
|
|
|
<axis xyz="-1.0 0.0 -0.0"/>
|
|
|
|
|
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
2025-02-09 00:08:54 +00:00
|
|
|
<joint name="slider_right" type="prismatic">
|
2025-02-07 09:22:54 +00:00
|
|
|
<origin xyz="0.0775 -0.121655 0.012086" rpy="0 0 0"/>
|
|
|
|
|
<parent link="grip_attach_1"/>
|
|
|
|
|
<child link="right_jaw_1"/>
|
|
|
|
|
<axis xyz="1.0 -0.0 0.0"/>
|
|
|
|
|
<limit upper="0.0" lower="-0.0455" effort="100" velocity="1.0" acceleration="0.5"/>
|
2025-02-18 06:47:08 +00:00
|
|
|
<dynamics damping="1.0" friction="1.0"/>
|
2025-02-10 02:16:26 +00:00
|
|
|
<mimic joint="slider_left"/>
|
2025-02-07 09:22:54 +00:00
|
|
|
</joint>
|
|
|
|
|
|
|
|
|
|
</robot>
|