Link 5 checkpoint
This commit is contained in:
parent
213a35fb78
commit
45f5e21513
@ -97,22 +97,22 @@
|
|||||||
<link name="${prefix}link5">
|
<link name="${prefix}link5">
|
||||||
<visual>
|
<visual>
|
||||||
<!--J5 v003/Part__Feature005.-->
|
<!--J5 v003/Part__Feature005.-->
|
||||||
<origin rpy="0 -0.008758182894317394 0" xyz="0.303864 0.0 -0.128451"/>
|
<origin rpy="0 ${reflect*-0.008758182894317394} 0" xyz="${reflect*0.303864} 0.0 ${-0.128451 if side=='right' else -0.0689415"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<mesh filename="package://openarm_two_arms/meshes/full_upper_j5v2_ckk9an.dae"/>
|
<mesh filename="package://openarm_two_arms/meshes/full_upper_j5v2_ckk9an.dae"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<!--bound_obj__right_link5__col_J5_v2__BoundBox/col_J5_v2__BoundBox.-->
|
<!--bound_obj__right_link5__col_J5_v2__BoundBox/col_J5_v2__BoundBox.-->
|
||||||
<origin rpy="0 -0.008758182894316818 0" xyz="-0.0542814 0.00265291 -0.0302022"/>
|
<origin rpy="0 ${reflect*-0.008758182894316818} 0" xyz="${reflect*-0.0542814} 0.00265291 ${reflect*-0.0302022}"/>
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
|
<box size="0.16827213220625828 0.06430555048399171 0.08257859967140947"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="0.4086748254352304"/>
|
<mass value="0.4086748254352304"/>
|
||||||
<origin rpy="0 -0.008758182894316905 0" xyz="-0.0831891 0.00251789 -0.0290107"/>
|
<origin rpy="0 ${reflect*-0.008758182894316905} 0" xyz="${reflect*-0.0831891} 0.00251789 ${reflect*-0.0290107}"/>
|
||||||
<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="${reflect*-1.1391566029536723e-05}" ixz="${reflect*-1.883474090056124e-05}" iyy="0.001221711435313989" iyz="${reflect*1.46725418421127e-06}" izz="0.0010755135067660488"/>
|
||||||
</inertial>
|
</inertial>
|
||||||
</link>
|
</link>
|
||||||
<link name="${prefix}link6_right_wrist">
|
<link name="${prefix}link6_right_wrist">
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user