Lerobot/docker/visualize/assets/SO101/so101_new_calib.urdf
2025-12-11 14:11:41 +08:00

453 lines
16 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<!-- Generated using onshape-to-robot -->
<!-- Onshape https://cad.onshape.com/documents/7715cc284bb430fe6dab4ffd/w/4fd0791b683777b02f8d975a/e/826c553ede3b7592eb9ca800 -->
<robot name="so101_new_calib">
<!-- Materials -->
<material name="3d_printed">
<color rgba="1.0 0.82 0.12 1.0"/>
</material>
<material name="sts3215">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<!-- Link base -->
<link name="base_link">
<inertial>
<origin xyz="0.0137179 -5.19711e-05 0.0334843" 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>
<!-- Part base_motor_holder_so101_v1 -->
<visual>
<origin xyz="-0.00636471 -9.94414e-05 -0.0024" rpy="1.5708 -1.67685e-15 1.5708"/>
<geometry>
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="-0.00636471 -9.94414e-05 -0.0024" rpy="1.5708 -1.67685e-15 1.5708"/>
<geometry>
<mesh filename="assets/base_motor_holder_so101_v1.stl"/>
</geometry>
</collision>
<!-- Part base_so101_v2 -->
<visual>
<origin xyz="-0.00636471 -8.97657e-09 -0.0024" rpy="1.5708 -2.78073e-29 1.5708"/>
<geometry>
<mesh filename="assets/base_so101_v2.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="-0.00636471 -8.97657e-09 -0.0024" rpy="1.5708 -2.78073e-29 1.5708"/>
<geometry>
<mesh filename="assets/base_so101_v2.stl"/>
</geometry>
</collision>
<!-- Part sts3215_03a_v1 -->
<visual>
<origin xyz="0.0263353 -8.97657e-09 0.0437" rpy="-8.21148e-16 7.84513e-18 1.249e-15"/>
<geometry>
<mesh filename="assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215"/>
</visual>
<collision>
<origin xyz="0.0263353 -8.97657e-09 0.0437" rpy="-8.21148e-16 7.84513e-18 1.249e-15"/>
<geometry>
<mesh filename="assets/sts3215_03a_v1.stl"/>
</geometry>
</collision>
<!-- Part waveshare_mounting_plate_so101_v2 -->
<visual>
<origin xyz="-0.0309827 -0.000199441 0.0474" rpy="1.5708 -1.35493e-14 1.5708"/>
<geometry>
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="-0.0309827 -0.000199441 0.0474" rpy="1.5708 -1.35493e-14 1.5708"/>
<geometry>
<mesh filename="assets/waveshare_mounting_plate_so101_v2.stl"/>
</geometry>
</collision>
</link>
<!-- Link shoulder -->
<link name="shoulder_link">
<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>
<!-- Part sts3215_03a_v1_2 -->
<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="sts3215"/>
</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>
<!-- Part motor_holder_so101_base_v1 -->
<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="3d_printed"/>
</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>
<!-- Part rotation_pitch_so101_v1 -->
<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="3d_printed"/>
</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 upper_arm -->
<link name="upper_arm_link">
<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>
<!-- Part sts3215_03a_v1_3 -->
<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="sts3215"/>
</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>
<!-- Part upper_arm_so101_v1 -->
<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="3d_printed"/>
</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 lower_arm -->
<link name="lower_arm_link">
<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>
<!-- Part under_arm_so101_v1 -->
<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="3d_printed"/>
</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>
<!-- Part motor_holder_so101_wrist_v1 -->
<visual>
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -1.83387e-30"/>
<geometry>
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="-0.0648499 -0.032 0.018" rpy="-3.14159 -2.55351e-15 -1.83387e-30"/>
<geometry>
<mesh filename="assets/motor_holder_so101_wrist_v1.stl"/>
</geometry>
</collision>
<!-- Part sts3215_03a_v1_4 -->
<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="sts3215"/>
</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 wrist -->
<link name="wrist_link">
<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>
<!-- Part sts3215_03a_no_horn_v1 -->
<visual>
<origin xyz="8.32667e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
</geometry>
<material name="sts3215"/>
</visual>
<collision>
<origin xyz="8.32667e-17 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="assets/sts3215_03a_no_horn_v1.stl"/>
</geometry>
</collision>
<!-- Part wrist_roll_pitch_so101_v2 -->
<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="3d_printed"/>
</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 gripper -->
<link name="gripper_link">
<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>
<!-- Part sts3215_03a_v1_5 -->
<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="sts3215"/>
</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>
<!-- Part wrist_roll_follower_so101_v1 -->
<visual>
<origin xyz="8.32667e-17 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0"/>
<geometry>
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="8.32667e-17 -0.000218214 0.000949706" rpy="-3.14159 -5.55112e-17 0"/>
<geometry>
<mesh filename="assets/wrist_roll_follower_so101_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Gripper frame (dummy link + fixed joint) -->
<link name="gripper_frame_link">
<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="gripper_frame_joint" type="fixed">
<origin xyz="-0.0079 -0.000218121 -0.0981274" rpy="0 3.14159 0"/>
<parent link="gripper_link"/>
<child link="gripper_frame_link"/>
<axis xyz="0 0 0"/>
</joint>
<!-- Link moving_jaw_so101_v1 -->
<link name="moving_jaw_so101_v1_link">
<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>
<!-- Part moving_jaw_so101_v1 -->
<visual>
<origin xyz="-5.55112e-17 -5.55112e-17 0.0189" rpy="9.53145e-17 6.93889e-18 1.24077e-24"/>
<geometry>
<mesh filename="assets/moving_jaw_so101_v1.stl"/>
</geometry>
<material name="3d_printed"/>
</visual>
<collision>
<origin xyz="-5.55112e-17 -5.55112e-17 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 from gripper to moving_jaw_so101_v1 -->
<joint name="gripper" type="revolute">
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 -5.24284e-08 -1.41553e-15"/>
<parent link="gripper_link"/>
<child link="moving_jaw_so101_v1_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-0.174533" upper="1.74533"/>
</joint>
<transmission name="gripper_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="gripper">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor6">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Joint from wrist to gripper -->
<joint name="wrist_roll" type="revolute">
<origin xyz="5.55112e-17 -0.0611 0.0181" rpy="1.5708 0.0486795 3.14159"/>
<parent link="wrist_link"/>
<child link="gripper_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-2.74385" upper="2.84121"/>
</joint>
<transmission name="wrist_roll_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_roll">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor5">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Joint from lower_arm to wrist -->
<joint name="wrist_flex" type="revolute">
<origin xyz="-0.1349 0.0052 3.62355e-17" rpy="4.02456e-15 8.67362e-16 -1.5708"/>
<parent link="lower_arm_link"/>
<child link="wrist_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.65806" upper="1.65806"/>
</joint>
<transmission name="wrist_flex_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="wrist_flex">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor4">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Joint from upper_arm to lower_arm -->
<!-- Note: 5-degree calibration offset applied to joint limits -->
<joint name="elbow_flex" type="revolute">
<origin xyz="-0.11257 -0.028 1.73763e-16" rpy="-3.63608e-16 8.74301e-16 1.5708"/>
<parent link="upper_arm_link"/>
<child link="lower_arm_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.69" upper="1.69"/>
</joint>
<transmission name="elbow_flex_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="elbow_flex">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor3">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Joint from shoulder to upper_arm -->
<joint name="shoulder_lift" type="revolute">
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="-1.5708 -1.5708 0"/>
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.74533" upper="1.74533"/>
</joint>
<transmission name="shoulder_lift_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_lift">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor2">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Joint from base to shoulder -->
<joint name="shoulder_pan" type="revolute">
<origin xyz="0.0388353 -8.97657e-09 0.0624" rpy="3.14159 4.18253e-17 -3.14159"/>
<parent link="base_link"/>
<child link="shoulder_link"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.91986" upper="1.91986"/>
</joint>
<transmission name="shoulder_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="shoulder_pan">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="motor1">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>