Add SO101 mujoco and urdf

This commit is contained in:
Pepijn
2025-05-12 11:26:28 +02:00
parent a1ce4cb530
commit 9d92eb2a6c
76 changed files with 800 additions and 0 deletions

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "84d8ae1881704ebae1ffb70a",
"documentMicroversion": "0eea3500852bdb2f58b1cb79",
"documentVersion": "a5c3b0dfaa52ddd6829011cd",
"elementId": "22efbe4e0bef24fcd20f96e5",
"fullConfiguration": "default",
"id": "MCOhripg0ry51VlsC",
"isStandardContent": false,
"name": "Base_motor_holder_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "bf61a6bc85b1d1a8bf9ea51b",
"documentMicroversion": "20484d37162a32a8a41a37f2",
"documentVersion": "25801b070e5b360715de8a30",
"elementId": "312f32f0073fa6e8e36fba7a",
"fullConfiguration": "default",
"id": "MY69cJlqvSzIiODdH",
"isStandardContent": false,
"name": "Base_SO101 v2 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "652d5731024e57367badfda6",
"documentMicroversion": "56a8b8013480c176fd87df8d",
"documentVersion": "984ac31c92cac3664c8effb3",
"elementId": "6fb7b7f9315511b548d670ff",
"fullConfiguration": "default",
"id": "Mf4ZebMr4BkShucFj",
"isStandardContent": false,
"name": "Motor_holder_SO101_Base v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "4bd66da73cacb4d946d43e44",
"documentMicroversion": "2bf56247e58b70e90806e318",
"documentVersion": "df78bb7089f1de7d5588d238",
"elementId": "d7dfe76e402c21bbd8124e43",
"fullConfiguration": "default",
"id": "MN9BZ1p69dQQtKTjq",
"isStandardContent": false,
"name": "Motor_holder_SO101_Wrist v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "46218c02ef80d36172edbb35",
"documentMicroversion": "68b7d387e2500c451586ae59",
"documentVersion": "79c101d1a0207b77362b561a",
"elementId": "d4b1411d5d7333298f6e2458",
"fullConfiguration": "default",
"id": "MrHPLr9hZkrXwcSA4",
"isStandardContent": false,
"name": "Moving_Jaw_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "14078aa6723c502d07d6902e",
"documentMicroversion": "c0fca717407275159bcc6ed7",
"documentVersion": "3d9a887ff68fa477d98162b8",
"elementId": "43d24b3857ff686b275578bf",
"fullConfiguration": "default",
"id": "MrQ6Kmk9QDZlwbp95",
"isStandardContent": false,
"name": "Rotation_Pitch_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "56e5f3702dad85e17841d2e2",
"documentMicroversion": "7958a6acbc8e0d0a0a611746",
"documentVersion": "29a4c51b8bf277a22743a333",
"elementId": "8c14fb13a6557ec89ff5d227",
"fullConfiguration": "default",
"id": "MOcaIFg8XgL+Ybg9z",
"isStandardContent": false,
"name": "STS3215_03a_no_horn v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "d2941bdba816affebdc6d6f0",
"documentMicroversion": "5904ef3cea04a0d0bc88b698",
"documentVersion": "dd4f7470101215836a4ae8c9",
"elementId": "e670b72d49b06f88fad5dbd8",
"fullConfiguration": "default",
"id": "M5vQNpe0onRFueych",
"isStandardContent": false,
"name": "STS3215_03a v1 <5>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "9f5d6db47eb112442b9f130f",
"documentMicroversion": "e99cf45162e34789bd99512b",
"documentVersion": "817ebf29c5663d412edc0753",
"elementId": "2813aaffe3c8a342616d3527",
"fullConfiguration": "default",
"id": "M9yAEiX02J3c4HqXa",
"isStandardContent": false,
"name": "Under_arm_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "57f3eae43434311c28ac752b",
"documentMicroversion": "33eeab136e831427f0f0ca74",
"documentVersion": "435d47b71ef26075bf82672c",
"elementId": "a8e0c02dc43f7ccb373c52e4",
"fullConfiguration": "default",
"id": "Ml3rwO4kV53jDRgcs",
"isStandardContent": false,
"name": "Upper_arm_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "066f8b5064455ec46759cd8c",
"documentMicroversion": "04c5790374bf3edfbbb7e818",
"documentVersion": "408440a116f7d8700bbb11c2",
"elementId": "dc35e56269e36de39738b34d",
"fullConfiguration": "default",
"id": "MjhXxhyF1+iAgCtUh",
"isStandardContent": false,
"name": "WaveShare_Mounting_Plate_SO101 v2 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "e02f1e1d3fdd766a19a55890",
"documentMicroversion": "03f1dfc090db6bbecdb14475",
"documentVersion": "8a15327cfbde0344e0951076",
"elementId": "2317bd70c68862eeebd64492",
"fullConfiguration": "default",
"id": "MpI0voU28BOAZ6D9x",
"isStandardContent": false,
"name": "Wrist_Roll_Follower_SO101 v1 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

View File

@@ -0,0 +1,14 @@
{
"configuration": "default",
"documentId": "eb144d215e733b8dbbb50b81",
"documentMicroversion": "4fef760722dee3a9b5ff19b1",
"documentVersion": "5880c1e9413206cac10772d0",
"elementId": "3c22c2c23cb0ce545b9df2ba",
"fullConfiguration": "default",
"id": "Ma99J59HxnSe2TArb",
"isStandardContent": false,
"name": "Wrist_Roll_Pitch_SO101 v2 <1>",
"partId": "JFD",
"suppressed": false,
"type": "Part"
}

Binary file not shown.

View File

@@ -0,0 +1,13 @@
<!-- Taken from https://github.com/apirrone/Open_Duck_Playground -->
<default>
<default class="sts3215">
<geom contype="0" conaffinity="0"/>
<joint damping="0.60" frictionloss="0.052" armature="0.028"/>
<position kp="17.8" kv="0.0" forcerange="-3.35 3.35"/>
</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>

View File

@@ -0,0 +1,24 @@
<mujoco model="scene">
<include file="so101.xml" />
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0" />
<rgba haze="0.15 0.25 0.35 1" />
<global azimuth="160" elevation="-20" />
</visual>
<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512"
height="3072" />
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4"
rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300" />
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5"
reflectance="0.2" />
</asset>
<worldbody>
<light pos="0 0 3.5" dir="0 0 -1" directional="true" />
<geom name="floor" size="0 0 0.05" pos="0 0 0" type="plane" material="groundplane" />
</worldbody>
</mujoco>

422
Simulation/SO101/so101.urdf Normal file
View File

@@ -0,0 +1,422 @@
<?xml version="1.0" ?>
<!-- Generated using onshape-to-robot -->
<robot name="so101">
<!-- Link base -->
<link name="base">
<inertial>
<origin xyz="0.020739 0.00204287 0.065966" rpy="0 0 0"/>
<mass value="0.147"/>
<inertia ixx="0.000136117" ixy="4.59787e-07" ixz="9.75275e-08" iyy="0.000114686" iyz="-4.97151e-06" izz="0.000130364"/>
</inertial>
<!-- Part base_motor_holder_so101_v1 -->
<visual>
<origin xyz="0.0206915 0.0221255 0.0300817" rpy="1.5708 -1.23909e-16 2.33147e-15"/>
<geometry>
<mesh filename="package://assets/base_motor_holder_so101_v1.stl"/>
</geometry>
<material name="base_motor_holder_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0206915 0.0221255 0.0300817" rpy="1.5708 -1.23909e-16 2.33147e-15"/>
<geometry>
<mesh filename="package://assets/base_motor_holder_so101_v1.stl"/>
</geometry>
</collision>
<!-- Part base_so101_v2 -->
<visual>
<origin xyz="0.0207909 0.0221255 0.0300817" rpy="1.5708 -0 0"/>
<geometry>
<mesh filename="package://assets/base_so101_v2.stl"/>
</geometry>
<material name="base_so101_v2_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0207909 0.0221255 0.0300817" rpy="1.5708 -0 0"/>
<geometry>
<mesh filename="package://assets/base_so101_v2.stl"/>
</geometry>
</collision>
<!-- Part sts3215_03a_v1 -->
<visual>
<origin xyz="0.0207909 -0.0105745 0.0761817" rpy="-2.20282e-15 2.77556e-17 -1.5708"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215_03a_v1_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0207909 -0.0105745 0.0761817" rpy="-2.20282e-15 2.77556e-17 -1.5708"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
</collision>
<!-- Part waveshare_mounting_plate_so101_v2 -->
<visual>
<origin xyz="0.0205915 0.0467435 0.0798817" rpy="1.5708 -1.21716e-14 2.33147e-15"/>
<geometry>
<mesh filename="package://assets/waveshare_mounting_plate_so101_v2.stl"/>
</geometry>
<material name="waveshare_mounting_plate_so101_v2_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0205915 0.0467435 0.0798817" rpy="1.5708 -1.21716e-14 2.33147e-15"/>
<geometry>
<mesh filename="package://assets/waveshare_mounting_plate_so101_v2.stl"/>
</geometry>
</collision>
</link>
<!-- Frame base (dummy link + fixed joint) -->
<link name="base">
<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="base_frame" type="fixed">
<origin xyz="0.020791 0.0157608 0.0324817" rpy="-3.14159 -9.52796e-30 -2.64454e-46"/>
<parent link="base"/>
<child link="base"/>
<axis xyz="0 0 0"/>
</joint>
<!-- Link shoulder -->
<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>
<!-- Part sts3215_03a_v1_2 -->
<visual>
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215_03a_v1_2_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.0303992 0.000422241 -0.0417" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="package://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="package://assets/motor_holder_so101_base_v1.stl"/>
</geometry>
<material name="motor_holder_so101_base_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.0675992 -0.000177759 0.0158499" rpy="1.5708 -1.5708 0"/>
<geometry>
<mesh filename="package://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 -0 0"/>
<geometry>
<mesh filename="package://assets/rotation_pitch_so101_v1.stl"/>
</geometry>
<material name="rotation_pitch_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0122008 2.22413e-05 0.0464" rpy="-1.5708 -0 0"/>
<geometry>
<mesh filename="package://assets/rotation_pitch_so101_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Link upper_arm -->
<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>
<!-- Part sts3215_03a_v1_3 -->
<visual>
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -1.31839e-15 -1.5708"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215_03a_v1_3_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.11257 -0.0155 0.0187" rpy="-3.14159 -1.31839e-15 -1.5708"/>
<geometry>
<mesh filename="package://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 0"/>
<geometry>
<mesh filename="package://assets/upper_arm_so101_v1.stl"/>
</geometry>
<material name="upper_arm_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.065085 0.012 0.0182" rpy="-3.14159 -0 0"/>
<geometry>
<mesh filename="package://assets/upper_arm_so101_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Link lower_arm -->
<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>
<!-- Part under_arm_so101_v1 -->
<visual>
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 9.86076e-32 7.88861e-31"/>
<geometry>
<mesh filename="package://assets/under_arm_so101_v1.stl"/>
</geometry>
<material name="under_arm_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.0648499 -0.032 0.0182" rpy="3.14159 9.86076e-32 7.88861e-31"/>
<geometry>
<mesh filename="package://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 1.58207e-15 7.14706e-16"/>
<geometry>
<mesh filename="package://assets/motor_holder_so101_wrist_v1.stl"/>
</geometry>
<material name="motor_holder_so101_wrist_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.0648499 -0.032 0.018" rpy="3.14159 1.58207e-15 7.14706e-16"/>
<geometry>
<mesh filename="package://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 -6.93889e-15 -3.14159"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215_03a_v1_4_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="-0.1224 0.0052 0.0187" rpy="-3.14159 -6.93889e-15 -3.14159"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Link wrist -->
<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>
<!-- Part sts3215_03a_no_horn_v1 -->
<visual>
<origin xyz="0 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_no_horn_v1.stl"/>
</geometry>
<material name="sts3215_03a_no_horn_v1_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 -0.0424 0.0306" rpy="1.5708 1.5708 0"/>
<geometry>
<mesh filename="package://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="package://assets/wrist_roll_pitch_so101_v2.stl"/>
</geometry>
<material name="wrist_roll_pitch_so101_v2_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 -0.028 0.0181" rpy="-1.5708 -1.5708 0"/>
<geometry>
<mesh filename="package://assets/wrist_roll_pitch_so101_v2.stl"/>
</geometry>
</collision>
</link>
<!-- Link gripper -->
<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>
<!-- Part sts3215_03a_v1_5 -->
<visual>
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.55112e-17 -1.38213e-14"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
<material name="sts3215_03a_v1_5_material">
<color rgba="0.627451 0.627451 0.627451 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0077 0.0001 -0.0234" rpy="-1.5708 -5.55112e-17 -1.38213e-14"/>
<geometry>
<mesh filename="package://assets/sts3215_03a_v1.stl"/>
</geometry>
</collision>
<!-- Part wrist_roll_follower_so101_v1 -->
<visual>
<origin xyz="5.55112e-17 -0.000218214 0.000949706" rpy="3.14159 -5.55112e-17 -2.54515e-32"/>
<geometry>
<mesh filename="package://assets/wrist_roll_follower_so101_v1.stl"/>
</geometry>
<material name="wrist_roll_follower_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="5.55112e-17 -0.000218214 0.000949706" rpy="3.14159 -5.55112e-17 -2.54515e-32"/>
<geometry>
<mesh filename="package://assets/wrist_roll_follower_so101_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Frame gripper (dummy link + fixed joint) -->
<link name="gripper">
<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" type="fixed">
<origin xyz="-0.0079 -0.000218121 -0.0981274" rpy="-1.5708 -0 -1.5708"/>
<parent link="gripper"/>
<child link="gripper"/>
<axis xyz="0 0 0"/>
</joint>
<!-- Link moving_jaw_so101_v1 -->
<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>
<!-- Part moving_jaw_so101_v1 -->
<visual>
<origin xyz="2.77556e-17 -1.31397e-17 0.0189" rpy="9.53145e-17 1.02153e-32 1.57772e-30"/>
<geometry>
<mesh filename="package://assets/moving_jaw_so101_v1.stl"/>
</geometry>
<material name="moving_jaw_so101_v1_material">
<color rgba="0.964706 0.964706 0.952941 1.0"/>
</material>
</visual>
<collision>
<origin xyz="2.77556e-17 -1.31397e-17 0.0189" rpy="9.53145e-17 1.02153e-32 1.57772e-30"/>
<geometry>
<mesh filename="package://assets/moving_jaw_so101_v1.stl"/>
</geometry>
</collision>
</link>
<!-- Joint from gripper to moving_jaw_so101_v1 -->
<joint name="6" type="revolute">
<origin xyz="0.0202 0.0188 -0.0234" rpy="1.5708 4.00612e-15 -2.2678e-16"/>
<parent link="gripper"/>
<child link="moving_jaw_so101_v1"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-0.261799" upper="1.74533"/>
</joint>
<!-- Joint from wrist to gripper -->
<joint name="5" type="revolute">
<origin xyz="-2.77556e-17 -0.0611 0.0181" rpy="1.5708 2.18394e-16 3.14159"/>
<parent link="wrist"/>
<child link="gripper"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-2.79253" upper="2.79253"/>
</joint>
<!-- Joint from lower_arm to wrist -->
<joint name="4" type="revolute">
<origin xyz="-0.1349 0.0052 3.21791e-16" rpy="-1.11022e-16 1.11022e-16 -1.5708"/>
<parent link="lower_arm"/>
<child link="wrist"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.65806" upper="1.65806"/>
</joint>
<!-- Joint from upper_arm to lower_arm -->
<joint name="3" type="revolute">
<origin xyz="-0.11257 -0.028 2.29417e-16" rpy="-2.26208e-15 -1.3739e-15 3.14159"/>
<parent link="upper_arm"/>
<child link="lower_arm"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-3.22886" upper="0.0872665"/>
</joint>
<!-- Joint from shoulder to upper_arm -->
<joint name="2" type="revolute">
<origin xyz="-0.0303992 -0.0182778 -0.0542" rpy="1.5708 8.18789e-16 3.14159"/>
<parent link="shoulder"/>
<child link="upper_arm"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-0.174533" upper="3.31613"/>
</joint>
<!-- Joint from base to shoulder -->
<joint name="1" type="revolute">
<origin xyz="0.0207909 -0.0230745 0.0948817" rpy="-3.14159 6.03684e-16 1.5708"/>
<parent link="base"/>
<child link="shoulder"/>
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-1.91986" upper="1.91986"/>
</joint>
<!-- 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" kv="0.0" forcerange="-3.35 3.35"/>
</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>
</robot>

159
Simulation/SO101/so101.xml Normal file
View File

@@ -0,0 +1,159 @@
<?xml version="1.0" ?>
<!-- Generated using onshape-to-robot -->
<mujoco model="so101">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<default>
<default class="so101">
<joint frictionloss="0.1" armature="0.005"/>
<position kp="50" dampratio="1"/>
<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, from https://github.com/apirrone/Open_Duck_Playground -->
<default>
<default class="sts3215">
<geom contype="0" conaffinity="0"/>
<joint damping="0.60" frictionloss="0.052" armature="0.028"/>
<position kp="17.8" kv="0.0" forcerange="-3.35 3.35"/>
</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">
<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="1" 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="1.88657e-16 -0 0.707107 0.707107">
<!-- Joint from shoulder to upper_arm -->
<joint axis="0 0 1" name="2" type="hinge" range="-0.17453292519943472 3.3161255787892245" class="sts3215"/>
<inertial pos="-0.0898471 -0.00838224 0.0184089" mass="0.103" fullinertia="4.08002e-05 0.000147318 0.000142487 -1.97819e-05 -4.03016e-08 8.97326e-09"/>
<!-- Part sts3215_03a_v1_3 -->
<geom type="mesh" class="visual" pos="-0.11257 -0.0155 0.0187" quat="8.61227e-17 -0.707107 0.707107 -6.73749e-18" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="-0.11257 -0.0155 0.0187" quat="8.61227e-17 -0.707107 0.707107 -6.73749e-18" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part upper_arm_so101_v1 -->
<geom type="mesh" class="visual" pos="-0.065085 0.012 0.0182" quat="0 1 0 0" mesh="upper_arm_so101_v1" material="upper_arm_so101_v1_material"/>
<geom type="mesh" class="collision" pos="-0.065085 0.012 0.0182" quat="0 1 0 0" mesh="upper_arm_so101_v1" material="upper_arm_so101_v1_material"/>
<!-- Link lower_arm -->
<body name="lower_arm" pos="-0.11257 -0.028 2.29417e-16" quat="1.34913e-15 3.69655e-16 -7.40756e-16 1">
<!-- Joint from upper_arm to lower_arm -->
<joint axis="0 0 1" name="3" type="hinge" range="-3.2288591161895077 0.08726646259971825" class="sts3215"/>
<inertial pos="-0.0980701 0.00324376 0.0182831" mass="0.104" fullinertia="2.87438e-05 0.000159844 0.00014529 7.41152e-06 1.26409e-06 -4.90188e-08"/>
<!-- Part under_arm_so101_v1 -->
<geom type="mesh" class="visual" pos="-0.0648499 -0.032 0.0182" quat="0 1 0 0" mesh="under_arm_so101_v1" material="under_arm_so101_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0648499 -0.032 0.0182" quat="0 1 0 0" mesh="under_arm_so101_v1" material="under_arm_so101_v1_material"/>
<!-- Part motor_holder_so101_wrist_v1 -->
<geom type="mesh" class="visual" pos="-0.0648499 -0.032 0.018" quat="1.48409e-16 1 9.52363e-16 -5.84602e-16" mesh="motor_holder_so101_wrist_v1" material="motor_holder_so101_wrist_v1_material"/>
<geom type="mesh" class="collision" pos="-0.0648499 -0.032 0.018" quat="1.48409e-16 1 9.52363e-16 -5.84602e-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.1224 0.0052 0.0187" quat="1.69977e-15 -2.89309e-15 -1 6.11166e-16" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<geom type="mesh" class="collision" pos="-0.1224 0.0052 0.0187" quat="1.69977e-15 -2.89309e-15 -1 6.11166e-16" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Link wrist -->
<body name="wrist" pos="-0.1349 0.0052 3.21791e-16" quat="0.707107 -1.48288e-20 1.96685e-16 -0.707107">
<!-- Joint from lower_arm to wrist -->
<joint axis="0 0 1" name="4" type="hinge" range="-1.658062789394615 1.6580627893946114" 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="0 -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="0 -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="4.29003e-16 1.03623e-16 0.707107 0.707107">
<!-- Joint from wrist to gripper -->
<joint axis="0 0 1" name="5" type="hinge" range="-2.792526803190913 2.7925268031909414" 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.59247e-15 1.57708e-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.59247e-15 1.57708e-15" mesh="sts3215_03a_v1" material="sts3215_03a_v1_material"/>
<!-- Part wrist_roll_follower_so101_v1 -->
<geom type="mesh" class="visual" pos="5.55112e-17 -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="5.55112e-17 -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 1.41308e-15 -1.5309e-15">
<!-- Joint from gripper to moving_jaw_so101_v1 -->
<joint axis="0 0 1" name="6" type="hinge" range="-0.2617993877991352 1.7453292519943437" 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="2.77556e-17 -1.31397e-17 0.0189" quat="1 -0 2.22045e-16 4.44203e-31" mesh="moving_jaw_so101_v1" material="moving_jaw_so101_v1_material"/>
<geom type="mesh" class="collision" pos="2.77556e-17 -1.31397e-17 0.0189" quat="1 -0 2.22045e-16 4.44203e-31" mesh="moving_jaw_so101_v1" material="moving_jaw_so101_v1_material"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<asset>
<mesh file="waveshare_mounting_plate_so101_v2.stl"/>
<mesh file="wrist_roll_follower_so101_v1.stl"/>
<mesh file="upper_arm_so101_v1.stl"/>
<mesh file="sts3215_03a_v1.stl"/>
<mesh file="motor_holder_so101_base_v1.stl"/>
<mesh file="base_motor_holder_so101_v1.stl"/>
<mesh file="wrist_roll_pitch_so101_v2.stl"/>
<mesh file="moving_jaw_so101_v1.stl"/>
<mesh file="sts3215_03a_no_horn_v1.stl"/>
<mesh file="base_so101_v2.stl"/>
<mesh file="rotation_pitch_so101_v1.stl"/>
<mesh file="motor_holder_so101_wrist_v1.stl"/>
<mesh file="under_arm_so101_v1.stl"/>
<material name="base_motor_holder_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="base_so101_v2_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="sts3215_03a_v1_material" rgba="0.627451 0.627451 0.627451 1"/>
<material name="waveshare_mounting_plate_so101_v2_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="motor_holder_so101_base_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="rotation_pitch_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="upper_arm_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="under_arm_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="motor_holder_so101_wrist_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="sts3215_03a_no_horn_v1_material" rgba="0.627451 0.627451 0.627451 1"/>
<material name="wrist_roll_pitch_so101_v2_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="wrist_roll_follower_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
<material name="moving_jaw_so101_v1_material" rgba="0.964706 0.964706 0.952941 1"/>
</asset>
<actuator>
<position class="sts3215" name="1" joint="1" inheritrange="1"/>
<position class="sts3215" name="2" joint="2" inheritrange="1"/>
<position class="sts3215" name="3" joint="3" inheritrange="1"/>
<position class="sts3215" name="4" joint="4" inheritrange="1"/>
<position class="sts3215" name="5" joint="5" inheritrange="1"/>
<position class="sts3215" name="6" joint="6" inheritrange="1"/>
</actuator>
<equality/>
</mujoco>