Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@

All notable changes to this repository will be documented here.

## [19/05/2025]

- Added [YAM manipulator](i2rt_yam/README.md) from I2RT Robotics.

## [22/04/2025]
- Adds changelog structure, contributor list, and PR template.

Expand Down
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -189,6 +189,7 @@ Menagerie, see [CONTRIBUTING](CONTRIBUTING.md).
| Gen3 | Kinova Robotics | 7 | [BSD-3-Clause](kinova_gen3/LICENSE) |✖️|
| SO-ARM100 | The Robot Studio | 5 | [Apache-2.0](trs_so_arm100/LICENSE) |✖️|
| Koch v1.1 Low-Cost Robot | Hugging Face | 5 | [Apache-2.0](low_cost_robot_arm/LICENSE) |✖️|
| YAM | I2RT Robotics | 7 | [MIT](i2rt_yam/LICENSE) |✖️|

**Bipeds.**

Expand Down
7 changes: 7 additions & 0 deletions i2rt_yam/CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# Changelog – YAM Description

All notable changes to this model will be documented in this file.

## [19/05/2025]

- Initial release.
21 changes: 21 additions & 0 deletions i2rt_yam/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
MIT License

Copyright (c) 2025 i2rt robotics

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.
34 changes: 34 additions & 0 deletions i2rt_yam/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
# Yet Another Manipulator (YAM) Description (MJCF)

> [!IMPORTANT]
> Requires MuJoCo 3.1.3 or later.

## Changelog

See [CHANGELOG.md](./CHANGELOG.md) for a full history of changes.

## Overview

This package contains a simplified robot description (MJCF) of the [YAM robot](https://i2rt.com/products/yam-manipulator) developed by [I2
RT Robotics](https://i2rt.com/). It is derived from the [publicly available
URDF
description](https://github.com/i2rt-robotics/i2rt/blob/main/robot_models/yam/yam.urdf).

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

## MJCF derivation steps

1. Started from `yam.urdf` (commit SHA d4efb66d81bd8bde42909880b16591d4af82e8c0).
2. Added the following to the URDF `<robot>` tag `<mujoco><compiler balanceinertia="true" discardvisual="false" fusestatic="false" strippath="false"/></mujoco>`.
3. Loaded the URDF into MuJoCo and saved a corresponding MJCF.
4. Added home keyframe.
5. Added tracking light.
6. Add frictionloss (not identified).
7. Added armature based on reflected inertia values provided by the manufacturer.
8. Switched to implicitfast and used position actuators with kp/kv semantics.

## License

This model is released under an [MIT License](LICENSE).
Binary file added i2rt_yam/assets/model2.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__10.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__11.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__12.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__13.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__14.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__15.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__16.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__17.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__2.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__3.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__4.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__5.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__6.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__7.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__8.stl
Binary file not shown.
Binary file added i2rt_yam/assets/model2__9.stl
Binary file not shown.
23 changes: 23 additions & 0 deletions i2rt_yam/scene.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<mujoco model="yam scene">
<include file="yam.xml"/>

<statistic center="0.2 -0.1 0.3" extent="0.45"/>

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

<option integrator="implicitfast"/>

<default>
<default class="yam">
<position inheritrange="1"/>
<joint frictionloss="0.1" axis="0 0 1"/>
<default class="dm4340">
<joint armature="0.032"/>
<position kp="40" kv="2.5" forcerange="-28 28"/>
</default>
<default class="dm4310">
<joint armature="0.0018"/>
<position kp="10" kv="1" forcerange="-10 10"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" density="0" group="2" material="black"/>
</default>
<default class="collision">
<geom group="3" type="capsule"/>
<default class="sphere_collision">
<geom size="0.0006 0 0" type="sphere" rgba="1 0 0 1"/>
</default>
</default>
<default class="finger">
<joint type="slide" armature="0.1" frictionloss="0.1"/>
<position ctrlrange="0.0 0.041" kp="100" kv="10" inheritrange="0"/>
</default>
</default>
</default>

<asset>
<material name="black" rgba="0.25 0.25 0.25 1"/>
<material name="white" rgba="0.9 0.9 0.9 1"/>

<mesh file="model2.stl"/>
<mesh file="model2__2.stl"/>
<mesh file="model2__3.stl"/>
<mesh file="model2__4.stl"/>
<mesh file="model2__5.stl"/>
<mesh file="model2__6.stl"/>
<mesh file="model2__7.stl"/>
<mesh file="model2__8.stl"/>
<mesh file="model2__9.stl"/>
<mesh file="model2__10.stl"/>
<mesh file="model2__11.stl"/>
<mesh file="model2__12.stl"/>
<mesh file="model2__13.stl"/>
<mesh file="model2__14.stl"/>
<mesh file="model2__15.stl"/>
<mesh file="model2__16.stl"/>
<mesh file="model2__17.stl"/>
</asset>

<worldbody>
<light name="spotlight" mode="targetbodycom" target="link_6" pos="0 0 1"/>
<body name="arm" childclass="yam">
<geom class="visual" pos="0 0 -0.0006" quat="1 0 0 1" mesh="model2"/>
<geom class="collision" size="0.033 0.01" pos="0.0 0.0 0.026" quat="1 0 0 0"/>
<body name="link_1" pos="0 0 0.0631" quat="1 0 0 1">
<inertial pos="-0.00192861 -0.00795735 0.0208176" quat="0.297851 0.642634 0.360045 0.607185" mass="0.12415"
diaginertia="0.000180751 0.000145532 5.89179e-05"/>
<joint name="joint1" range="-2.61799 3.05433" class="dm4340"/>
<geom class="visual" pos="5.26159e-07 2.34355e-07 -0.0632" quat="1 0 0 0" mesh="model2__2"/>
<body name="link_2" pos="2.5e-05 -0.02 0.0409" quat="1 1 1 1" gravcomp="1">
<inertial pos="0.132008 2.10599e-06 0.000293073" quat="1 1 1 1" mass="1.24434"
diaginertia="0.0121902 0.0121318 0.000683304"/>
<joint name="joint2" range="0 3.66519" class="dm4340"/>
<geom class="visual" pos="0.0199992 -0.1041 -2.44738e-05" quat="1 -1 -1 -1" mesh="model2__3"/>
<geom class="visual" pos="0.0199992 -0.1041 -2.44738e-05" quat="1 -1 -1 -1" mesh="model2__4"/>
<geom class="visual" pos="0.0199992 -0.1041 -2.44738e-05" quat="1 -1 -1 -1" mesh="model2__5" material="white"/>
<geom class="collision" size="0.032 0.11" pos="0.13 0 0" quat="1 0 1 0"/>
<geom class="collision" size="0.033 0.02" pos="0 0.0 0" quat="1 0 0 0"/>
<geom class="collision" size="0.033 0.025" pos="0.265 0 0" quat="1 0 0 0"/>
<body name="link_3" pos="0.264 0 0" quat="0 1 0 0" gravcomp="1">
<inertial pos="-0.121816 -0.054846 -0.000111108" quat="1 1 1 1" mass="0.853698"
diaginertia="0.00699732 0.00696112 0.000788244"/>
<joint name="joint3" range="0 3.66519" class="dm4340"/>
<geom class="visual" pos="-0.244001 0.104101 2.44738e-05" quat="1 1 1 -1" mesh="model2__6"/>
<geom class="visual" pos="-0.244001 0.104101 2.44738e-05" quat="1 1 1 -1" mesh="model2__7"/>
<geom class="visual" pos="-0.244001 0.104101 2.44738e-05" quat="1 1 1 -1" mesh="model2__8" material="white"/>
<geom class="visual" pos="-0.244001 0.104101 2.44738e-05" quat="1 1 1 -1" mesh="model2__9"/>
<geom class="collision" size="0.034 0.12" pos="-0.14 -0.06 0.0" quat="1 0 1 0"/>
<geom class="collision" size="0.034 0.015" pos="-0.24 -0.06 0.0" quat="1 0 0 0"/>
<body name="link_4" pos="-0.245 -0.06 0" quat="1 0 0 0" gravcomp="1">
<inertial pos="-0.0769778 -0.0527104 0.000154878" quat="0.667 0.667 -0.236 -0.236" mass="0.463511"
diaginertia="0.000791532 0.000744733 0.000282116"/>
<joint name="joint4" range="-1.5708 1.5708" class="dm4310"/>
<geom class="visual" pos="0.00100023 0.164101 2.44738e-05" quat="1 1 1 -1" mesh="model2__10"/>
<geom class="collision" size="0.03 0.015" pos="-0.073 -0.06 0.0" quat="1 1 0 0"/>
<body name="link_5" pos="-0.074 -0.0395 2.5e-05" quat="1 -1 1 1" gravcomp="1">
<inertial pos="3.64861e-05 0.00025665 0.0353526" quat="1 0 0 0" mass="0.350962"
diaginertia="0.000197802 0.0001775 0.000147402"/>
<joint name="joint5" range="-1.5708 1.5708" class="dm4310"/>
<geom class="visual" pos="0 -0.0749971 0.203601" quat="1.32679e-06 1 0 0" mesh="model2__11"/>
<geom class="collision" size="0.030 0.015" pos="0 0.025 0.0395" quat="1 1 0 0"/>
<body name="link_6" pos="0 0.0353 0.0395" quat="1 -1 0 0" gravcomp="1">
<inertial pos="-0.000217767 7.37059e-05 0.0270545" quat="1 1 0 0" mass="0.367476"
diaginertia="0.000265958 0.000242686 0.000227409"/>
<joint name="joint6" range="-2.0944 2.0944" class="dm4310"/>
<geom class="visual" pos="0 -0.164101 -0.110597" quat="1 -1 0 0" mesh="model2__12"/>
<geom class="visual" pos="0 -0.164101 -0.110597" quat="1 -1 0 0" mesh="model2__13"/>
<geom class="collision" size="0.01 0.035" pos="0 0.039 0.052" quat="1 0 1 0"/>
<geom class="collision" size="0.030 0.005" pos="0 0.0 0.03" quat="1 0 0 1"/>
<geom class="collision" size="0.01 0.035" pos="0 -0.039 0.052" quat="1 0 1 0"/>
<site name="tcp_site" pos="0 0 0" quat="1 0 0 -1" size="0.005" rgba="1 0 0 1" group="4"/>
<site name="grasp_site" pos="0 0 0.1347" quat="1 0 0 -1" size="0.005" rgba="0 1 0 1" group="4"/>
<body name="link_left_finger" pos="-0.037 0.0392 0.0605" quat="1 0 1 0" gravcomp="1">
<inertial pos="-0.0192995 -0.0365902 0.039774" quat="0.757351 0.568898 -0.3199 0.0" mass="0.118"
diaginertia="0.000159084 0.000154909 4.63655e-05"/>
<joint class="finger" name="left_finger" range="-0.00205 0.037524"/>
<geom class="visual" pos="0.171097 -0.203301 0.037" quat="1 -1 -1 -1" mesh="model2__14"/>
<geom class="visual" pos="0.171097 -0.203301 0.037" quat="1 -1 -1 -1" mesh="model2__15"/>
<body name="lf_rot" quat="1 -1 -1 1" pos="0.0 -0.0392 0.037" gravcomp="1">
<geom class="collision" size="0.01 0.03" pos="0.0 -0.02 0.012" quat="1 0 1 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.01 0.02" pos="-0.02 -0.01 0.032" quat="1 0 2.5 0"
rgba="0.381493 0.492734 0.780446 1"/>
<body name="lf_down" quat="1 0 0 0" pos="-0.044 0.0 0.0" gravcomp="1">
<geom class="collision" size="0.01 0.01" pos="0.0 -0.020 0.012" quat="1 -0.1 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.003 0.022" pos="0.005 -0.014 0.04" quat="1 -0.2 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.003 0.022" pos="-0.005 -0.014 0.04" quat="1 -0.2 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" type="box" size="0.006 0.002 0.04" pos="0 -0.0024 0.046" quat="1 0 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" type="box" size="0.006 0.002 0.039" pos="0.027 -0.0024 0.053"
quat="1 0 2.5 0" rgba="0.381493 0.492734 0.780446 1"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.078"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.078"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.07"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.07"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.06"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.06"/>
</body>
</body>
</body>
<body name="link_right_finger" pos="0.037 -0.0392 0.0605" quat="1 0 1 0" gravcomp="1">
<inertial pos="-0.0192995 0.0365902 -0.039774" quat="-0.757351 0.568898 -0.3199 0" mass="0.118"
diaginertia="0.000159084 0.000154909 4.63655e-05"/>
<joint class="finger" name="right_finger" range="-0.037524 0.00205"/>
<geom class="visual" pos="0.171097 -0.124901 -0.037" quat="1 -1 -1 -1" mesh="model2__16"/>
<geom class="visual" pos="0.171097 -0.124901 -0.037" quat="1 -1 -1 -1" mesh="model2__17"/>
<body name="rf_rot" quat="1 1 -1 -1" pos="0.0 0.0392 -0.037" gravcomp="1">
<geom class="collision" size="0.01 0.03" pos="0.0 -0.02 0.012" quat="1 0 1 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.01 0.02" pos="0.02 -0.01 0.032" quat="1 0 -2.5 0"
rgba="0.381493 0.492734 0.780446 1"/>
<body name="rf_down" quat="1 0 0 0" pos="0.044 0.0 0.0" gravcomp="1">
<geom class="collision" size="0.01 0.01" pos="0.0 -0.020 0.012" quat="1 -0.1 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.003 0.022" pos="0.005 -0.014 0.04" quat="1 -0.2 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" size="0.003 0.022" pos="-0.005 -0.014 0.04" quat="1 -0.2 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" type="box" size="0.006 0.002 0.04" pos="0 -0.0024 0.046" quat="1 0 0 0"
rgba="0.381493 0.492734 0.780446 1"/>
<geom class="collision" type="box" size="0.006 0.002 0.039" pos="-0.027 -0.0024 0.053"
quat="1 0 -2.5 0" rgba="0.381493 0.492734 0.780446 1"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.078"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.078"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.07"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.07"/>
<geom class="sphere_collision" pos="0.003 -0.0004 0.06"/>
<geom class="sphere_collision" pos="-0.003 -0.0004 0.06"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<equality>
<joint joint1="left_finger" joint2="right_finger" polycoef="0 -1 0 0 0"/>
</equality>

<actuator>
<position name="joint1" joint="joint1" class="dm4340"/>
<position name="joint2" joint="joint2" class="dm4340"/>
<position name="joint3" joint="joint3" class="dm4340"/>
<position name="joint4" joint="joint4" class="dm4310" kp="20" kv=".5"/>
<position name="joint5" joint="joint5" class="dm4310"/>
<position name="joint6" joint="joint6" class="dm4310"/>
<position class="finger" name="gripper" joint="left_finger"/>
</actuator>

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