Skip to content
Open
Show file tree
Hide file tree
Changes from 14 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
5 changes: 4 additions & 1 deletion mujoco_playground/_src/manipulation/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
from mujoco_playground._src.manipulation.franka_emika_panda_robotiq import push_cube as robotiq_push_cube
from mujoco_playground._src.manipulation.leap_hand import reorient as leap_cube_reorient
from mujoco_playground._src.manipulation.leap_hand import rotate_z as leap_rotate_z

from mujoco_playground._src.manipulation.aero_hand import rotate_z as aero_hand_rotate_z

_envs = {
"AlohaHandOver": aloha_handover.HandOver,
Expand All @@ -40,6 +40,7 @@
"PandaRobotiqPushCube": robotiq_push_cube.PandaRobotiqPushCube,
"LeapCubeReorient": leap_cube_reorient.CubeReorient,
"LeapCubeRotateZAxis": leap_rotate_z.CubeRotateZAxis,
"AeroCubeRotateZAxis": aero_hand_rotate_z.CubeRotateZAxis,
}

_cfgs = {
Expand All @@ -52,11 +53,13 @@
"PandaRobotiqPushCube": robotiq_push_cube.default_config,
"LeapCubeReorient": leap_cube_reorient.default_config,
"LeapCubeRotateZAxis": leap_rotate_z.default_config,
"AeroCubeRotateZAxis": aero_hand_rotate_z.default_config,
}

_randomizer = {
"LeapCubeRotateZAxis": leap_rotate_z.domain_randomize,
"LeapCubeReorient": leap_cube_reorient.domain_randomize,
"AeroCubeRotateZAxis": aero_hand_rotate_z.domain_randomize,
}


Expand Down
150 changes: 150 additions & 0 deletions mujoco_playground/_src/manipulation/aero_hand/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,150 @@
# Tetheria Aero Hand Open with Tendon-Driven Actuation

This directory introduces a tendon-driven manipulation example that extends MuJoCo Playground with support for tendon-level control and observation in reinforcement learning tasks.

The model is adapted from the [Tetheria Aero Hand Open](https://docs.tetheria.ai/), featuring a physically accurate tendon system that emulates cable-driven actuation. In this setup, both the policy inputs and observations are defined in the tendon space, providing a complete example of training and deploying tendon-driven controllers and under-actuated fingers in MuJoCo.

An overview of the hand is shown below:

| ![Rock](imgs/rock.png) | ![Paper](imgs/paper.png) | ![Scissor](imgs/scissor.png) |
|------------------------|------------------------|------------------------|


## 1. Tendon-Driven MuJoCo Model

### 1.1 Modeling

The mechanical design is derived from URDF files, ensuring accurate representation of the real hand structure. The actuation system in the simulator models the cable design in the real hand through three key components:

#### 1.1.1 Tendon Drives
The tendons drive the hand to close the fingers and control the thumbs. These are modeled as spatial tendons in MuJoCo that follow the exact routing paths of the real cables.

#### 1.1.2 Springs
The springs, which are also modeled by tendon components in MuJoCo, provide the forces to pull the fingers in the backward direction. This creates the restoring forces necessary for finger extension.

#### 1.1.3 Pulleys
The pulleys, which are modeled as cylinders, organize the cables and springs to ensure they are routed in a similar way to the real hand. Careful placement of these pulleys ensures accurate tendon routing.

| front view| close-up of index|
|------------------------|------------------------|
| ![skeleton](imgs/skeleton.png) | ![index](imgs/index_close_up.png)

### 1.2 Parameters

#### 1.2.1 Mechanical Parameters
- **Joint limits, mass, and inertia**: Come directly from URDF and are accurate to the real hand
- **Pulley placement**: Positioned precisely where they are placed in the real hand, ensuring cable and spring routes match the real system
- **Validation**: The range of tendon between fully open and fully closed fingers in simulation (0.0459454) closely matches the real hand (0.04553) without manual adjustment

#### 1.2.2 Tendon and Spring Specifications
- **Tendon properties**: Use the same specifications as those in the real hand
- **Spring properties**: Match real hand specifications, except for the spring on the DIP joint, which is adjusted as a compromise to achieve similar joint space behavior as the real hand

#### 1.2.3 Control Parameters
All remaining parameters, including:
- Joint damping values
- Actuator gains
- Joint-specific damping coefficients

These are fine-tuned to satisfy both similar joint behaviors in simulation and the real world.


## 2. Training your own policy

We introduce a **z-axis rotation task** for the **Tetheria Aero Hand Open**, optimized using the following reward formulation:

$$
\text{reward} = 1.0 \times \text{angular velocity}
- 1.0 \times \text{action rate}
+ \text{termination} (-100.0)
$$

The optimization variables include the **tendon lengths** and the **thumb abduction joint**, which correspond to the real hand’s actuation system.
This setup ensures that the same control inputs and sensory data can be directly applied for **sim-to-real deployment** on the physical Tetheria Aero Hand Open.


To train policies for the Tetheria Hand:

```bash

# Run the training script
python learning/train_jax_ppo.py --env_name TetheriaCubeRotateZAxis
```

Although the reward curves from different training runs may vary due to stochasticity in the learning process, they consistently **converge toward a positive reward**.
The plots below show an example set of reward curves obtained from training with the **PPO algorithm**.


Overall Reward:

![overall](imgs/reward_overall.png)

Angular Velocity Reward

![reward_angvel](imgs/reward_angvel.png)

Action-Rate Penalty:

![penalty_action_rate](imgs/penalty_action_rate.png)

Termination Penalty

![penalty_termination](imgs/penalty_termination.png)

## 3. Running a pretrained policy


To test trained policies in simulation:

```bash
# Run the simulation rollout script
python learning/train_jax_ppo.py --env_name TetheriaCubeRotateZAxis --play_only --load_checkpoint_path path/to/checkpoints
```

This will:
- Load the trained policy
- Run episodes in the MuJoCo simulation
- Display the hand performing manipulation tasks

Seed = 0:

![seed = 0](imgs/cube_rotation.gif)

Seed = 1:

![seed = 1](imgs/cube_rotation1.gif)

Seed = 14:

![seed = 14](imgs/cube_rotation14.gif)

Sim2real deployment on Tetheria Aero Hand Open:

![Z-Axis Rotation Demo](imgs/output.gif)

*Note: The finger markers are **not** used.*

## File Structure

### Core Implementation
- **`tetheria_hand_tendon_constants.py`** - Constants and configuration
- **`rotate_z.py`** - Cube rotation task implementation

### XML Models
- **`xmls/right_hand.xml`** - Main hand model with tendon system
- **`xmls/scene_mjx_cube.xml`** - Manipulation scene
- **`xmls/reorientation_cube.xml`** - Cube reorientation task

## Key Features

- **Accurate tendon modeling**: Direct translation from real hand cable system
- **Precise pulley placement**: Matches real hand routing exactly
- **Validated parameters**: Tendon ranges match real hand within 0.1%

---

*This implementation provides a high-fidelity tendon-driven hand model that closely matches the real robotic hand, enabling effective sim-to-real transfer for manipulation tasks.*

## Acknowledgements
Our code is built upon
- MuJoCo playground - https://github.com/google-deepmind/mujoco_playground
17 changes: 17 additions & 0 deletions mujoco_playground/_src/manipulation/aero_hand/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# Copyright 2025 TetherIA Inc.
# Copyright 2023 DeepMind Technologies Limited
#
# Author: Nan Wang (TetherIA Inc.)
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# ==============================================================================
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
# Copyright 2025 TetherIA Inc.
# Copyright 2023 DeepMind Technologies Limited
#
# Author: Nan Wang (TetherIA Inc.)
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
# ==============================================================================

"""Constants for TetherIA Aero Hand Open."""

from mujoco_playground._src import mjx_env

ROOT_PATH = mjx_env.ROOT_PATH / "manipulation" / "aero_hand"
CUBE_XML = ROOT_PATH / "xmls" / "scene_mjx_cube.xml"

NQ = 16
NV = 16
NU = 7

JOINT_NAMES = [
# index
"right_index_mcp_flex",
"right_index_pip",
"right_index_dip",
# middle
"right_middle_mcp_flex",
"right_middle_pip",
"right_middle_dip",
# ring
"right_ring_mcp_flex",
"right_ring_pip",
"right_ring_dip",
# pinky
"right_pinky_mcp_flex",
"right_pinky_pip",
"right_pinky_dip",
# thumb
"right_thumb_cmc_abd",
"right_thumb_cmc_flex",
"right_thumb_mcp",
"right_thumb_ip",
]

ACTUATOR_NAMES = [
# index
"right_index_A_tendon",
# middle
"right_middle_A_tendon",
# ring
"right_ring_A_tendon",
# pinky
"right_pinky_A_tendon",
# thumb
"right_thumb_A_cmc_abd",
"right_th1_A_tendon",
"right_th2_A_tendon",
]

FINGERTIP_NAMES = [
"if_tip",
"mf_tip",
"rf_tip",
"pf_tip",
"th_tip",
]


SENSOR_TENDON_NAMES = [
"len_if",
"len_mf",
"len_rf",
"len_pf",
"len_th1",
"len_th2",
]

SENSOR_JOINT_NAMES = [
"len_th_abd",
]
Loading