|
|
<?xml version="1.0"?> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<robot name="so100"> |
|
|
|
|
|
<material name="green"> |
|
|
<color rgba="0.06 0.4 0.1 1.0" /> |
|
|
</material> |
|
|
<material name="black"> |
|
|
<color rgba="0.1 0.1 0.1 1.0" /> |
|
|
</material> |
|
|
|
|
|
|
|
|
<link name="world" /> |
|
|
|
|
|
|
|
|
<joint name="world_to_base" type="fixed"> |
|
|
<parent link="world" /> |
|
|
<child link="base" /> |
|
|
<origin xyz="0.163038 0.168068 -0.0300817" rpy="0 0 0" /> |
|
|
</joint> |
|
|
|
|
|
|
|
|
<link name="base"> |
|
|
<inertial> |
|
|
<origin xyz="-0.14932 -0.16812 0.065966" rpy="0 0 0" /> |
|
|
<mass value="0.147" /> |
|
|
<inertia ixx="0.000114686" ixy="-4.59787e-07" ixz="4.97151e-06" iyy="0.000136117" |
|
|
iyz="9.75275e-08" izz="0.000130364" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.169402 -0.168167 0.0300817" rpy="1.5708 -1.67685e-15 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/base_motor_holder_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.169402 -0.168167 0.0300817" rpy="1.5708 -1.67685e-15 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/base_motor_holder_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.169402 -0.168068 0.0300817" rpy="1.5708 -1.6144e-15 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/base_so101_v2.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.169402 -0.168068 0.0300817" rpy="1.5708 -1.6144e-15 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/base_so101_v2.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.136702 -0.168068 0.0761817" rpy="-8.21148e-16 7.84513e-18 1.249e-15" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.136702 -0.168068 0.0761817" rpy="-8.21148e-16 7.84513e-18 1.249e-15" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.19402 -0.168267 0.0798817" rpy="1.5708 -1.35493e-14 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.19402 -0.168267 0.0798817" rpy="1.5708 -1.35493e-14 1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="baseframe"> |
|
|
<origin xyz="0 0 0" rpy="0 -0 0" /> |
|
|
<inertial> |
|
|
<origin xyz="0 0 0" rpy="0 0 0" /> |
|
|
<mass value="1e-9" /> |
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="baseframe_frame" type="fixed"> |
|
|
<origin xyz="-0.163038 -0.168068 0.0324817" rpy="1.6144e-15 7.84513e-18 1.33799e-15" /> |
|
|
<parent link="base" /> |
|
|
<child link="baseframe" /> |
|
|
<axis xyz="0 0 0" /> |
|
|
</joint> |
|
|
|
|
|
<link name="shoulder"> |
|
|
<inertial> |
|
|
<origin xyz="-0.0307604 -1.66727e-05 -0.0252713" rpy="0 0 0" /> |
|
|
<mass value="0.100006" /> |
|
|
<inertia ixx="8.3759e-05" ixy="7.55525e-08" ixz="-1.16342e-06" iyy="8.10403e-05" |
|
|
iyz="1.54663e-07" izz="2.39783e-05" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/motor_holder_so101_base_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/motor_holder_so101_base_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 2.35221e-33 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/rotation_pitch_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 2.35221e-33 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/rotation_pitch_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="upper_arm"> |
|
|
<inertial> |
|
|
<origin xyz="-0.0898471 -0.00838224 0.0184089" rpy="0 0 0" /> |
|
|
<mass value="0.103" /> |
|
|
<inertia ixx="4.08002e-05" ixy="-1.97819e-05" ixz="-4.03016e-08" iyy="0.000147318" |
|
|
iyz="8.97326e-09" izz="0.000142487" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -5.27356e-16 -1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -5.27356e-16 -1.5708" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.065085 0.012 0.0182" rpy="3.14159 -0 -1.30911e-30" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/upper_arm_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.065085 0.012 0.0182" rpy="3.14159 -0 -1.30911e-30" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/upper_arm_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="lower_arm"> |
|
|
<inertial> |
|
|
<origin xyz="-0.0980701 0.00324376 0.0182831" rpy="0 0 0" /> |
|
|
<mass value="0.104" /> |
|
|
<inertia ixx="2.87438e-05" ixy="7.41152e-06" ixz="1.26409e-06" iyy="0.000159844" |
|
|
iyz="-4.90188e-08" izz="0.00014529" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 -0 6.67202e-31" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/under_arm_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 -0 6.67202e-31" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/under_arm_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -2.56146e-31" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -2.56146e-31" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/motor_holder_so101_wrist_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-0.1224 0.0052 0.0187" rpy="-3.14159 -7.88861e-31 -3.14159" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-0.1224 0.0052 0.0187" rpy="-3.14159 -7.88861e-31 -3.14159" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="wrist"> |
|
|
<inertial> |
|
|
<origin xyz="-0.000103312 -0.0386143 0.0281156" rpy="0 0 0" /> |
|
|
<mass value="0.079" /> |
|
|
<inertia ixx="3.68263e-05" ixy="1.7893e-08" ixz="-5.28128e-08" iyy="2.5391e-05" |
|
|
iyz="3.6412e-06" izz="2.1e-05" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="5.55112e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="5.55112e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_no_horn_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="0 -0.028 0.0181" rpy="-1.5708 -1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="0 -0.028 0.0181" rpy="-1.5708 -1.5708 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/wrist_roll_pitch_so101_v2.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="gripper"> |
|
|
<inertial> |
|
|
<origin xyz="0.000213627 0.000245138 -0.025187" rpy="0 0 0" /> |
|
|
<mass value="0.087" /> |
|
|
<inertia ixx="2.75087e-05" ixy="-3.35241e-07" ixz="-5.7352e-06" iyy="4.33657e-05" |
|
|
iyz="-5.17847e-08" izz="3.45059e-05" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.19179e-17 -1.66533e-16" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="black" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.19179e-17 -1.66533e-16" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/sts3215_03a_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="0 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="0 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/wrist_roll_follower_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<link name="gripperframe"> |
|
|
<origin xyz="0 0 0" rpy="0 -0 0" /> |
|
|
<inertial> |
|
|
<origin xyz="0 0 0" rpy="0 0 0" /> |
|
|
<mass value="1e-9" /> |
|
|
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0" /> |
|
|
</inertial> |
|
|
</link> |
|
|
<joint name="gripperframe_frame" type="fixed"> |
|
|
<origin xyz="-0.0079 -0.000218121 -0.0981274" rpy="-0 1.5708 0" /> |
|
|
<parent link="gripper" /> |
|
|
<child link="gripperframe" /> |
|
|
<axis xyz="0 0 0" /> |
|
|
</joint> |
|
|
|
|
|
<link name="moving_jaw_so101_v1"> |
|
|
<inertial> |
|
|
<origin xyz="-0.00157495 -0.0300244 0.0192755" rpy="0 0 0" /> |
|
|
<mass value="0.012" /> |
|
|
<inertia ixx="6.61427e-06" ixy="-3.19807e-07" ixz="-5.90717e-09" iyy="1.89032e-06" |
|
|
iyz="-1.09945e-07" izz="5.28738e-06" /> |
|
|
</inertial> |
|
|
|
|
|
<visual> |
|
|
<origin xyz="-5.55112e-17 0 0.0189" rpy="9.53145e-17 6.93889e-18 1.24077e-24" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/moving_jaw_so101_v1.stl" /> |
|
|
</geometry> |
|
|
<material name="green" /> |
|
|
</visual> |
|
|
<collision> |
|
|
<origin xyz="-5.55112e-17 0 0.0189" rpy="9.53145e-17 6.93889e-18 1.24077e-24" /> |
|
|
<geometry> |
|
|
<mesh filename="assets/moving_jaw_so101_v1.stl" /> |
|
|
</geometry> |
|
|
</collision> |
|
|
</link> |
|
|
|
|
|
<joint name="Jaw" type="revolute"> |
|
|
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 3.315 0" /> |
|
|
<parent link="gripper" /> |
|
|
<child link="moving_jaw_so101_v1" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="3.14" upper="4.88692" /> |
|
|
</joint> |
|
|
|
|
|
<joint name="Wrist_Roll" type="revolute"> |
|
|
<origin xyz="2.77556e-16 -0.0611 0.0181" rpy="1.5708 3.1902695 3.14159" /> |
|
|
<parent link="wrist" /> |
|
|
<child link="gripper" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="0.39774" upper="5.9828" /> |
|
|
</joint> |
|
|
|
|
|
<joint name="Wrist_Pitch" type="revolute"> |
|
|
<origin xyz="-0.1349 0.0052 8.44651e-17" rpy="0 0 1.57079" /> |
|
|
<parent link="lower_arm" /> |
|
|
<child link="wrist" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="1.48353" upper="4.79965" /> |
|
|
</joint> |
|
|
|
|
|
<joint name="Elbow" type="revolute"> |
|
|
<origin xyz="-0.11257 -0.028 2.09886e-16" rpy="0 0 4.71239" /> |
|
|
<parent link="upper_arm" /> |
|
|
<child link="lower_arm" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="1.39626" upper="4.71239" /> |
|
|
</joint> |
|
|
|
|
|
<joint name="Pitch" type="revolute"> |
|
|
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 1.5692 0" /> |
|
|
<parent link="shoulder" /> |
|
|
<child link="upper_arm" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="1.39467" upper="4.88692" /> |
|
|
</joint> |
|
|
|
|
|
<joint name="Rotation" type="revolute"> |
|
|
<origin xyz="-0.124202 -0.168068 0.0948817" rpy="3.14159 0 0" /> |
|
|
<parent link="base" /> |
|
|
<child link="shoulder" /> |
|
|
<axis xyz="0 0 1" /> |
|
|
<limit effort="10" velocity="10" lower="1.22014" upper="5.05986" /> |
|
|
</joint> |
|
|
</robot> |