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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -98,3 +98,4 @@ docs/.vitepress/cache/
docs/public/models/

CLAUDE.md
*.mjb
13 changes: 12 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,11 @@ A Python client library for interacting with [I2RT](https://i2rt.com/) products

- Plug-and-play Python interface for YAM arms and Flow Base
- Real-time robot control via CAN bus (DM series motors)
- MuJoCo gravity compensation, simulation, and URDF/MJCF models
- MuJoCo gravity + Coulomb friction compensation, with sim-side parity
- Threaded MuJoCo control loop with self-collision detection (`examples/control_with_mujoco/`)
- Gripper force control and auto-calibration
- Bimanual teleoperation and trajectory record & replay
- URDF / MJCF models for every arm and gripper
- Policy-deployment ready — works with standard robot learning pipelines

## Installation
Expand Down Expand Up @@ -98,6 +100,15 @@ python scripts/run_yam_leader.py --channel $CAN_CHANNEL
python examples/minimum_gello/minimum_gello.py --mode visualizer_local
```

### Gravity & friction compensation

YAM ships with hand-tuned per-arm YAML knobs in `i2rt/robots/config/<arm>.yml`:
`gravity_comp_factor`, `grav_comp_kd` (motor-side idle damping), and
`coulomb_friction` (applied as `friction · sign(q_dot)`). The same control law
runs in `SimRobot` via a background physics thread, so sim and hardware feel
the same. See [`docs/guides/gravity-compensation.md`](./docs/guides/gravity-compensation.md)
for the tuning workflow.

## Gripper Types

| Gripper | Motor | Notes |
Expand Down
16 changes: 13 additions & 3 deletions docs/.vitepress/config.mjs
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,9 @@ export default defineConfig({
{ text: 'Products', link: '/products/' },
{ text: 'Get Started', link: '/getting-started/installation' },
{ text: 'SDK', link: '/sdk/' },
{ text: 'Guides', link: '/guides/gravity-compensation' },
{ text: 'Examples', link: '/examples/' },
{ text: 'Releases', link: '/releases/v1.1' },
{ text: 'Releases', link: '/releases/v1.1.1' },
{ text: 'i2rt.com', link: 'https://i2rt.com', target: '_blank' },
],

Expand Down Expand Up @@ -102,8 +103,17 @@ export default defineConfig({
{
text: 'Release Notes',
items: [
{ text: 'v1.1', link: '/releases/v1.1' },
{ text: 'v1.0', link: '/releases/v1.0' },
{ text: 'v1.1.1', link: '/releases/v1.1.1' },
{ text: 'v1.1.0', link: '/releases/v1.1.0' },
{ text: 'v1.0.0', link: '/releases/v1.0.0' },
],
},
],
'/guides/': [
{
text: 'Guides',
items: [
{ text: 'Gravity & Friction Compensation', link: '/guides/gravity-compensation' },
],
},
],
Expand Down
13 changes: 11 additions & 2 deletions docs/examples/control-with-mujoco.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@

Interactive MuJoCo viewer for i2rt robots. Visualises the robot in real time and lets you move it by dragging a target marker via inverse kinematics — no hardware required in simulation mode.

The control loop runs in a background thread, performs self-collision detection (commands that would self-collide are blocked), and applies gravity compensation when running on real hardware. Pass `--log` to print joint state and torques every loop iteration.
The sliders / mocap → IK → self-collision → `command_joint_pos` pipeline runs on a daemon control thread at `control_dt = 5 ms` (200 Hz), guarded by short `viewer.lock()` sections so viewer rendering never stalls commands and vice versa. Commands that would self-collide are blocked. On real hardware the arm holds itself under gravity compensation; in simulation the same loop drives a `SimRobot` physics thread that mirrors the hardware behaviour. Pass `--log` to print joint state and torques every loop iteration.

## Hardware Required

Expand All @@ -17,12 +17,16 @@ The interface has two modes toggled with **SPACE**:

```
VIS mode (default):
Robot joint states ──► MuJoCo viewer (gravity comp active on real hw)
Robot joint states ──► MuJoCo viewer
(real hw: gravity comp idle sim: physics thread on, grav-comp active)

CONTROL mode (press SPACE):
Drag target marker ──► IK solver ──► Command arm
(real hw: PD tracks target sim: physics paused; arm teleports)
```

In `--sim`, SPACE additionally calls `SimRobot.enable_gravity_comp()` / `disable_gravity_comp()` so the simulated arm settles under gravity in VIS and follows the IK target instantly in CONTROL — matching the hardware feel. Returning to VIS calls `MotorChainRobot.enter_gravity_comp_idle()` (real hw) or re-enables the physics thread (sim) so the arm is left in a clean float, not holding the last PD target.

## Running

### Simulation
Expand Down Expand Up @@ -82,3 +86,8 @@ All YAM-family arm × gripper combinations are supported:
| `yam_ultra` | same as yam |
| `big_yam` | same as yam |
| `no_arm` | any gripper except `no_gripper` (gripper-only test rig) |

## See Also

- [Gravity & Friction Compensation](/guides/gravity-compensation) — what SPACE actually toggles, and how to tune it.
- [YAM Arm SDK reference](/sdk/yam-arm) — `get_yam_robot()` arguments and `MotorChainRobot` API.
131 changes: 131 additions & 0 deletions docs/guides/gravity-compensation.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,131 @@
# Gravity & Friction Compensation

YAM arms compute gravity torques from their MuJoCo model and add them to every motor command, so the arm "floats" against gravity. From v1.1.1 the same control law also includes per-joint **Coulomb friction compensation** and per-joint **motor-side idle damping (`grav_comp_kd`)**. Together they make the arm easy to backdrive while keeping idle behaviour stable.

This page covers what each knob does, how to tune them, and how the sim mirrors the hardware.

## How the torque command is built

In gravity-comp idle (`zero_gravity_mode=True`, no active control command), each motor receives:

```
τ = g(q) · gravity_comp_factor + coulomb_friction · sign(q_dot)
```

plus motor-side MIT-mode `kd` damping equal to `grav_comp_kd[i]` running at kHz on the motor's onboard loop.

Under an active PD command (`command_joint_pos` / `command_joint_state`):

```
τ = τ_PD + g(q) · gravity_comp_factor + coulomb_friction · sign(q_dot)
```

`grav_comp_kd` is **not** applied during PD control — `self._kd` is used instead, so PD tracking gains are unchanged. The relevant code lives in `i2rt/robots/motor_chain_robot.py:340-355`.

## Per-arm YAML configuration

Tuning lives in `i2rt/robots/config/<arm>.yml`. The current YAM defaults:

```yaml
gravity_comp_factor: [1.0, 1.1, 1.1, 1.2, 1.0, 1.0]
grav_comp_kd: [0.1, 0.1, 0.1, 0.3, 0.05, 0.05]
coulomb_friction: [0.3, 0.3, 0.3, 0.06, 0.06, 0.06]
```

| Field | Units | Purpose |
|-------|-------|---------|
| `gravity_comp_factor` | unitless multiplier on `g(q)` | Compensates per-joint underdrive (gear loss, harness drag). Six elements, one per arm joint. |
| `grav_comp_kd` | MIT-mode kd (motor units) | Passive idle damping on the motor's onboard loop. Six elements; only active when the robot is in gravity-comp idle. |
| `coulomb_friction` | Nm | Magnitude of `friction · sign(q_dot)` injection. Six elements; cancels static stiction so light pushes move the joint. |

The gripper slot is automatically padded with `0.0` in [`i2rt/robots/get_robot.py:206-207`](https://github.com/i2rt-robotics/i2rt/blob/main/i2rt/robots/get_robot.py) — gripper joints are position-commanded and need no passive compensation.

::: tip Per-arm defaults
`yam_pro.yml`, `yam_ultra.yml`, and `big_yam.yml` ship sensible starting values, but the wrist joints in particular vary with payload — expect to retune `grav_comp_kd[3]` (J4) and `coulomb_friction[3]` on a custom build.
:::

## Runtime override

Only `gravity_comp_factor` can be overridden per-call:

```python
import numpy as np
from i2rt.robots.get_robot import get_yam_robot

robot = get_yam_robot(
channel="can0",
gravity_comp_factor=np.array([1.0, 1.15, 1.10, 1.25, 1.0, 1.0]),
)
```

`grav_comp_kd` and `coulomb_friction` are YAML-only — they're hardware-tuning constants tied to the specific arm build, so they live with the arm config.

## Mode transitions: `enter_gravity_comp_idle()`

After issuing PD commands you can return the arm to a clean gravity-comp idle:

```python
robot.command_joint_pos(target) # active PD
# ... do work ...
robot.enter_gravity_comp_idle() # back to floating, with grav_comp_kd damping
```

This sets `self._commands` to zeros with `kd = grav_comp_kd`, so the arm stops actively tracking the last target and resumes the float-and-damp behaviour. The MuJoCo viewer (`examples/control_with_mujoco/`) calls this automatically on every CONTROL → VIS toggle.

::: warning Why this matters
Before v1.1.1 the viewer used `update_kp_kd(zeros, zeros)` on toggle. That only rewrote member caches and left the stale PD target in `_commands`, so the motors kept holding the last CONTROL pose — felt as per-joint friction after returning to VIS. If you call `update_kp_kd` directly, follow it with `enter_gravity_comp_idle()` to clear the stale target.
:::

## Simulation parity

`SimRobot` runs a daemon **physics thread** (`_physics_loop` in `i2rt/robots/sim_robot.py`) that applies model-based gravity comp at the same `gravity_comp_factor` schedule as hardware. The MuJoCo viewer toggles it via:

```python
robot.enable_gravity_comp() # VIS mode
robot.disable_gravity_comp() # CONTROL mode (teleport on; physics paused)
```

`get_yam_robot(sim=True)` passes a unit factor (`np.ones(...)`) so sim uses the unscaled MuJoCo gravity — there's no harness-loss or gear-loss to compensate for. `coulomb_friction` and `grav_comp_kd` flow through but have no observable effect in sim, because the MuJoCo model has no Coulomb friction and no MIT-mode motor model.

## Tuning workflow

Start from the per-arm defaults and adjust in this order:

1. **Set `gravity_comp_factor`.** Lift the arm to a horizontal pose and release. Increase `gravity_comp_factor[i]` on whichever joint sags first; decrease on whichever drifts up. Tune one joint at a time, shoulder-to-wrist.
2. **Set `coulomb_friction`.** Once the arm holds pose, give each joint a small push. If a joint resists at first then "snaps free", raise its `coulomb_friction` slightly. Stop just before joints start drifting on their own.
3. **Set `grav_comp_kd` only if needed.** If a joint chatters or limit-cycles after release, raise its `grav_comp_kd`. Most joints don't need it (defaults near 0.05–0.1); only J4 typically needs more on bigger wrists.

::: tip Quick test loop
Run the arm in gravity-comp idle from any of these entry points — all three accept `--arm`, `--gripper`, and `--channel`:

```bash
# Headless: just brings the arm up in grav-comp idle (add --log for a live joint/torque table)
python i2rt/robots/motor_chain_robot.py --arm yam --gripper linear_4310 --channel can0

# Browser viewer (Viser) — mirror, IK drag, per-joint sliders
python examples/control_with_viser/control_with_viser.py --arm yam --gripper linear_4310 --channel can0

# MuJoCo viewer — VIS/CONTROL toggle, auto-calls enter_gravity_comp_idle() on toggle
python examples/control_with_mujoco/control_with_mujoco.py --arm yam --gripper linear_4310 --channel can0
```

Edit the YAML, re-run, repeat. No code changes needed.
:::

## Troubleshooting

| Symptom | Likely cause | Fix |
|---------|------|-----|
| Joint sags slowly under gravity | `gravity_comp_factor` too low | Raise the per-joint factor by 0.05–0.10 increments |
| Joint drifts up against gravity | `gravity_comp_factor` too high | Lower the per-joint factor |
| Joint chatters / limit-cycles when released | Stiction interacting with under-compensation; or `grav_comp_kd` too low | First, recheck `gravity_comp_factor`; if clean, raise `grav_comp_kd` |
| Joint feels "sticky" — needs a push to start moving, then moves freely | `coulomb_friction` too low | Raise the per-joint friction value |
| Joint walks on its own after release | `coulomb_friction` too high | Lower the per-joint friction value |
| Arm "holds" the previous PD target after CONTROL → VIS | `enter_gravity_comp_idle()` was not called | Use the v1.1.1 viewer (auto-calls), or call it yourself after `command_joint_pos` |
| Sim arm flops to the floor | `enable_gravity_comp()` was not called or `start_server()` not invoked | Use `mujoco_control_interface` (calls both for you) |

## See also

- [YAM Arm SDK reference](/sdk/yam-arm) — `get_yam_robot()` arguments and the `MotorChainRobot` API.
- [MuJoCo Control example](/examples/control-with-mujoco) — interactive grav-comp testbed.
- [v1.1.1 release notes](/releases/v1.1.1) — the PR that introduced these knobs.
2 changes: 1 addition & 1 deletion docs/releases/v1.0.md → docs/releases/v1.0.0.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# v1.0 Release Notes
# v1.0.0 Release Notes

**Date:** 2026-03-03

Expand Down
2 changes: 1 addition & 1 deletion docs/releases/v1.1.md → docs/releases/v1.1.0.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# v1.1 Release Notes
# v1.1.0 Release Notes

**Date:** 2026-05-05

Expand Down
53 changes: 53 additions & 0 deletions docs/releases/v1.1.1.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
# v1.1.1 Release Notes

**Date:** 2026-05-06

## Highlights

A patch release on top of v1.1 focused on stability of the gravity-compensation idle and on real-hardware feel. Adds **Coulomb friction compensation**, **motor-side idle damping (`grav_comp_kd`)**, **gravity compensation in simulation**, and threads the **MuJoCo control loop** so the viewer never stalls commands.

See the new [Gravity & Friction Compensation guide](/guides/gravity-compensation) for the physics, YAML knobs, and tuning workflow.

## Gravity-Comp Idle Damping (`grav_comp_kd`)

- New per-arm YAML field in `i2rt/robots/config/<arm>.yml` — one value per arm joint (gripper slot is auto-padded with `0.0` in `get_robot.py`).
- Implemented as **motor-side MIT-mode kd**, so the damping closes on the motor's onboard kHz loop with no CAN round-trip. This replaces an earlier host-side `-damping * qvel` approach that introduced one-sample delay and amplified CAN velocity quantization noise — together producing a stiction limit cycle.
- Active only while the arm is in gravity-comp idle (`zero_gravity_mode=True`); `command_joint_pos` / `command_joint_state` continue to use `self._kd` as before, so PD tracking is unchanged.
- Hand-tuned shipping defaults (`yam.yml`):
```yaml
grav_comp_kd: [0.1, 0.1, 0.1, 0.3, 0.05, 0.05]
```

## Coulomb Friction Compensation (`coulomb_friction`)

- New per-arm YAML field. Added to gravity torque in `MotorChainRobot.update()` as `coulomb_friction * sign(q_dot)`.
- Cancels the velocity-direction-dependent stiction torque so small joint perturbations move freely instead of needing to overcome static friction first.
- Sim path: friction comp is harmless but has no observable effect, since `SimRobot` has no joint friction in MuJoCo by default.
- Shipping defaults (`yam.yml`):
```yaml
coulomb_friction: [0.3, 0.3, 0.3, 0.06, 0.06, 0.06]
```

## `MotorChainRobot.enter_gravity_comp_idle()`

- New public method that resets `self._commands` to zeros with `kd = grav_comp_kd`, mirroring the `zero_gravity_mode=True` initialisation branch. Leaves `self._kp` / `self._kd` untouched so subsequent control commands keep their gains.
- The MuJoCo viewer (`mujoco_control_interface.py`) now calls this on every CONTROL → VIS toggle. The previous `update_kp_kd(zeros, zeros)` call only rewrote member caches and left a stale PD target in `_commands`, so motors kept holding the last CONTROL pose — felt as per-joint friction after toggling back to VIS.

## Sim-Side Gravity Compensation in `SimRobot`

- `SimRobot.start_server()` now spawns a daemon **physics thread** (`_physics_loop`) that steps MuJoCo with model-based gravity-comp torques applied at the same `gravity_comp_factor` schedule as hardware. `get_yam_robot(sim=True)` passes `np.ones(...)` so sim uses the unscaled model gravity.
- New `enable_gravity_comp()` / `disable_gravity_comp()` methods toggle the loop. The MuJoCo viewer drives both methods on SPACE in `--sim`, mirroring the hardware VIS ↔ CONTROL behaviour.
- Clean shutdown: `close()` joins the physics thread.

## Threaded MuJoCo Control Loop

- `i2rt/utils/mujoco_control_interface.py` moves sliders / mocap → IK → self-collision check → `command_joint_pos` into a daemon thread at `control_dt = 5 ms` (200 Hz). Commands are no longer driven by the viewer's render loop.
- Shared `MjData` is guarded by `viewer.lock()`; locks are held only for short snapshot / write-back sections so viewer rendering never stalls commands and vice versa.
- In sim mode, the interface defaults to **VIS** on launch (so the arm settles under gravity comp before any teleport) and toggles between sim grav-comp on (VIS) / off (CONTROL) on SPACE.

## Tuning Notes

- `gravity_comp_factor` was retuned across arms once friction comp became active — JN values were lowered slightly because static friction had previously been masking under-compensation.
- `big_yam` ships a higher `grav_comp_kd` on the wrist J4 (0.3 vs 0.15) to match its larger moment arm.

See [`/guides/gravity-compensation`](/guides/gravity-compensation) for the recommended workflow when retuning a custom build.
30 changes: 30 additions & 0 deletions docs/sdk/yam-arm.md
Original file line number Diff line number Diff line change
Expand Up @@ -136,6 +136,18 @@ Update the PD gains at runtime.
robot.update_kp_kd(kp=new_kp_array, kd=new_kd_array)
```

### `enter_gravity_comp_idle() → None`

Reset the command buffer to zeros with `kd = grav_comp_kd` (from the arm's YAML), returning the arm to gravity-comp idle. `self._kp` and `self._kd` are left untouched, so a later `command_joint_pos` keeps its tracking gains.

```python
robot.command_joint_pos(target)
# ... do work ...
robot.enter_gravity_comp_idle() # arm floats again, with motor-side idle damping
```

The MuJoCo viewer (`examples/control_with_mujoco/`) calls this automatically on every CONTROL → VIS toggle. See [Gravity & Friction Compensation](/guides/gravity-compensation) for details.

### `close() → None`

Safely shuts down the robot: stops the control thread and closes the CAN interface.
Expand Down Expand Up @@ -246,8 +258,26 @@ Higher `--bilateral-kp` = leader arm feels heavier (more force feedback from fol

---

## Per-Arm YAML Configuration

Hardware tuning lives in `i2rt/robots/config/<arm>.yml` — one file per arm variant. The fields most users adjust:

| Field | Type | Purpose |
|-------|------|---------|
| `kp` / `kd` | 6-element list | Per-joint PD gains used by `command_joint_pos` / `command_joint_state`. |
| `gravity_comp_factor` | 6-element list | Per-joint multiplier on the model gravity torque. May be overridden per-call via `get_yam_robot(gravity_comp_factor=...)`. |
| `grav_comp_kd` | 6-element list | Motor-side MIT-mode kd applied **only** in gravity-comp idle. Tunes how stiff the arm feels when released. YAML-only. |
| `coulomb_friction` | 6-element list, Nm | Magnitude of `friction · sign(q_dot)` injected alongside gravity comp. Cancels static stiction. YAML-only. |

The gripper slot is automatically padded with `0.0` for `grav_comp_kd` and `coulomb_friction` in `i2rt/robots/get_robot.py` — gripper joints don't need passive compensation.

See [Gravity & Friction Compensation](/guides/gravity-compensation) for the full physics, tuning workflow, and troubleshooting.

---

## See Also

- [Quick Start](/getting-started/quick-start)
- [Grippers](/sdk/grippers)
- [Gravity & Friction Compensation](/guides/gravity-compensation)
- [Bimanual Teleoperation Example](/examples/bimanual-teleoperation)
Loading
Loading