File size: 13,567 Bytes
0c0bb46 | 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 | <?xml version="1.0" ?>
<!-- Generated using onshape-to-robot -->
<!-- Onshape https://cad.onshape.com/documents/7715cc284bb430fe6dab4ffd/w/4fd0791b683777b02f8d975a/e/bbd5da878b987933c7940f7d -->
<mujoco model="so101_old_calib">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<default>
<default class="so101_old_calib">
<joint damping="1" frictionloss="0.1" armature="0.005"/>
<position kp="50"/>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3"/>
</default>
</default>
</default>
<!-- Additional joints_properties.xml -->
<default>
<default class="sts3215">
<geom contype="0" conaffinity="0"/>
<joint damping="0.60" frictionloss="0.052" armature="0.028"/>
<position kp="17.8"/>
</default>
<default class="backlash">
<!-- +/- 0.5° of backlash -->
<joint damping="0.01" frictionloss="0" armature="0.01" limited="true" range="-0.008726646259971648 0.008726646259971648"/>
</default>
</default>
<worldbody>
<!-- Link base -->
<body name="base" pos="0 0 0" quat="1 0 0 0" childclass="so101_old_calib">
<inertial pos="0.020739 0.00204287 0.065966" mass="0.147" fullinertia="0.000136117 0.000114686 0.000130364 4.59787e-07 9.75275e-08 -4.97151e-06"/>
<!-- Part base_motor_holder_so101_v1 -->
<geom type="mesh" class="visual" pos="0.0206915 0.0221255 0.0300817" quat="0.707107 0.707107 7.85046e-16 8.68107e-16" mesh="base_motor_holder_so101_v1" material="base_motor_holder_so101_v1_material"/>
<!-- Part base_so101_v2 -->
<geom type="mesh" class="visual" pos="0.0207909 0.0221255 0.0300817" quat="0.707107 0.707107 -0 -0" mesh="base_so101_v2" material="base_so101_v2_material"/>
<!-- Part sts3215_03a_v1 -->
<geom type="mesh" class="visual" pos="0.0207909 -0.0105745 0.0761817" quat="0.707107 -7.69919e-16 8.95976e-16 -0.707107" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part waveshare_mounting_plate_so101_v2 -->
<geom type="mesh" class="visual" pos="0.0205915 0.0467435 0.0798817" quat="0.707107 0.707107 -3.34318e-15 5.1276e-15" mesh="waveshare_mounting_plate_so101_v2" material="waveshare_mounting_plate_so101_v2_material"/>
<!-- Frame base -->
<site group="3" name="base" pos="0.020791 0.0157608 0.0324817" quat="0 1 0 0"/>
<!-- Link shoulder -->
<body name="shoulder" pos="0.0207909 -0.0230745 0.0948817" quat="7.88629e-16 -0.707107 -0.707107 7.69003e-16">
<!-- Joint from base to shoulder -->
<joint axis="0 0 1" name="shoulder_pan" type="hinge" range="-1.9198621771937616 1.9198621771937634" class="sts3215"/>
<inertial pos="-0.0307604 -1.66727e-05 -0.0252713" mass="0.100006" fullinertia="8.3759e-05 8.10403e-05 2.39783e-05 7.55525e-08 -1.16342e-06 1.54663e-07"/>
<!-- Part sts3215_03a_v1_2 -->
<geom type="mesh" class="visual" pos="-0.0303992 0.000422241 -0.0417" quat="0.5 0.5 0.5 -0.5" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0303992 0.000422241 -0.0417" quat="0.5 0.5 0.5 -0.5" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part motor_holder_so101_base_v1 -->
<geom type="mesh" class="visual" pos="-0.0675992 -0.000177759 0.0158499" quat="0.5 0.5 -0.5 0.5" mesh="motor_holder_so101_base_v1" material="motor_holder_so101_base_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0675992 -0.000177759 0.0158499" quat="0.5 0.5 -0.5 0.5" mesh="motor_holder_so101_base_v1" material="motor_holder_so101_base_v1_material"/>
<!-- Part rotation_pitch_so101_v1 -->
<geom type="mesh" class="visual" pos="0.0122008 2.22413e-05 0.0464" quat="0.707107 -0.707107 0 0" mesh="rotation_pitch_so101_v1" material="rotation_pitch_so101_v1_material"/>
<geom type="mesh" class="collision" pos="0.0122008 2.22413e-05 0.0464" quat="0.707107 -0.707107 0 0" mesh="rotation_pitch_so101_v1" material="rotation_pitch_so101_v1_material"/>
<!-- Link upper_arm -->
<body name="upper_arm" pos="-0.0303992 -0.0182778 -0.0542" quat="0.5 -0.5 0.5 0.5">
<!-- Joint from shoulder to upper_arm -->
<joint axis="0 0 1" name="shoulder_lift" type="hinge" range="-3.31612557878923 0.1745329251994294" class="sts3215"/>
<inertial pos="-0.00838224 0.0898471 0.0184089" mass="0.103" fullinertia="0.000147318 4.08002e-05 0.000142487 1.97819e-05 8.97326e-09 4.03016e-08"/>
<!-- Part sts3215_03a_v1_3 -->
<geom type="mesh" class="visual" pos="-0.0155 0.11257 0.0187" quat="4.91381e-16 3.1572e-16 -1 6.21545e-16" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0155 0.11257 0.0187" quat="4.91381e-16 3.1572e-16 -1 6.21545e-16" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part upper_arm_so101_v1 -->
<geom type="mesh" class="visual" pos="0.012 0.065085 0.0182" quat="5.77339e-30 0.707107 -0.707107 -1.0267e-29" mesh="upper_arm_so101_v1" material="upper_arm_so101_v1_material"/>
<geom type="mesh" class="collision" pos="0.012 0.065085 0.0182" quat="5.77339e-30 0.707107 -0.707107 -1.0267e-29" mesh="upper_arm_so101_v1" material="upper_arm_so101_v1_material"/>
<!-- Link lower_arm -->
<body name="lower_arm" pos="-0.028 0.11257 1.24466e-16" quat="2.34133e-16 -3.33458e-16 -3.62568e-16 -1">
<!-- Joint from upper_arm to lower_arm -->
<joint axis="0 0 1" name="elbow_flex" type="hinge" range="-0.17453292519941607 3.14159265358981" class="sts3215"/>
<inertial pos="-0.00324376 -0.0980701 0.0182831" mass="0.104" fullinertia="0.000159844 2.87438e-05 0.00014529 -7.41152e-06 4.90188e-08 1.26409e-06"/>
<!-- Part under_arm_so101_v1 -->
<geom type="mesh" class="visual" pos="0.032 -0.0648499 0.0182" quat="7.0875e-26 0.707107 0.707107 -7.0875e-26" mesh="under_arm_so101_v1" material="under_arm_so101_v1_material"/>
<geom type="mesh" class="collision" pos="0.032 -0.0648499 0.0182" quat="7.0875e-26 0.707107 0.707107 -7.0875e-26" mesh="under_arm_so101_v1" material="under_arm_so101_v1_material"/>
<!-- Part motor_holder_so101_wrist_v1 -->
<geom type="mesh" class="visual" pos="0.032 -0.0648499 0.018" quat="1.01856e-15 -0.707107 -0.707107 2.26153e-16" mesh="motor_holder_so101_wrist_v1" material="motor_holder_so101_wrist_v1_material"/>
<geom type="mesh" class="collision" pos="0.032 -0.0648499 0.018" quat="1.01856e-15 -0.707107 -0.707107 2.26153e-16" mesh="motor_holder_so101_wrist_v1" material="motor_holder_so101_wrist_v1_material"/>
<!-- Part sts3215_03a_v1_4 -->
<geom type="mesh" class="visual" pos="-0.0052 -0.1224 0.0187" quat="1.64704e-15 0.707107 -0.707107 1.29806e-15" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0052 -0.1224 0.0187" quat="1.64704e-15 0.707107 -0.707107 1.29806e-15" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Link wrist -->
<body name="wrist" pos="-0.0052 -0.1349 3.40439e-16" quat="1 -3.94784e-16 1.66357e-15 3.78078e-09">
<!-- Joint from lower_arm to wrist -->
<joint axis="0 0 1" name="wrist_flex" type="hinge" range="-1.6580627969561947 1.6580627818330316" class="sts3215"/>
<inertial pos="-0.000103312 -0.0386143 0.0281156" mass="0.079" fullinertia="3.68263e-05 2.5391e-05 2.1e-05 1.7893e-08 -5.28128e-08 3.6412e-06"/>
<!-- Part sts3215_03a_no_horn_v1 -->
<geom type="mesh" class="visual" pos="0 -0.0424 0.0306" quat="0.5 0.5 0.5 -0.5" mesh="sts3215_03a_no_horn_v1" material="sts3215_03a_no_horn_v1_material"/>
<geom type="mesh" class="collision" pos="0 -0.0424 0.0306" quat="0.5 0.5 0.5 -0.5" mesh="sts3215_03a_no_horn_v1" material="sts3215_03a_no_horn_v1_material"/>
<!-- Part wrist_roll_pitch_so101_v2 -->
<geom type="mesh" class="visual" pos="-2.77556e-17 -0.028 0.0181" quat="0.5 -0.5 -0.5 -0.5" mesh="wrist_roll_pitch_so101_v2" material="wrist_roll_pitch_so101_v2_material"/>
<geom type="mesh" class="collision" pos="-2.77556e-17 -0.028 0.0181" quat="0.5 -0.5 -0.5 -0.5" mesh="wrist_roll_pitch_so101_v2" material="wrist_roll_pitch_so101_v2_material"/>
<!-- Link gripper -->
<body name="gripper" pos="2.77556e-17 -0.0611 0.0181" quat="3.31663e-08 -3.31663e-08 -0.707107 -0.707107">
<!-- Joint from wrist to gripper -->
<joint axis="0 0 1" name="wrist_roll" type="hinge" range="-2.7925268969992394 2.792526709382615" class="sts3215"/>
<inertial pos="0.000213627 0.000245138 -0.025187" mass="0.087" fullinertia="2.75087e-05 4.33657e-05 3.45059e-05 -3.35241e-07 -5.7352e-06 -5.17847e-08"/>
<!-- Part sts3215_03a_v1_5 -->
<geom type="mesh" class="visual" pos="0.0077 0.0001 -0.0234" quat="0.707107 -0.707107 6.48145e-15 1.60424e-15" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="0.0077 0.0001 -0.0234" quat="0.707107 -0.707107 6.48145e-15 1.60424e-15" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part wrist_roll_follower_so101_v1 -->
<geom type="mesh" class="visual" pos="1.11022e-16 -0.000218214 0.000949706" quat="0 1 0 0" mesh="wrist_roll_follower_so101_v1" material="wrist_roll_follower_so101_v1_material"/>
<geom type="mesh" class="collision" pos="1.11022e-16 -0.000218214 0.000949706" quat="0 1 0 0" mesh="wrist_roll_follower_so101_v1" material="wrist_roll_follower_so101_v1_material"/>
<!-- Frame gripper -->
<site group="3" name="gripper" pos="-0.0079 -0.000218121 -0.0981274" quat="0.5 -0.5 0.5 -0.5"/>
<!-- Link moving_jaw_so101_v1 -->
<body name="moving_jaw_so101_v1" pos="0.0202 0.0188 -0.0234" quat="0.707107 0.707107 0 -4.88629e-17">
<!-- Joint from gripper to moving_jaw_so101_v1 -->
<joint axis="0 0 1" name="gripper" type="hinge" range="-0.17453292519941963 1.7453292519943429" class="sts3215"/>
<inertial pos="-0.00157495 -0.0300244 0.0192755" mass="0.012" fullinertia="6.61427e-06 1.89032e-06 5.28738e-06 -3.19807e-07 -5.90717e-09 -1.09945e-07"/>
<!-- Part moving_jaw_so101_v1 -->
<geom type="mesh" class="visual" pos="0 1.89351e-17 0.0189" quat="1 0 1.11022e-16 8.14512e-24" mesh="moving_jaw_so101_v1" material="moving_jaw_so101_v1_material"/>
<geom type="mesh" class="collision" pos="0 1.89351e-17 0.0189" quat="1 0 1.11022e-16 8.14512e-24" mesh="moving_jaw_so101_v1" material="moving_jaw_so101_v1_material"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<asset>
<mesh file="motor_holder_so101_wrist_v1.stl"/>
<mesh file="moving_jaw_so101_v1.stl"/>
<mesh file="wrist_roll_follower_so101_v1.stl"/>
<mesh file="rotation_pitch_so101_v1.stl"/>
<mesh file="base_so101_v2.stl"/>
<mesh file="motor_holder_so101_base_v1.stl"/>
<mesh file="upper_arm_so101_v1.stl"/>
<mesh file="sts3215_03a_v1.stl"/>
<mesh file="under_arm_so101_v1.stl"/>
<mesh file="waveshare_mounting_plate_so101_v2.stl"/>
<mesh file="base_motor_holder_so101_v1.stl"/>
<mesh file="wrist_roll_pitch_so101_v2.stl"/>
<mesh file="sts3215_03a_no_horn_v1.stl"/>
<material name="base_motor_holder_so101_v1_material" rgba="1 0.82 0.12 1"/>
<material name="base_so101_v2_material" rgba="1 0.82 0.12 1"/>
<material name="sts3215_03a_v1_material" rgba="0.1 0.1 0.1 1"/>
<material name="waveshare_mounting_plate_so101_v2_material" rgba="1 0.82 0.12 1"/>
<material name="motor_holder_so101_base_v1_material" rgba="1 0.82 0.12 1"/>
<material name="rotation_pitch_so101_v1_material" rgba="1 0.82 0.12 1"/>
<material name="upper_arm_so101_v1_material" rgba="1 0.82 0.12 1"/>
<material name="under_arm_so101_v1_material" rgba="1 0.82 0.12 1"/>
<material name="motor_holder_so101_wrist_v1_material" rgba="1 0.82 0.12 1"/>
<material name="sts3215_03a_no_horn_v1_material" rgba="0.1 0.1 0.1 1"/>
<material name="wrist_roll_pitch_so101_v2_material" rgba="1 0.82 0.12 1"/>
<material name="wrist_roll_follower_so101_v1_material" rgba="1 0.82 0.12 1"/>
<material name="moving_jaw_so101_v1_material" rgba="1 0.82 0.12 1"/>
</asset>
<actuator>
<position class="sts3215" name="shoulder_pan" joint="shoulder_pan" forcerange="-3.35 3.35" ctrlrange="-1.91986 1.91986"/>
<position class="sts3215" name="shoulder_lift" joint="shoulder_lift" forcerange="-3.35 3.35" ctrlrange="-3.31612 0.17453"/>
<position class="sts3215" name="elbow_flex" joint="elbow_flex" forcerange="-3.35 3.35" ctrlrange="-0.17453 3.14159"/>
<position class="sts3215" name="wrist_flex" joint="wrist_flex" forcerange="-3.35 3.35" ctrlrange="-1.65806 1.65806"/>
<position class="sts3215" name="wrist_roll" joint="wrist_roll" forcerange="-3.35 3.35" ctrlrange="-2.79252 2.79252"/>
<position class="sts3215" name="gripper" joint="gripper" forcerange="-3.35 3.35" ctrlrange="-0.17453 1.74533"/>
</actuator>
<equality/>
</mujoco>
|