Add left wrist

This commit is contained in:
Thomason Zhou 2025-03-10 22:37:42 +09:00
parent fdf02a7284
commit 90f859b54a

View File

@ -116,12 +116,12 @@
<inertia ixx="0.00031417157425298747" ixy="-1.1391566029536723e-05" ixz="-1.883474090056124e-05" iyy="0.001221711435313989" iyz="1.46725418421127e-06" izz="0.0010755135067660488"/> <inertia ixx="0.00031417157425298747" ixy="-1.1391566029536723e-05" ixz="-1.883474090056124e-05" iyy="0.001221711435313989" iyz="1.46725418421127e-06" izz="0.0010755135067660488"/>
</inertial> </inertial>
</link> </link>
<link name="${prefix}link6_right_wrist"> <link name="${prefix}link6">
<visual> <visual>
<!--J6 right_wrist/Part__Feature006.--> <!--J6 right_wrist/Part__Feature006.-->
<origin rpy="-2.1276679791326423 -1.5542266826921929 0" xyz="-0.0485412 -0.0860404 0.437784"/> <origin rpy="${reflect*-2.1276679791326423} ${rotate -1.5542266826921929} ${rotate}" xyz="-0.0485412 -0.0860404 0.437784"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j6v1_mg9rps.dae"/> <mesh filename="package://openarm_two_arms/meshes/${'full_upper_j6v1_mg9rps.dae' if side=='right' else 'full_upper_j6_leftv005_f8km11.dae'}"/>
</geometry> </geometry>
</visual> </visual>
<collision> <collision>
@ -142,7 +142,7 @@
<!--J7 right v002/Part__Feature007.--> <!--J7 right v002/Part__Feature007.-->
<origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/> <origin rpy="0 -0.008758182894510852 0" xyz="0.558839 -0.00358671 -0.0631962"/>
<geometry> <geometry>
<mesh filename="package://openarm_two_arms/meshes/full_upper_j7v1_9yzky6.dae"/> <mesh filename="package://openarm_two_arms/meshes/${'full_upper_j7v1_9yzky6.dae' if side=='right' else 'full_upper_j7_leftv005_8ohvh2.dae'}"/>
</geometry> </geometry>
</visual> </visual>
<collision> <collision>
@ -251,13 +251,13 @@
</joint> </joint>
<joint name="${prefix}rev5" type="revolute"> <joint name="${prefix}rev5" type="revolute">
<parent link="${prefix}link5"/> <parent link="${prefix}link5"/>
<child link="${prefix}link6_right_wrist"/> <child link="${prefix}link6"/>
<origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/> <origin rpy="1.5707963267948473 -0.5569332500492129 1.556730325338251" xyz="-0.133937 0.00188408 -0.0297547"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
<limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/> <limit effort="0.0" lower="-2.0943951023931953" upper="2.0943951023931953" velocity="0.0"/>
</joint> </joint>
<joint name="${prefix}rev6" type="revolute"> <joint name="${prefix}rev6" type="revolute">
<parent link="${prefix}link6_right_wrist"/> <parent link="${prefix}link6"/>
<child link="${prefix}link7"/> <child link="${prefix}link7"/>
<origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/> <origin rpy="-1.5707963268024898 -1.5567303253382425 -0.5569332500461536" xyz="-0.0187648 -0.0301352 -0.12105"/>
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>