openarm_ros2/openarm_two_arms/urdf/openarm.xacro

289 lines
16 KiB
Plaintext
Raw Normal View History

2025-03-10 08:06:07 +00:00
<?xml version="1.0" ?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="side" value="right"/>
<xacro:property name="prefix" value=""/>
2025-03-10 08:16:37 +00:00
2025-03-10 08:32:31 +00:00
<!-- <xacro:property name="pi" value="3.1415926535897927"/> -->
2025-03-10 08:06:07 +00:00
<!-- <xacro:property name="zero_pos" value="vertical"/> -->
<xacro:macro name="openarm" params="side prefix">
2025-03-10 08:32:31 +00:00
<xacro:property name="reflect" value ="${ 1 if side=='right' else -1}"/>
2025-03-10 08:06:07 +00:00
<link name="${prefix}link1">
<visual>
2025-03-10 08:16:37 +00:00
<!--J1 v002/Part__Feature001.-->
2025-03-10 09:08:07 +00:00
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*-0.0007}"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j1v1_fj2ul1.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link1__col_J1_v1__BoundBox/col_J1_v1__BoundBox.-->
2025-03-10 08:32:31 +00:00
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*0.0289}"/>
2025-03-10 08:06:07 +00:00
<geometry>
<box size="0.11 0.073 0.0592"/>
</geometry>
</collision>
<inertial>
<mass value="0.5769283920617254"/>
2025-03-10 09:08:07 +00:00
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 ${reflect*2.52845e-05} ${reflect*0.0229621}"/>
2025-03-10 08:16:37 +00:00
<inertia ixx="0.00034035167574060775" ixy="-2.623557985991217e-18" ixz="-6.093726095527621e-18" iyy="0.0004300058300010205" iyz="-5.09829482074806e-07" izz="0.0004802171432001996"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link2">
<visual>
2025-03-10 08:16:37 +00:00
<!--J2 v002/Part__Feature002.-->
2025-03-10 09:08:07 +00:00
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*-0.05395}"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j2v1_xzm1cu.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link2__col_J2_v1__BoundBox/col_J2_v1__BoundBox.-->
2025-03-10 09:08:07 +00:00
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*0.0371236}"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.0590000000149012 0.08200000000000002 0.0742471498637348"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
<mass value="0.16257504134917358"/>
2025-03-10 09:08:07 +00:00
<origin rpy="0 0 0" xyz="${reflect*-0.000225878} ${reflect*-0.00183836} 0.0278368"/>
<inertia ixx="0.00023903110213294374" ixy="-7.551692921096027e-08" ixz="${reflect*-1.1282723362433474e-06}" iyy="0.00010490798314778774" iyz="${reflect*5.9079627839725245e-06}" izz="0.00019737368685935776"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link3">
<visual>
2025-03-10 08:16:37 +00:00
<!--J3 v003/Part__Feature003.-->
2025-03-10 09:08:07 +00:00
<origin rpy="1.570796326794897 0 0" xyz="0.0 0.0987 ${reflect*0.02975}"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j3v2_5nirfo.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link3__col_J3_v2__BoundBox/col_J3_v2__BoundBox.-->
<origin rpy="1.5707963267948968 0 0" xyz="-0.0164466 -0.00045542 0.02975"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.08989101803441879 0.06999999999999983 0.05903276947803012"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.4201676469910031"/>
2025-03-10 09:08:07 +00:00
<origin rpy="1.5707963267948968 0 0" xyz="${reflect*-0.00688022} 0.0 0.0282752"/>
<inertia ixx="0.00020256001126230057" ixy="6.004247875311213e-06" ixz="${reflect*1.3304903057525575e-06}" iyy="0.0002970624991387495" iyz="${reflect*5.980157765704868e-07}" izz="0.00032889994351244413"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link4">
<visual>
2025-03-10 08:16:37 +00:00
<!--J4 v002/Part__Feature004.-->
<origin rpy="-3.1415926535888543 -1.5620381439005742 0" xyz="-0.0986962 0.0 0.0621144"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j4v1_u1e2xn.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link4__col_J4_v1__BoundBox/col_J4_v1__BoundBox.-->
<origin rpy="-3.14159265358886 -1.5620381439005742 0" xyz="0.000266276 -0.0125642 -0.132604"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.27584673777150337 0.08211429171582063 0.07186573179325861"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.819475539373447"/>
<origin rpy="-3.14159265358886 -1.5620381439005742 0" xyz="0.000781326 -0.0019461 -0.132411"/>
<inertia ixx="0.00044078452033976287" ixy="6.020023694043618e-05" ixz="0.00014637459261941218" iyy="0.009208791480530413" iyz="1.5469710436444469e-06" izz="0.009170539316023695"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link5">
<visual>
2025-03-10 08:16:37 +00:00
<!--J5 v003/Part__Feature005.-->
2025-03-10 09:25:08 +00:00
<origin rpy="0 ${reflect*-0.008758182894317394} 0" xyz="${reflect*0.303864} 0.0 ${-0.128451 if side=='right' else -0.0689415"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j5v2_ckk9an.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link5__col_J5_v2__BoundBox/col_J5_v2__BoundBox.-->
2025-03-10 09:25:08 +00:00
<origin rpy="0 ${reflect*-0.008758182894316818} 0" xyz="${reflect*-0.0542814} 0.00265291 ${reflect*-0.0302022}"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.4086748254352304"/>
2025-03-10 09:25:08 +00:00
<origin rpy="0 ${reflect*-0.008758182894316905} 0" xyz="${reflect*-0.0831891} 0.00251789 ${reflect*-0.0290107}"/>
<inertia ixx="0.00031417157425298747" ixy="${reflect*-1.1391566029536723e-05}" ixz="${reflect*-1.883474090056124e-05}" iyy="0.001221711435313989" iyz="${reflect*1.46725418421127e-06}" izz="0.0010755135067660488"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
2025-03-10 09:08:07 +00:00
<link name="${prefix}link6_right_wrist">
2025-03-10 08:06:07 +00:00
<visual>
2025-03-10 08:16:37 +00:00
<!--J6 right_wrist/Part__Feature006.-->
<origin rpy="-2.1276679791326423 -1.5542266826921929 0" xyz="-0.0485412 -0.0860404 0.437784"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j6v1_mg9rps.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link6__col_J6_v1__BoundBox/col_J6_v1__BoundBox.-->
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00260794 -0.00312921 -0.0652641"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.13114353004704765 0.05953478325301745 0.08817196195081879"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.3448471958049249"/>
<origin rpy="-2.127667979132636 -1.5542266826921927 0" xyz="-0.00898536 -0.0135065 -0.0438611"/>
<inertia ixx="0.00019355980999748924" ixy="-1.0061665815148114e-06" ixz="-3.9096495715032716e-05" iyy="0.0003486912031865755" iyz="6.088060315273385e-06" izz="0.00028774975153756256"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link7">
<visual>
2025-03-10 08:16:37 +00:00
<!--J7 right v002/Part__Feature007.-->
<origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j7v1_9yzky6.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link7__col_J7_v1__BoundBox/col_J7_v1__BoundBox.-->
<origin rpy="0 -0.008758182894511114 0" xyz="-0.000318103 0.0022839 0.0340014"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.058327402175132874 0.04432916698753661 0.08267601622411752"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.2782138078738053"/>
<origin rpy="0 -0.008758182894511043 0" xyz="5.99432e-05 0.0041433 0.0354274"/>
<inertia ixx="0.00010424153315648891" ixy="2.735265831785291e-07" ixz="-1.0662322382945994e-07" iyy="0.00012313550743283462" iyz="-8.604996754782856e-08" izz="9.221319958512582e-05"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
<link name="${prefix}link8">
<visual>
2025-03-10 08:16:37 +00:00
<!--J8 v002/Part__Feature008.-->
<origin rpy="1.5709195259578714 -0.014065461951077267 0" xyz="0.557948 0.103587 0.019724"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_j8v1_dka5zq.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_link8__col_J8_v1__BoundBox/col_J8_v1__BoundBox.-->
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.042694 -0.000543176 0.0110286"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<box size="0.13038799671743653 0.05180887692688926 0.1601236763440867"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.31261452743802165"/>
<origin rpy="1.5709195259578714 -0.01406546195107726 0" xyz="-0.0607602 -0.000341696 0.00876618"/>
<inertia ixx="0.00023465661366788053" ixy="7.609048882006294e-05" ixz="3.088694121124684e-07" iyy="0.0005065459365215377" iyz="1.9022818028658623e-07" izz="0.0003737029250058136"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
2025-03-10 09:08:07 +00:00
<link name="${prefix}link_left_jaw">
2025-03-10 08:06:07 +00:00
<visual>
2025-03-10 08:16:37 +00:00
<!--left_jaw v002/Part__Feature009.-->
<origin rpy="0 -0.008758182894469432 0" xyz="0.665265 -0.00286677 -0.0209282"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_left_jawv1_6yxtlc.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_left_jaw__col_left_jaw_v1_col_obj/col_left_jaw_v1_col_obj.-->
<origin rpy="0 -0.0087581828944695 0" xyz="0.665265 -0.00286677 -0.0209282"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_col_left_jaw_v1_col_obj_wr4fju.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.04297897856394934"/>
<origin rpy="0 -0.008758182894469429 0" xyz="-0.0187138 0.00217075 0.0159499"/>
<inertia ixx="1.1771768742932353e-05" ixy="-2.389928166589898e-06" ixz="3.999292204534159e-06" iyy="2.3837354480794824e-05" iyz="3.494431877242991e-07" izz="3.0474590214086944e-05"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
2025-03-10 09:08:07 +00:00
<link name="${prefix}link_right_jaw">
2025-03-10 08:06:07 +00:00
<visual>
2025-03-10 08:16:37 +00:00
<!--right_jaw v002/Part__Feature010.-->
<origin rpy="0 -0.008758182898001485 0" xyz="0.665265 -0.00286677 -0.175928"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_right_jawv1_0fmgsg.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</visual>
<collision>
2025-03-10 08:16:37 +00:00
<!--bound_obj__right_right_jaw__col_right_jaw_v1_col_obj/col_right_jaw_v1_col_obj.-->
<origin rpy="0 -0.008758182898001553 0" xyz="0.665265 -0.00286677 -0.175928"/>
2025-03-10 08:06:07 +00:00
<geometry>
2025-03-10 08:16:37 +00:00
<mesh filename="package://openarm_two_arms/meshes/full_upper_col_right_jaw_v1_col_obj_9qatoq.dae"/>
2025-03-10 08:06:07 +00:00
</geometry>
</collision>
<inertial>
2025-03-10 08:16:37 +00:00
<mass value="0.042981665301134515"/>
<origin rpy="0 -0.00875818289800148 0" xyz="-0.0187844 -0.00272415 -0.0159503"/>
<inertia ixx="1.1561293087621594e-05" ixy="2.537718468008212e-06" ixz="-3.6591812257702003e-06" iyy="2.370165527871047e-05" iyz="4.848038235889027e-07" izz="3.039652946542647e-05"/>
2025-03-10 08:06:07 +00:00
</inertial>
</link>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev1" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link1"/>
<child link="${prefix}link2"/>
2025-03-10 09:08:07 +00:00
<origin rpy="${0 if side=='right' else -pi} ${0 if side=='right' else -pi} 0" xyz="0.0 0.0 ${reflect*0.05325}"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev2" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link2"/>
<child link="${prefix}link3"/>
2025-03-10 09:08:07 +00:00
<origin rpy="-1.5707963267948968 0 0" xyz="0.0 ${reflect*-0.02975} 0.04475"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
2025-03-10 09:08:07 +00:00
<limit effort="0.0" lower="${0.0 if side=='right' else -pi}" upper="${pi if side=='right' else 0.0}" velocity="0.0"/>
2025-03-10 08:06:07 +00:00
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev3" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link3"/>
<child link="${prefix}link4"/>
2025-03-10 09:08:07 +00:00
<origin rpy="${reflect*-1.5707963267949054} 0 ${reflect*-1.562038143900564}" xyz="${reflect*-0.0612477} -0.000536432 ${reflect*0.02975}"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev4" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link4"/>
<child link="${prefix}link5"/>
2025-03-10 09:16:48 +00:00
<origin rpy="${-0.20701608758495998 if side=='right' else -3.0383286058327292} -1.5707963267948566 ${-2.937419385117548 if side=='right' else 3.038328605832587}" xyz="0.0297547 0.0 ${reflect*-0.24175}"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
2025-03-10 09:16:48 +00:00
<limit effort="0.0" lower="${-0.3490658503988659 if side=='right' else -2.792526803190927}" upper="${2.792526803190927 if side=='right' else 0.3490658503988659}" velocity="0.0"/>
2025-03-10 08:06:07 +00:00
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev5" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link5"/>
2025-03-10 09:08:07 +00:00
<child link="${prefix}link6_right_wrist"/>
2025-03-10 09:16:48 +00:00
<origin rpy="${reflect*1.5707963267948473} ${reflect*-0.5569332500492129} 1.556730325338251" xyz="${reflect*-0.133937} 0.00188408 ${reflect*-0.0297547}"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev6" type="revolute">
<parent link="${prefix}link6_right_wrist"/>
2025-03-10 08:06:07 +00:00
<child link="${prefix}link7"/>
2025-03-10 09:16:48 +00:00
<origin rpy="${reflect*-1.5707963268024898} -1.5567303253382425 -0.5569332500461536" xyz="${reflect*-0.0187648} ${reflect*-0.0301352} ${reflect*-0.12105}"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}rev7" type="revolute">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link7"/>
<child link="${prefix}link8"/>
2025-03-10 08:16:37 +00:00
<origin rpy="-1.5707963267950005 -0.00875904933536772 -0.014066001454933467" xyz="-0.000217313 -0.0154485 0.0355"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-0.9599310885968813" upper="0.9599310885968813" velocity="0.0"/>
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}left_pris1" type="prismatic">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link8"/>
2025-03-10 09:08:07 +00:00
<child link="${prefix}link_left_jaw"/>
2025-03-10 08:16:37 +00:00
<origin rpy="1.570796326795101 -0.014066001454929162 0.00875904933542146" xyz="-0.1071 0.0768568 0.0132053"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
2025-03-10 08:16:37 +00:00
<limit effort="0.0" lower="0.0" upper="0.045" velocity="0.0"/>
2025-03-10 08:06:07 +00:00
</joint>
2025-03-10 09:08:07 +00:00
<joint name="${prefix}right_pris2" type="prismatic">
2025-03-10 08:06:07 +00:00
<parent link="${prefix}link8"/>
2025-03-10 09:08:07 +00:00
<child link="${prefix}link_right_jaw"/>
2025-03-10 08:16:37 +00:00
<origin rpy="1.570796326794883 -0.014066001454927403 0.008759049336290027" xyz="-0.10571 -0.0781373 0.0132053"/>
2025-03-10 08:06:07 +00:00
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="0.0" upper="0.045" velocity="0.0"/>
2025-03-10 09:08:07 +00:00
<mimic joint="${prefix}left_pris1" multiplier="-1.0" offset="0.0"/>
2025-03-10 08:06:07 +00:00
</joint>
</xacro:macro>
</robot>