Revert mirrors

This commit is contained in:
Thomason Zhou 2025-03-10 19:24:37 +09:00
parent 45f5e21513
commit 184959e49b

View File

@ -13,49 +13,49 @@
<link name="${prefix}link1">
<visual>
<!--J1 v002/Part__Feature001.-->
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*-0.0007}"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 -0.0007"/>
<geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j1v1_fj2ul1.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__right_link1__col_J1_v1__BoundBox/col_J1_v1__BoundBox.-->
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*0.0289}"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 0.0289"/>
<geometry>
<box size="0.11 0.073 0.0592"/>
</geometry>
</collision>
<inertial>
<mass value="0.5769283920617254"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 ${reflect*2.52845e-05} ${reflect*0.0229621}"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 2.52845e-05 0.0229621"/>
<inertia ixx="0.00034035167574060775" ixy="-2.623557985991217e-18" ixz="-6.093726095527621e-18" iyy="0.0004300058300010205" iyz="-5.09829482074806e-07" izz="0.0004802171432001996"/>
</inertial>
</link>
<link name="${prefix}link2">
<visual>
<!--J2 v002/Part__Feature002.-->
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*-0.05395}"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 -0.05395"/>
<geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j2v1_xzm1cu.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__right_link2__col_J2_v1__BoundBox/col_J2_v1__BoundBox.-->
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 ${reflect*0.0371236}"/>
<origin rpy="${0 if side=='right' else pi} 0 0" xyz="0.0 0.0 0.0371236"/>
<geometry>
<box size="0.0590000000149012 0.08200000000000002 0.0742471498637348"/>
</geometry>
</collision>
<inertial>
<mass value="0.16257504134917358"/>
<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"/>
<origin rpy="0 0 0" xyz="-0.000225878 -0.00183836 0.0278368"/>
<inertia ixx="0.00023903110213294374" ixy="-7.551692921096027e-08" ixz="-1.1282723362433474e-06" iyy="0.00010490798314778774" iyz="5.9079627839725245e-06" izz="0.00019737368685935776"/>
</inertial>
</link>
<link name="${prefix}link3">
<visual>
<!--J3 v003/Part__Feature003.-->
<origin rpy="1.570796326794897 0 0" xyz="0.0 0.0987 ${reflect*0.02975}"/>
<origin rpy="1.570796326794897 0 0" xyz="0.0 0.0987 0.02975"/>
<geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j3v2_5nirfo.dae"/>
</geometry>
@ -69,8 +69,8 @@
</collision>
<inertial>
<mass value="0.4201676469910031"/>
<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"/>
<origin rpy="1.5707963267948968 0 0" xyz="-0.00688022 0.0 0.0282752"/>
<inertia ixx="0.00020256001126230057" ixy="6.004247875311213e-06" ixz="1.3304903057525575e-06" iyy="0.0002970624991387495" iyz="5.980157765704868e-07" izz="0.00032889994351244413"/>
</inertial>
</link>
<link name="${prefix}link4">
@ -97,22 +97,22 @@
<link name="${prefix}link5">
<visual>
<!--J5 v003/Part__Feature005.-->
<origin rpy="0 ${reflect*-0.008758182894317394} 0" xyz="${reflect*0.303864} 0.0 ${-0.128451 if side=='right' else -0.0689415"/>
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
<geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j5v2_ckk9an.dae"/>
</geometry>
</visual>
<collision>
<!--bound_obj__right_link5__col_J5_v2__BoundBox/col_J5_v2__BoundBox.-->
<origin rpy="0 ${reflect*-0.008758182894316818} 0" xyz="${reflect*-0.0542814} 0.00265291 ${reflect*-0.0302022}"/>
<origin rpy="0 -0.008758182894316818 0" xyz="-0.0542814 0.00265291 -0.0302022"/>
<geometry>
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
</geometry>
</collision>
<inertial>
<mass value="0.4086748254352304"/>
<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"/>
<origin rpy="0 -0.008758182894316905 0" xyz="-0.0831891 0.00251789 -0.0290107"/>
<inertia ixx="0.00031417157425298747" ixy="-1.1391566029536723e-05" ixz="-1.883474090056124e-05" iyy="0.001221711435313989" iyz="1.46725418421127e-06" izz="0.0010755135067660488"/>
</inertial>
</link>
<link name="${prefix}link6_right_wrist">
@ -223,42 +223,42 @@
<joint name="${prefix}rev1" type="revolute">
<parent link="${prefix}link1"/>
<child link="${prefix}link2"/>
<origin rpy="${0 if side=='right' else -pi} ${0 if side=='right' else -pi} 0" xyz="0.0 0.0 ${reflect*0.05325}"/>
<origin rpy="${0 if side=='right' else -pi} ${0 if side=='right' else -pi} 0" xyz="0.0 0.0 0.05325"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="${prefix}rev2" type="revolute">
<parent link="${prefix}link2"/>
<child link="${prefix}link3"/>
<origin rpy="-1.5707963267948968 0 0" xyz="0.0 ${reflect*-0.02975} 0.04475"/>
<origin rpy="-1.5707963267948968 0 0" xyz="0.0 -0.02975 0.04475"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="${0.0 if side=='right' else -pi}" upper="${pi if side=='right' else 0.0}" velocity="0.0"/>
</joint>
<joint name="${prefix}rev3" type="revolute">
<parent link="${prefix}link3"/>
<child link="${prefix}link4"/>
<origin rpy="${reflect*-1.5707963267949054} 0 ${reflect*-1.562038143900564}" xyz="${reflect*-0.0612477} -0.000536432 ${reflect*0.02975}"/>
<origin rpy="-1.5707963267949054 0 -1.562038143900564" xyz="-0.0612477 -0.000536432 0.02975"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-3.6651914291880923" upper="0.5235987755982988" velocity="0.0"/>
</joint>
<joint name="${prefix}rev4" type="revolute">
<parent link="${prefix}link4"/>
<child link="${prefix}link5"/>
<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}"/>
<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 -0.24175"/>
<axis xyz="0 0 1"/>
<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"/>
</joint>
<joint name="${prefix}rev5" type="revolute">
<parent link="${prefix}link5"/>
<child link="${prefix}link6_right_wrist"/>
<origin rpy="${reflect*1.5707963267948473} ${reflect*-0.5569332500492129} 1.556730325338251" xyz="${reflect*-0.133937} 0.00188408 ${reflect*-0.0297547}"/>
<origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint>
<joint name="${prefix}rev6" type="revolute">
<parent link="${prefix}link6_right_wrist"/>
<child link="${prefix}link7"/>
<origin rpy="${reflect*-1.5707963268024898} -1.5567303253382425 -0.5569332500461536" xyz="${reflect*-0.0187648} ${reflect*-0.0301352} ${reflect*-0.12105}"/>
<origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/>
<axis xyz="0 0 1"/>
<limit effort="0.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="0.0"/>
</joint>