Skip to content

Add support for MoveIt2 robots #1280

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 10 commits into
base: main
Choose a base branch
from
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
1 change: 1 addition & 0 deletions docs/source/moveit2.mdx
1 change: 1 addition & 0 deletions lerobot/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@
"aloha",
"so100",
"so101",
"annin_ar4",
]

# lists all available cameras from `lerobot/common/robot_devices/cameras`
Expand Down
2 changes: 2 additions & 0 deletions lerobot/common/robots/moveit2/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
from .config_moveit2 import AnninAR4Config, MoveIt2Config
from .moveit2 import MoveIt2
87 changes: 87 additions & 0 deletions lerobot/common/robots/moveit2/config_moveit2.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
# Copyright 2024 The HuggingFace Inc. team. All rights reserved.
#
# 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.
from dataclasses import dataclass, field

from lerobot.common.cameras import CameraConfig

from ..config import RobotConfig


@dataclass
class MoveIt2InterfaceConfig:
# Namespace used by MoveIt2 nodes
namespace: str = ""

# The MoveIt2 base link name.
base_link: str = "base_link"

arm_joint_names: list[str] = field(
default_factory=lambda: [
"joint_1",
"joint_2",
"joint_3",
"joint_4",
"joint_5",
"joint_6",
]
)

gripper_joint_name: str = "gripper_joint"

max_linear_velocity: float = 0.05
max_angular_velocity: float = 0.25 # rad/s

gripper_open_position: float = 0.0
gripper_close_position: float = 1.0


@dataclass
class MoveIt2Config(RobotConfig):
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
# Set this to a positive scalar to have the same value for all motors, or a list that is the same length as
# the number of motors in your follower arms.
max_relative_target: int | None = None

# cameras
cameras: dict[str, CameraConfig] = field(default_factory=dict)

# MoveIt2 interface configuration
moveit2_interface: MoveIt2InterfaceConfig = field(default_factory=MoveIt2InterfaceConfig)

action_from_keyboard: bool = False


@RobotConfig.register_subclass("annin_ar4")
@dataclass
class AnninAR4Config(MoveIt2Config):
"""Annin Robotics AR4 robot configuration - extends MoveIt2Config with
AR4-specific settings
"""

moveit2_interface: MoveIt2InterfaceConfig = field(
default_factory=lambda: MoveIt2InterfaceConfig(
base_link="base_link",
arm_joint_names=[
"joint_1",
"joint_2",
"joint_3",
"joint_4",
"joint_5",
"joint_6",
],
gripper_joint_name="gripper_jaw1_joint",
gripper_open_position=0.014,
gripper_close_position=0.0,
)
)
147 changes: 147 additions & 0 deletions lerobot/common/robots/moveit2/moveit2.mdx
Original file line number Diff line number Diff line change
@@ -0,0 +1,147 @@
# MoveIt2

This guide shows you how to integrate any MoveIt2-compatible robot with LeRobot. The integration uses MoveIt Servo for real-time cartesian velocity control.

## Overview

**Supported control modes:**
- ✅ Cartesian velocity control
- 🚧 End-effector pose and joint position control (coming soon)

**Compatible robots:** Any robot with a working MoveIt2 configuration package

## Prerequisites

### System Requirements

Before getting started, ensure you have the following installed:

- [ROS 2 Jazzy](https://docs.ros.org/en/jazzy/Installation.html)
- [MoveIt2](https://moveit.ai/install-moveit2/binary)


Since ROS 2 Jazzy uses Python 3.12, you must run LeRobot in a Python 3.12 virtual environment, i.e:
```bash
uv venv --python 3.12 && source .venv/bin/activate
```

### Robot Setup

Your robot must be properly configured and working with MoveIt2 before integration:

- ✅ MoveIt2 configuration package exists for your robot
- ✅ `move_group` and `moveit_servo` nodes can be launched successfully
- ✅ Robot is calibrated and ready for operation

See [AR4 ROS Driver](https://github.com/ycheng517/ar4_ros_driver) for an example of a MoveIt2-enabled robot that works with LeRobot.

## Configuration

Create a config class for your robot by sub-classing `MoveIt2Config`.
You may override joint names, gripper configurations, and other parameters as needed.
An example config class may look like this:

```python
from dataclasses import dataclass, field
from lerobot.common.robots.config import RobotConfig
from lerobot.common.robots.moveit2.config_moveit2 import MoveIt2Config, MoveIt2InterfaceConfig

@RobotConfig.register_subclass("my_moveit2_robot")
@dataclass
class MyRobotConfig(MoveIt2Config):
moveit2_interface: MoveIt2InterfaceConfig = field(
default_factory=lambda: MoveIt2InterfaceConfig(
base_link="base_link",
arm_joint_names=[
"joint_1",
"joint_2",
"joint_3",
"joint_4",
"joint_5",
"joint_6",
],
gripper_joint_name="gripper_joint",
gripper_open_position=0.0,
gripper_close_position=1.0,
max_linear_velocity=0.05, # m/s
max_angular_velocity=0.25, # rad/s
)
)
```

## Getting Started

### Step 1: Launch Your Robot

Start your MoveIt2-enabled robot stack.
The exact commands depend on your robot model and configuration.

**Example: Annin Robotics AR4**
```bash
# Launch the robot driver
ros2 launch annin_ar4_driver driver.launch.py ar_model:=mk1 calibrate:=True

# Launch MoveIt2 with Moveit Servo enabled
ros2 launch annin_ar4_moveit_config moveit.launch.py ar_model:=mk1 moveit_servo:=True
```

### Step 2: Verify Robot Status

Before teleoperation, verify your robot is ready:

1. **Check that required nodes are running**:
```bash
ros2 node list | grep -E "(move_group|servo_node)"
```

2. **Verify joint states are being published**:
```bash
ros2 topic echo /joint_states --once
```

3. **Check MoveIt Servo services are available**:
```bash
ros2 service list | grep servo_node
```

### Step 3: Teleoperation (with keyboard)

Once your robot is launched and ready, you can teleoperate it using keyboard controls:

```bash
# Source the ROS environment
source /opt/ros/jazzy/setup.bash

python -m lerobot.teleoperate \
--robot.type=my_robot \
--robot.id=my_robot_arm \
--robot.action_from_keyboard=True \
--teleop.type=keyboard \
--teleop.id=keyboard_controller \
--display_data=true
```

#### Control Mapping

The default keyboard mapping provides intuitive control:

| Key | Action |
|-----|--------|
| `A/D` | Move left/right (X-axis) |
| `W/S` | Move backward/forward (Y-axis) |
| `N/M` | Move down/up (Z-axis) |
| `I/K` | Rotate around X-axis |
| `J/L` | Rotate around Y-axis |
| `U/O` | Rotate around Z-axis |
| `Space` | Close gripper (hold to close) |

> **Note**: The gripper closes when Space is held down, and opens when released. All movements are velocity-based and stop when keys are released.

### Next Steps

Once you have teleoperation working, you can use all standard LeRobot features as usual:

- Incorporate cameras and other sensors
- Use `lerobot.record` to collect demonstration datasets
- Use `lerobot.replay` to test recorded trajectories
- Train policies on your robot's data
Loading