Skip to content
Open
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 .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@

# Python caches
__pycache__/
*.py[cod]
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.

## [2025-08-27]

- Added Kinova Gen3 Lite.

## [2025-05-30]

- Added an MJX-tuned version of the G1 model.
Expand Down
3 changes: 2 additions & 1 deletion CONTRIBUTORS.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ Built by the Google DeepMind team with contributions from the open-source commun
- [Silvia Cruciani](https://github.com/silviacruciani) - Google DeepMind

## Community Contributors

- [Achraf Anas Houssaini](https://github.com/anashoussaini)
- [Albert Li](https://github.com/alberthli)
- [Alper Ahmetoglu](https://github.com/alper111)
- [Andrew Luo](https://github.com/Andrew-Luo1)
Expand All @@ -24,6 +24,7 @@ Built by the Google DeepMind team with contributions from the open-source commun
- [Eugene Frizza](https://github.com/eufrizz)
- [Ian Noh](https://github.com/dongridong)
- [Jason Chen](https://github.com/chenxin199305)
- [Jonathan Lussier](https://github.com/kinovajon)
- [Jonathan Zamora](https://github.com/jonzamora)
- [Kallinteris Andreas](https://github.com/Kallinteris-Andreas)
- [Lev Kozlov](https://github.com/lvjonok)
Expand Down
6 changes: 6 additions & 0 deletions kinova_gen3_lite/CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
# Changelog – Gen3 Lite Description

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

## [2025-27-08]
- Initial release.
11 changes: 11 additions & 0 deletions kinova_gen3_lite/LICENSE
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
Copyright (c) 2018, Kinova inc.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
69 changes: 69 additions & 0 deletions kinova_gen3_lite/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
# Kinova Gen3 Lite Description (MJCF)

> [!IMPORTANT]
> Requires MuJoCo 2.3.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 [Kinova
Gen3 Lite](https://www.kinovarobotics.com/product/gen3-lite-robots) developed by [Kinova Robotics](https://www.kinovarobotics.com/). It is derived from the [publicly
available URDF description](https://github.com/Kinovarobotics/ros2_kortex/blob/main/kortex_description/robots/gen3_lite.urdf).



<p float="left">
<img src="assets/gen3_lite.png" width="400">
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Don't put the image in the assets folder but at the same level as this readme.

</p>


## MJCF derivation steps

1. Converted xacro to URDF: `rosrun xacro xacro gen3_lite.xacro > gen3_lite.urdf`
2. Added the following to the URDF's `<robot>` clause:

```xml
<mujoco>
<compiler meshdir="assets" discardvisual="false" fusestatic="false"/>
</mujoco>
```

3. Converted to MJCF:

```python
import mujoco
model = mujoco.MjModel.from_xml_path('gen3_lite.urdf')
mujoco.mj_saveLastXML('gen3_lite_raw.xml', model)
```

4. Cleaned up the MJCF file as follows:

* Added physics options: `<option integrator="implicitfast" cone="pyramidal" impratio="50" tolerance="1e-10" noslip_iterations="8"/>` and `<size nconmax="400" njmax="2000"/>`.
* Replaced `type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.75294 0.75294 0.75294 1"` with `class="visual"` and added the class to defaults.
* Replaced bare `type="mesh"` collision geoms with `class="collision"` and added the class to defaults (including `condim="4"`, `solref="0.005 1"`, `solimp="0.9 0.95 0.001"`).
* Added small global joint damping/armature in `<default>`, plus a `grip_joint` default for the gripper.
* Standardized mesh filenames to lowercase `.stl` with `<compiler angle="radian" meshdir="assets/"/>`.
* Added a tool frame and TCP site: `<body name="tool_frame" ...>` with `<site name="ee_site" .../>`.
* Implemented an underactuated two-finger gripper using `<equality joint ... polycoef="...">` couplings and added near-neighbor contact excludes.
5. Added the following to the MJCF:

* Position actuators for all six arm joints with per-class gains/limits; a single actuator drives `right_finger_bottom_joint` with the remaining gripper joints coupled.
* Keyframes for "home", "retract", "open", and "close".
6. Added `scene.xml` which includes the robot.

The end effector site can be shifted by an additional `0.12` along the tool frame to emulate certain Kortex TCP conventions:

```xml
<site name="ee_site" pos="0 0 0.12" quat="0 1 0 0" group="3"/>
```

## License

This model is released under a [BSD-3-Clause License](LICENSE).

## Acknowledgement

This model was graciously contributed by [Anas Houssaini](https://anashoussaini.github.io/), [Abed Al Rahman Al Mrad](https://github.com/aalmrad),[Jonathan Lussier](https://github.com/kinovajon).
Binary file added kinova_gen3_lite/assets/arm_link.stl
Binary file not shown.
Binary file added kinova_gen3_lite/assets/base_link.stl
Binary file not shown.
Binary file added kinova_gen3_lite/assets/forearm_link.stl
Binary file not shown.
Binary file added kinova_gen3_lite/assets/gen3_lite.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added kinova_gen3_lite/assets/gripper_base_link.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file added kinova_gen3_lite/assets/lower_wrist_link.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file added kinova_gen3_lite/assets/shoulder_link.stl
Binary file not shown.
Binary file added kinova_gen3_lite/assets/upper_wrist_link.stl
Binary file not shown.
221 changes: 221 additions & 0 deletions kinova_gen3_lite/gen3_lite.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,221 @@
<mujoco model="gen3_lite">
<compiler angle="radian" meshdir="assets/"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
<compiler angle="radian" meshdir="assets/"/>
<compiler angle="radian" meshdir="assets"/>


<option integrator="implicitfast" cone="pyramidal" impratio="50" tolerance="1e-10" noslip_iterations="8">
<flag gravity="enable"/>
</option>

<size nconmax="400" njmax="2000"/>

<default>

<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2" rgba="0.803 0.824 0.82 1"/>
</default>
<default class="collision">
<geom type="mesh" group="3" condim="4" solref="0.005 1" solimp="0.9 0.95 0.001"/>
</default>


<joint damping="0.02" armature="0.001" limited="true"/>

<default class="large_actuator">
<position kp="1200" kv="80" forcerange="-105 105" ctrllimited="true"/>
</default>
<default class="medium_actuator">
<position kp="650" kv="60" forcerange="-72 72" ctrllimited="true"/>
</default>
<default class="small_actuator">
<position kp="400" kv="40" forcerange="-52 52" ctrllimited="true"/>
</default>


<default class="grip_joint">
<joint damping="0.05" armature="0.002"/>
</default>
</default>
Comment on lines +10 to +36
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: remove the extra blank lines inside the <default> block.


<asset>
<mesh name="base_link" file="base_link.stl"/>
<mesh name="shoulder_link" file="shoulder_link.stl"/>
<mesh name="arm_link" file="arm_link.stl"/>
<mesh name="forearm_link" file="forearm_link.stl"/>
<mesh name="lower_wrist_link" file="lower_wrist_link.stl"/>
<mesh name="upper_wrist_link" file="upper_wrist_link.stl"/>
<mesh name="gripper_base_link" file="gripper_base_link.stl"/>
<mesh name="right_finger_prox_link" file="right_finger_prox_link.stl"/>
<mesh name="right_finger_dist_link" file="right_finger_dist_link.stl"/>
<mesh name="left_finger_prox_link" file="left_finger_prox_link.stl"/>
<mesh name="left_finger_dist_link" file="left_finger_dist_link.stl"/>
</asset>

<worldbody>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nit: remove the extra blank lines inside the <worldbody> block and also for the following ones.

<body name="base_link">
<inertial pos="0.00244324 0.00015573 0.0861674" quat="0.999765 0.000276221 -0.0211882 0.00451385" mass="1.14608"
diaginertia="0.0033632 0.003311 0.000766919"/>
<geom class="visual" mesh="base_link"/>
<geom class="collision" mesh="base_link"/>

<body name="shoulder_link" pos="0 0 0.12825">
<inertial pos="2.477e-05 0.0221353 0.0993769" quat="0.972429 0.233194 -0.000430944 0.00108761" mass="0.959744"
diaginertia="0.00165947 0.00158128 0.000717195"/>
<joint name="joint_1" pos="0 0 0" axis="0 0 1" range="-2.68 2.68" actuatorfrcrange="-10 10"/>
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

pos="0 0 0" and axis="0 0 1" are default values and can be omitted. Consider removing them (and other attributes where the default is already implied) to keep the XML minimal.

<geom class="visual" mesh="shoulder_link"/>
<geom class="collision" mesh="shoulder_link"/>

<body name="arm_link" pos="0 -0.03 0.115" quat="0.707105 0.707108 0 0">
<inertial pos="0.029983 0.211548 0.0453031" quat="0.534676 0.467794 -0.46336 0.529706" mass="1.17756"
diaginertia="0.0115237 0.0114928 0.000839712"/>
<joint name="joint_2" pos="0 0 0" axis="0 0 1" range="-2.61 2.61" actuatorfrcrange="-14 14"/>
<geom class="visual" mesh="arm_link"/>
<geom class="collision" mesh="arm_link"/>

<body name="forearm_link" pos="0 0.28 0" quat="-3.67321e-06 -1 0 0">
<inertial pos="0.0301559 0.0950221 0.0073555" quat="0.523543 0.49139 -0.473675 0.50997" mass="0.597677"
diaginertia="0.00169754 0.00163253 0.000291376"/>
<joint name="joint_3" pos="0 0 0" axis="0 0 1" range="-2.61 2.61" actuatorfrcrange="-10 10"/>
<geom class="visual" mesh="forearm_link"/>
<geom class="collision" mesh="forearm_link"/>

<body name="lower_wrist_link" pos="0 -0.14 0.02" quat="0.707105 0.707108 0 0">
<inertial pos="0.00575149 0.0100044 0.0871921" quat="0.700403 -0.13124 -0.134345 0.688595" mass="0.526934"
diaginertia="0.000785199 0.000756398 0.000275722"/>
<joint name="joint_4" pos="0 0 0" axis="0 0 1" range="-2.6 2.6" actuatorfrcrange="-7 7"/>
<geom class="visual" mesh="lower_wrist_link"/>
<geom class="collision" mesh="lower_wrist_link"/>

<body name="upper_wrist_link" pos="0.0285 0 0.105" quat="0.707105 0 0.707108 0">
<inertial pos="0.0805652 0.00980409 0.018728" quat="0.00431726 0.708285 -4.18922e-06 0.705913"
mass="0.580973" diaginertia="0.00108466 0.00106374 0.000212638"/>
<joint name="joint_5" pos="0 0 0" axis="0 0 1" range="-2.53 2.53" actuatorfrcrange="-7 7"/>
<geom class="visual" mesh="upper_wrist_link"/>
<geom class="collision" mesh="upper_wrist_link"/>

<body name="end_effector_link" pos="-0.105 0 0.0285" quat="0.707105 0 -0.707108 0">
<inertial pos="0 0 0" mass="0.05" diaginertia="0.0001 0.0001 0.0001"/>
<joint name="joint_6" pos="0 0 0" axis="0 0 1" range="-2.6 2.6" actuatorfrcrange="-7 7"/>


<body name="dummy_link">
<body name="tool_frame" pos="0 0 0.13" quat="0.707107 0 0 0.707107">

<site name="ee_site" pos="0 0 0" size="0.005" rgba="0.2 0.2 1 1"/>
</body>


<body name="gripper_base_link">
<inertial pos="4.03e-06 1.08e-05 0.041397" quat="0.999999 -2.09897e-06 -0.00104876 0.000388495"
mass="0.1395" diaginertia="0.00011614 0.00010327 9.70699e-05"/>
<geom class="visual" mesh="gripper_base_link"/>
<geom class="collision" mesh="gripper_base_link"/>


<body name="right_finger_prox_link" pos="0 -0.030501 0.070003" quat="0.707105 0 0.707108 0">
<inertial pos="0.020257 0.0063483 6.991e-05" quat="0.598941 0.598941 0.375858 0.375858"
mass="0.018385" diaginertia="5.25068e-06 4.77e-06 1.59932e-06"/>
<joint class="grip_joint" name="right_finger_bottom_joint" pos="0 0 0" axis="0 0 1"
range="-0.09 0.96" actuatorfrcrange="-1000 1000"/>
<geom class="visual" mesh="right_finger_prox_link"/>
<geom class="collision" mesh="right_finger_prox_link"/>

<body name="right_finger_dist_link" pos="-0.045636 0.020423 0">
<inertial pos="0.018488 0.0011091 0" quat="0.557345 0.557345 0.435162 0.435162"
mass="0.010748" diaginertia="1.91e-06 1.61e-06 5.5e-07"/>
<joint class="grip_joint" name="right_finger_tip_joint" pos="0 0 0" axis="0 0 1"
range="-0.5 0.21" actuatorfrcrange="-1000 1000"/>

<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.055 0.525 1"
mesh="right_finger_dist_link"/>
<geom type="mesh" rgba="0 0.055 0.525 1" mesh="right_finger_dist_link"/>
</body>
</body>


<body name="left_finger_prox_link" pos="0 0.0305 0.070003" quat="0.707105 0 0.707108 0">
<inertial pos="0.020257 0.0063483 6.99e-05" quat="0.598941 0.598941 0.375858 0.375858"
mass="0.018385" diaginertia="5.25068e-06 4.77e-06 1.59932e-06"/>
<joint class="grip_joint" name="left_finger_bottom_joint" pos="0 0 0" axis="0 0 1"
range="-0.96 0.09" actuatorfrcrange="-1000 1000"/>
<geom class="visual" mesh="left_finger_prox_link"/>
<geom class="collision" mesh="left_finger_prox_link"/>

<body name="left_finger_dist_link" pos="-0.045636 -0.020423 6.9901e-05">
<inertial pos="-0.018488 0.0011091 0" quat="0.557345 0.557345 0.435162 0.435162"
mass="0.010748" diaginertia="1.91e-06 1.61e-06 5.5e-07"/>
<joint class="grip_joint" name="left_finger_tip_joint" pos="0 0 0" axis="0 0 -1"
range="-0.5 0.21" actuatorfrcrange="-1000 1000"/>
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.055 0.525 1"
mesh="left_finger_dist_link"/>
<geom type="mesh" rgba="0 0.055 0.525 1" mesh="left_finger_dist_link"/>
</body>
</body>

</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>


<equality>

<joint joint1="left_finger_bottom_joint" joint2="right_finger_bottom_joint" polycoef="0 -1 0 0 0" solref="0.01 1"
solimp="0.95 0.99 0.001"/>

<joint joint1="right_finger_tip_joint" joint2="right_finger_bottom_joint" polycoef="0.149 -0.676 0 0 0"
solref="0.01 1" solimp="0.95 0.99 0.001"/>
<joint joint1="left_finger_tip_joint" joint2="right_finger_bottom_joint" polycoef="0.149 -0.676 0 0 0"
solref="0.01 1" solimp="0.95 0.99 0.001"/>
</equality>


<contact>
<exclude body1="right_finger_prox_link" body2="right_finger_dist_link"/>
<exclude body1="left_finger_prox_link" body2="left_finger_dist_link"/>
<exclude body1="gripper_base_link" body2="right_finger_prox_link"/>
<exclude body1="gripper_base_link" body2="left_finger_prox_link"/>
</contact>

<actuator>

<position class="medium_actuator" name="a_joint_1" joint="joint_1" ctrlrange="-2.68 2.68"/>
<position class="large_actuator" name="a_joint_2" joint="joint_2" ctrlrange="-1.1344640137963142 2.5656340004316642"/>
<position class="medium_actuator" name="a_joint_3" joint="joint_3" ctrlrange="-2.61 2.61"/>
<position class="small_actuator" name="a_joint_4" joint="joint_4" ctrlrange="-2.8797932657906435 2.8797932657906435"/>
<position class="small_actuator" name="a_joint_5" joint="joint_5" ctrlrange="-2.53 2.53"/>
<position class="small_actuator" name="a_joint_6" joint="joint_6" ctrlrange="-2.8797932657906435 2.8797932657906435"/>


<position class="small_actuator" name="a_gripper" joint="right_finger_bottom_joint" ctrlrange="-0.09 0.96"/>
</actuator>


<sensor>

<force name="ee_force" site="ee_site"/>
<torque name="ee_torque" site="ee_site"/>

<jointpos name="q_right_bottom" joint="right_finger_bottom_joint"/>
<jointpos name="q_left_bottom" joint="left_finger_bottom_joint"/>
<jointpos name="q_right_tip" joint="right_finger_tip_joint"/>
<jointpos name="q_left_tip" joint="left_finger_tip_joint"/>
</sensor>

<keyframe>

<key name="home" qpos="0 0.26179939 -2.26892803 0 0.95993109 1.57079633 0.0 0.149 0.0 0.149"
ctrl="0 0.26179939 -2.26892803 0 0.95993109 1.57079633 0.0"/>

<key name="retract" qpos="0 -0.34906585 -2.54818071 0 -0.87266463 1.57079633 0.0 0.149 0.0 0.149"
ctrl="0 -0.34906585 -2.54818071 0 -0.87266463 1.57079633 0.0"/>

<key name="open" qpos="0 0 0 0 0 0 0.90 -0.4594 -0.90 -0.4594" ctrl="0 0 0 0 0 0 0.90"/>

<key name="close" qpos="0 0 0 0 0 0 -0.09 0.20984 0.09 0.20984" ctrl="0 0 0 0 0 0 -0.09"/>
</keyframe>
</mujoco>
23 changes: 23 additions & 0 deletions kinova_gen3_lite/scene.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
<mujoco model="gen3_lite scene">
<include file="gen3_lite.xml"/>

<statistic center="0.3 0 0.45" extent="0.8" meansize="0.05"/>

<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="120" 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" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
</mujoco>