Skip to content

Commit

Permalink
Add 5-DOF Standard Open Arm-100
Browse files Browse the repository at this point in the history
  • Loading branch information
chernyadev committed Oct 28, 2024
1 parent 9e9185d commit 13d6c48
Show file tree
Hide file tree
Showing 23 changed files with 208 additions and 0 deletions.
7 changes: 7 additions & 0 deletions trs_so_arm100/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
Copyright 2024 Nikita Cherniadev

Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the “Software”), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED “AS IS”, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
29 changes: 29 additions & 0 deletions trs_so_arm100/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
# Standard Open Arm-100 5DOF - Version 1.3 (MJCF)

> [!IMPORTANT]
> Requires MuJoCo 3.1.6 or later.
## Overview

This package contains a simplified robot description (MJCF) of the [Standard Open Arm-100](https://github.com/TheRobotStudio/SO-ARM100/tree/main) developed by [The Robot Studio](https://www.therobotstudio.com/). It is derived from the [publicly available URDF description](https://github.com/TheRobotStudio/SO-ARM100/blob/4e9c5588d8a8415b6a6c2142a0ce8c32207cf3e9/URDF/SO_5DOF_ARM100_8j_URDF.SLDASM/urdf/SO_5DOF_ARM100_8j_URDF.SLDASM.urdf).

<p float="left">
<img src="so_arm100.png" width="400">
</p>

## URDF → MJCF derivation steps

1. Added `<mujoco><compiler discardvisual="false" strippath="false"/></mujoco>` to the URDF’s `<robot>` element to preserve visual geometries.
2. Loaded the URDF into MuJoCo and saved it as a corresponding MJCF.
3. Manually edited the MJCF to extract shared properties into the `<default>` section.
4. Edited original meshes: extracted servos into separate files, manually created convex collision meshes for the gripper jaws.
5. Added extra box-shaped collision geoms to the gripper for additional contact points.
6. Added an `exclude` clause to prevent collisions between `Base` and `Rotation_Pitch`.
7. Added approximate joint limits.
8. Added position-controlled actuators.
9. Added `impratio="10"` and `cone="elliptic"` attributes for improved no-slip behavior.
10. Created `scene.xml` to include the robot, along with a textured ground plane, skybox, and haze.

## License

This model is released under an [MIT License](LICENSE).
Binary file added trs_so_arm100/assets/Base.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Base_Motor.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Fixed_Jaw.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Fixed_Jaw_Collision_1.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Fixed_Jaw_Collision_2.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Fixed_Jaw_Motor.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Lower_Arm.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Lower_Arm_Motor.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Moving_Jaw.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Moving_Jaw_Collision_1.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Moving_Jaw_Collision_2.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Moving_Jaw_Collision_3.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Rotation_Pitch.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Rotation_Pitch_Motor.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Upper_Arm.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Upper_Arm_Motor.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Wrist_Pitch_Roll.stl
Binary file not shown.
Binary file added trs_so_arm100/assets/Wrist_Pitch_Roll_Motor.stl
Binary file not shown.
23 changes: 23 additions & 0 deletions trs_so_arm100/scene.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<mujoco model="so_arm100 scene">
<include file="so_arm100.xml"/>

<statistic center="0 -0.2 0.1" extent="0.4"/>

<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="140" elevation="-30"/>
</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 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
</mujoco>
Binary file added trs_so_arm100/so_arm100.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
149 changes: 149 additions & 0 deletions trs_so_arm100/so_arm100.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,149 @@
<mujoco model="so_arm100">
<compiler angle="radian" meshdir="assets/"/>

<option cone="elliptic" impratio="10"/>

<asset>
<material name="orange" rgba="1.0 0.331 0.0 1.0" specular="0.1" shininess="0.1"/>
<material name="black" rgba="0.1 0.1 0.1 1.0" specular="0.1" shininess="0.1"/>

<mesh name="Base" file="Base.stl"/>
<mesh name="Base_Motor" file="Base_Motor.stl"/>
<mesh name="Rotation_Pitch" file="Rotation_Pitch.stl"/>
<mesh name="Rotation_Pitch_Motor" file="Rotation_Pitch_Motor.stl"/>
<mesh name="Upper_Arm" file="Upper_Arm.stl"/>
<mesh name="Upper_Arm_Motor" file="Upper_Arm_Motor.stl"/>
<mesh name="Lower_Arm" file="Lower_Arm.stl"/>
<mesh name="Lower_Arm_Motor" file="Lower_Arm_Motor.stl"/>
<mesh name="Wrist_Pitch_Roll" file="Wrist_Pitch_Roll.stl"/>
<mesh name="Wrist_Pitch_Roll_Motor" file="Wrist_Pitch_Roll_Motor.stl"/>
<mesh name="Fixed_Jaw" file="Fixed_Jaw.stl"/>
<mesh name="Fixed_Jaw_Motor" file="Fixed_Jaw_Motor.stl"/>
<mesh name="Fixed_Jaw_Collision_1" file="Fixed_Jaw_Collision_1.stl"/>
<mesh name="Fixed_Jaw_Collision_2" file="Fixed_Jaw_Collision_2.stl"/>
<mesh name="Moving_Jaw" file="Moving_Jaw.stl"/>
<mesh name="Moving_Jaw_Collision_1" file="Moving_Jaw_Collision_1.stl"/>
<mesh name="Moving_Jaw_Collision_2" file="Moving_Jaw_Collision_2.stl"/>
<mesh name="Moving_Jaw_Collision_3" file="Moving_Jaw_Collision_3.stl"/>
</asset>

<default>
<default class="so_arm100">
<joint frictionloss="0.1" armature="0.1"/>
<position kp="50" dampratio="1" forcerange="-35 35" ctrlrange="-3.14158 3.14158"/>
<default class="Rotation">
<joint axis="0 1 0" range="-2.2 2.2"/>
</default>
<default class="Pitch">
<joint axis="1 0 0" range="-3.14158 0.2"/>
</default>
<default class="Elbow">
<joint axis="1 0 0" range="0 3.14158"/>
</default>
<default class="Wrist_Pitch">
<joint axis="1 0 0" range="-2.0 1.8"/>
</default>
<default class="Wrist_Roll">
<joint axis="0 1 0" range="-3.14158 3.14158"/>
</default>
<default class="Jaw">
<joint axis="0 0 1" range="-0.2 2.0"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" density="0" group="2" material="orange"/>
<default class="motor_visual">
<geom material="black"/>
</default>
</default>
<default class="collision">
<geom group="3" type="mesh"/>
<default class="finger_collision">
<geom type="box" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
</default>
</default>
</default>
</default>

<worldbody>
<body name="Base" childclass="so_arm100">
<geom type="mesh" mesh="Base" class="visual"/>
<geom type="mesh" mesh="Base_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Base" class="collision"/>
<body name="Rotation_Pitch" pos="0 -0.0452 0.0165" quat="0.707105 0.707108 0 0">
<inertial pos="-9.07886e-05 0.0590972 0.031089" quat="0.363978 0.441169 -0.623108 0.533504" mass="0.119226"
diaginertia="5.94278e-05 5.89975e-05 3.13712e-05"/>
<joint name="Rotation" class="Rotation"/>
<geom type="mesh" mesh="Rotation_Pitch" class="visual"/>
<geom type="mesh" mesh="Rotation_Pitch_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Rotation_Pitch" class="collision"/>
<body name="Upper_Arm" pos="0 0.1025 0.0306" euler="1.57079 0 0">
<inertial pos="-1.72052e-05 0.0701802 0.00310545" quat="0.50104 0.498994 -0.493562 0.50632" mass="0.162409"
diaginertia="0.000213312 0.000167164 7.01522e-05"/>
<joint name="Pitch" class="Pitch"/>
<geom type="mesh" mesh="Upper_Arm" class="visual"/>
<geom type="mesh" mesh="Upper_Arm_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Upper_Arm" class="collision"/>
<body name="Lower_Arm" pos="0 0.11257 0.028" euler="-1.57079 0 0">
<inertial pos="-0.00339604 0.00137796 0.0768007" quat="0.701995 0.0787996 0.0645626 0.704859"
mass="0.147968" diaginertia="0.000138803 0.000107748 4.84242e-05"/>
<joint name="Elbow" class="Elbow"/>
<geom type="mesh" mesh="Lower_Arm" class="visual"/>
<geom type="mesh" mesh="Lower_Arm_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Lower_Arm" class="collision"/>
<body name="Wrist_Pitch_Roll" pos="0 0.0052 0.1349" euler="-1.57079 0 0">
<inertial pos="-0.00852653 -0.0352279 -2.34622e-05" quat="-0.0522806 0.705235 0.0549524 0.704905"
mass="0.0661321" diaginertia="3.45403e-05 2.39041e-05 1.94704e-05"/>
<joint name="Wrist_Pitch" class="Wrist_Pitch"/>
<geom type="mesh" mesh="Wrist_Pitch_Roll" class="visual"/>
<geom type="mesh" mesh="Wrist_Pitch_Roll_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Wrist_Pitch_Roll" class="collision"/>
<body name="Fixed_Jaw" pos="0 -0.0601 0" euler="0 1.57079 0">
<inertial pos="0.00552377 -0.0280167 0.000483583" quat="0.41836 0.620891 -0.350644 0.562599"
mass="0.0929859" diaginertia="5.03136e-05 4.64098e-05 2.72961e-05"/>
<joint name="Wrist_Roll" class="Wrist_Roll"/>
<geom type="mesh" mesh="Fixed_Jaw" class="visual"/>
<geom type="mesh" mesh="Fixed_Jaw_Motor" class="motor_visual"/>
<geom type="mesh" mesh="Fixed_Jaw_Collision_1" class="collision"/>
<geom type="mesh" mesh="Fixed_Jaw_Collision_2" class="collision"/>
<geom class="finger_collision" name="fixed_jaw_pad_1" size="0.001 0.005 0.004" pos="0.0089 -0.1014 0"/>
<geom class="finger_collision" name="fixed_jaw_pad_2" size="0.001 0.005 0.006" pos="0.0109 -0.0914 0"/>
<geom class="finger_collision" name="fixed_jaw_pad_3" size="0.001 0.01 0.007" pos="0.0126 -0.0768 0"/>
<geom class="finger_collision" name="fixed_jaw_pad_4" size="0.001 0.01 0.008" pos="0.0143 -0.0572 0"/>
<body name="Moving_Jaw" pos="-0.0202 -0.0244 0" quat="1.34924e-11 -3.67321e-06 1 -3.67321e-06">
<inertial pos="-0.00161745 -0.0303473 0.000449646" quat="0.696562 0.716737 -0.0239844 -0.0227026"
mass="0.0202444" diaginertia="1.11265e-05 8.99651e-06 2.99548e-06"/>
<joint name="Jaw" class="Jaw"/>
<geom type="mesh" mesh="Moving_Jaw" class="visual"/>
<geom type="mesh" mesh="Moving_Jaw_Collision_1" class="collision"/>
<geom type="mesh" mesh="Moving_Jaw_Collision_2" class="collision"/>
<geom type="mesh" mesh="Moving_Jaw_Collision_3" class="collision"/>
<geom class="finger_collision" name="moving_jaw_pad_1" size="0.001 0.005 0.004" pos="-0.0113 -0.077 0"/>
<geom class="finger_collision" name="moving_jaw_pad_2" size="0.001 0.005 0.006" pos="-0.0093 -0.067 0"/>
<geom class="finger_collision" name="moving_jaw_pad_3" size="0.001 0.01 0.006" pos="-0.0073 -0.055 0"/>
<geom class="finger_collision" name="moving_jaw_pad_4" size="0.001 0.01 0.008" pos="-0.0073 -0.035 0"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<actuator>
<position class="Rotation" name="Rotation" joint="Rotation"/>
<position class="Pitch" name="Pitch" joint="Pitch"/>
<position class="Elbow" name="Elbow" joint="Elbow"/>
<position class="Wrist_Pitch" name="Wrist_Pitch" joint="Wrist_Pitch"/>
<position class="Wrist_Roll" name="Wrist_Roll" joint="Wrist_Roll"/>
<position class="Jaw" name="Jaw" joint="Jaw"/>
</actuator>

<contact>
<exclude body1="Base" body2="Rotation_Pitch"/>
</contact>

<keyframe>
<key name="home" qpos="0 -1.57079 1.57079 1.57079 -1.57079 0" ctrl="0 -1.57079 1.57079 1.57079 -1.57079 0"/>
</keyframe>
</mujoco>

0 comments on commit 13d6c48

Please sign in to comment.