mirror of
https://github.com/huggingface/lerobot.git
synced 2026-06-02 20:01:25 +00:00
Compare commits
8 Commits
accelerate
...
fix/aloha
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
ed773219c0 | ||
|
|
a075669184 | ||
|
|
bc953e4b5a | ||
|
|
6b62113515 | ||
|
|
d602e8169c | ||
|
|
49baccdccb | ||
|
|
6a3d57031a | ||
|
|
d74494d92b |
@@ -35,6 +35,8 @@
|
|||||||
title: Koch v1.1
|
title: Koch v1.1
|
||||||
- local: lekiwi
|
- local: lekiwi
|
||||||
title: LeKiwi
|
title: LeKiwi
|
||||||
|
- local: reachy2
|
||||||
|
title: Reachy 2
|
||||||
title: "Robots"
|
title: "Robots"
|
||||||
- sections:
|
- sections:
|
||||||
- local: notebooks
|
- local: notebooks
|
||||||
|
|||||||
288
docs/source/reachy2.mdx
Normal file
288
docs/source/reachy2.mdx
Normal file
@@ -0,0 +1,288 @@
|
|||||||
|
# Reachy 2
|
||||||
|
|
||||||
|
Reachy 2 is an open-source humanoid robot made by Pollen Robotics, specifically designed for the development of embodied AI and real-world applications.
|
||||||
|
Check out [Pollen Robotics website](https://www.pollen-robotics.com/reachy/), or access [Reachy 2 documentation](https://docs.pollen-robotics.com/) for more information on the platform!
|
||||||
|
|
||||||
|
## Teleoperate Reachy 2
|
||||||
|
|
||||||
|
Currently, there are two ways to teleoperate Reachy 2:
|
||||||
|
|
||||||
|
- Pollen Robotics’ VR teleoperation (not included in LeRobot).
|
||||||
|
- Robot-to-robot teleoperation (use one Reachy 2 to control another).
|
||||||
|
|
||||||
|
## Reachy 2 Simulation
|
||||||
|
|
||||||
|
**(Linux only)** You can run Reachy 2 in simulation (Gazebo or MuJoCo) using the provided [Docker image](https://hub.docker.com/r/pollenrobotics/reachy2_core).
|
||||||
|
|
||||||
|
1. Install [Docker Engine](https://docs.docker.com/engine/).
|
||||||
|
2. Run (for MuJoCo):
|
||||||
|
|
||||||
|
```
|
||||||
|
docker run --rm -it \
|
||||||
|
--name reachy \
|
||||||
|
--privileged \
|
||||||
|
--network host \
|
||||||
|
--ipc host \
|
||||||
|
--device-cgroup-rule='c 189:* rwm' \
|
||||||
|
--group-add audio \
|
||||||
|
-e ROS_DOMAIN_ID="$ROS_DOMAIN_ID" \
|
||||||
|
-e DISPLAY="$DISPLAY" \
|
||||||
|
-e RCUTILS_CONSOLE_OUTPUT_FORMAT="[{severity}]: {message}" \
|
||||||
|
-e REACHY2_CORE_SERVICE_FAKE="${REACHY2_CORE_SERVICE_FAKE:-true}" \
|
||||||
|
-v /dev:/dev \
|
||||||
|
-v "$HOME/.reachy_config":/home/reachy/.reachy_config_override \
|
||||||
|
-v "$HOME/.reachy.log":/home/reachy/.ros/log \
|
||||||
|
-v /usr/lib/x86_64-linux-gnu:/opt/host-libs \
|
||||||
|
--entrypoint /package/launch.sh \
|
||||||
|
pollenrobotics/reachy2_core:1.7.5.9_deploy \
|
||||||
|
start_rviz:=true start_sdk_server:=true mujoco:=true
|
||||||
|
```
|
||||||
|
|
||||||
|
> If MuJoCo runs slowly (low simulation frequency), append `-e LD_LIBRARY_PATH="/opt/host-libs:$LD_LIBRARY_PATH" \` to the previous command to improve performance:
|
||||||
|
>
|
||||||
|
> ```
|
||||||
|
> docker run --rm -it \
|
||||||
|
> --name reachy \
|
||||||
|
> --privileged \
|
||||||
|
> --network host \
|
||||||
|
> --ipc host \
|
||||||
|
> --device-cgroup-rule='c 189:* rwm' \
|
||||||
|
> --group-add audio \
|
||||||
|
> -e ROS_DOMAIN_ID="$ROS_DOMAIN_ID" \
|
||||||
|
> -e DISPLAY="$DISPLAY" \
|
||||||
|
> -e RCUTILS_CONSOLE_OUTPUT_FORMAT="[{severity}]: {message}" \
|
||||||
|
> -e REACHY2_CORE_SERVICE_FAKE="${REACHY2_CORE_SERVICE_FAKE:-true}" \
|
||||||
|
> -e LD_LIBRARY_PATH="/opt/host-libs:$LD_LIBRARY_PATH" \
|
||||||
|
> -v /dev:/dev \
|
||||||
|
> -v "$HOME/.reachy_config":/home/reachy/.reachy_config_override \
|
||||||
|
> -v "$HOME/.reachy.log":/home/reachy/.ros/log \
|
||||||
|
> -v /usr/lib/x86_64-linux-gnu:/opt/host-libs \
|
||||||
|
> --entrypoint /package/launch.sh \
|
||||||
|
> pollenrobotics/reachy2_core:1.7.5.9_deploy \
|
||||||
|
> start_rviz:=true start_sdk_server:=true mujoco:=true
|
||||||
|
> ```
|
||||||
|
|
||||||
|
## Setup
|
||||||
|
|
||||||
|
### Prerequisites
|
||||||
|
|
||||||
|
- On your robot, check the **service images** meet the minimum versions:
|
||||||
|
- **reachy2-core >= 1.7.5.2**
|
||||||
|
- **webrtc >= 2.0.1.1**
|
||||||
|
|
||||||
|
Then, if you want to use VR teleoperation:
|
||||||
|
|
||||||
|
- Install the [Reachy 2 teleoperation application](https://docs.pollen-robotics.com/teleoperation/teleoperation-introduction/discover-teleoperation/).
|
||||||
|
Use version **>=v1.2.0**
|
||||||
|
|
||||||
|
We recommend using two computers: one for teleoperation (Windows required) and another for recording with LeRobot.
|
||||||
|
|
||||||
|
### Install LeRobot
|
||||||
|
|
||||||
|
Follow the [installation instructions](https://github.com/huggingface/lerobot#installation) to install LeRobot.
|
||||||
|
|
||||||
|
Install LeRobot with Reachy 2 dependencies:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
pip install -e ".[reachy2]"
|
||||||
|
```
|
||||||
|
|
||||||
|
### (Optional but recommended) Install pollen_data_acquisition_server
|
||||||
|
|
||||||
|
How you manage Reachy 2 recording sessions is up to you, but the **easiest** way is to use this server so you can control sessions directly from the VR teleoperation app.
|
||||||
|
|
||||||
|
> **Note:** Currently, only the VR teleoperation application works as a client for this server, so this step primarily targets teleoperation. You’re free to develop custom clients to manage sessions to your needs.
|
||||||
|
|
||||||
|
In your LeRobot environment, install the server from source:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
git clone https://github.com/pollen-robotics/pollen_data_acquisition_server.git
|
||||||
|
cd pollen_data_acquisition_server
|
||||||
|
pip install -e .
|
||||||
|
```
|
||||||
|
|
||||||
|
Find the [pollen_data_acquisition_server documentation here](https://github.com/pollen-robotics/pollen_data_acquisition_server).
|
||||||
|
|
||||||
|
## Step 1: Recording
|
||||||
|
|
||||||
|
### Get Reachy 2 IP address
|
||||||
|
|
||||||
|
Before starting teleoperation and data recording, find the [robot's IP address](https://docs.pollen-robotics.com/getting-started/setup-reachy2/connect-reachy2/).
|
||||||
|
We strongly recommend connecting all devices (PC and robot) via **Ethernet**.
|
||||||
|
|
||||||
|
### Launch recording
|
||||||
|
|
||||||
|
There are two ways to manage recording sessions when using the Reachy 2 VR teleoperation application:
|
||||||
|
|
||||||
|
- **Using the data acquisition server (recommended for VR teleop)**: The VR app orchestrates sessions (via the server it tells LeRobot when to create datasets, start/stop episodes) while also controlling the robot’s motions.
|
||||||
|
- **Using LeRobot’s record script**: LeRobot owns session control and decides when to start/stop episodes. If you also use the VR teleop app, it’s only for motion control.
|
||||||
|
|
||||||
|
### Option 1: Using Pollen data acquisition server (recommended for VR teleop)
|
||||||
|
|
||||||
|
Make sure you have installed pollen_data_acquisition_server, as explained in the Setup section.
|
||||||
|
|
||||||
|
Launch the data acquisition server to be able to manage your session directly from the teleoperation application:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m pollen_data_acquisition_server.server
|
||||||
|
```
|
||||||
|
|
||||||
|
Then get into the teleoperation application and choose "Data acquisition session".
|
||||||
|
You can finally setup your session by following the screens displayed.
|
||||||
|
|
||||||
|
> Even without the VR app, you can use the `pollen_data_acquisition_server` with your own client implementation.
|
||||||
|
|
||||||
|
### Option 2: Using lerobot.record
|
||||||
|
|
||||||
|
Reachy 2 is fully supported by LeRobot’s recording features.
|
||||||
|
If you choose this option but still want to use the VR teleoperation application, select "Standard session" in the app.
|
||||||
|
|
||||||
|
**Example: start a recording without the mobile base:**
|
||||||
|
First add reachy2 and reachy2_teleoperator to the imports of the record script. Then you can use the following command:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m lerobot.record \
|
||||||
|
--robot.type=reachy2 \
|
||||||
|
--robot.ip_address=192.168.0.200 \
|
||||||
|
--robot.id=r2-0000 \
|
||||||
|
--robot.use_external_commands=true \
|
||||||
|
--robot.with_mobile_base=false \
|
||||||
|
--teleop.type=reachy2_teleoperator \
|
||||||
|
--teleop.ip_address=192.168.0.200 \
|
||||||
|
--teleop.with_mobile_base=false \
|
||||||
|
--dataset.repo_id=pollen_robotics/record_test \
|
||||||
|
--dataset.single_task="Reachy 2 recording test" \
|
||||||
|
--dataset.num_episodes=1 \
|
||||||
|
--dataset.episode_time_s=5 \
|
||||||
|
--dataset.fps=15 \
|
||||||
|
--dataset.push_to_hub=true \
|
||||||
|
--dataset.private=true \
|
||||||
|
--display_data=true
|
||||||
|
```
|
||||||
|
|
||||||
|
#### Specific Options
|
||||||
|
|
||||||
|
**Extended setup overview (all options included):**
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m lerobot.record \
|
||||||
|
--robot.type=reachy2 \
|
||||||
|
--robot.ip_address=192.168.0.200 \
|
||||||
|
--robot.use_external_commands=true \
|
||||||
|
--robot.with_mobile_base=true \
|
||||||
|
--robot.with_l_arm=true \
|
||||||
|
--robot.with_r_arm=true \
|
||||||
|
--robot.with_neck=true \
|
||||||
|
--robot.with_antennas=true \
|
||||||
|
--robot.with_left_teleop_camera=true \
|
||||||
|
--robot.with_right_teleop_camera=true \
|
||||||
|
--robot.with_torso_camera=false \
|
||||||
|
--robot.disable_torque_on_disconnect=false \
|
||||||
|
--robot.max_relative_target=5.0 \
|
||||||
|
--teleop.type=reachy2_teleoperator \
|
||||||
|
--teleop.ip_address=192.168.0.200 \
|
||||||
|
--teleop.use_present_position=false \
|
||||||
|
--teleop.with_mobile_base=false \
|
||||||
|
--teleop.with_l_arm=true \
|
||||||
|
--teleop.with_r_arm=true \
|
||||||
|
--teleop.with_neck=true \
|
||||||
|
--teleop.with_antennas=true \
|
||||||
|
--dataset.repo_id=pollen_robotics/record_test \
|
||||||
|
--dataset.single_task="Reachy 2 recording test" \
|
||||||
|
--dataset.num_episodes=1 \
|
||||||
|
--dataset.episode_time_s=5 \
|
||||||
|
--dataset.fps=15 \
|
||||||
|
--dataset.push_to_hub=true \
|
||||||
|
--dataset.private=true \
|
||||||
|
--display_data=true
|
||||||
|
```
|
||||||
|
|
||||||
|
##### `--robot.use_external_commands`
|
||||||
|
|
||||||
|
Determine whether LeRobot robot.send_action() sends commands to the robot.
|
||||||
|
**Must** be set to false while using the VR teleoperation application, as the app already sends commands.
|
||||||
|
|
||||||
|
##### `--teleop.use_present_position`
|
||||||
|
|
||||||
|
Determine whether the teleoperator reads the goal or present position of the robot.
|
||||||
|
Must be set to true if a compliant Reachy 2 is used to control another one.
|
||||||
|
|
||||||
|
##### Use the relevant parts
|
||||||
|
|
||||||
|
From our initial tests, recording **all** joints when only some are moving can reduce model quality with certain policies.
|
||||||
|
To avoid this, you can exclude specific parts from recording and replay using:
|
||||||
|
|
||||||
|
````
|
||||||
|
--robot.with_<part>=false
|
||||||
|
```,
|
||||||
|
with `<part>` being one of : `mobile_base`, `l_arm`, `r_arm", `neck`, `antennas`.
|
||||||
|
It determine whether the corresponding part is recorded in the observations. True if not set.
|
||||||
|
|
||||||
|
By default, **all parts are recorded**.
|
||||||
|
|
||||||
|
The same per-part mechanism is available in `reachy2_teleoperator` as well.
|
||||||
|
|
||||||
|
````
|
||||||
|
|
||||||
|
--teleop.with\_<part>
|
||||||
|
|
||||||
|
```
|
||||||
|
with `<part>` being one of : `mobile_base`, `l_arm`, `r_arm", `neck`, `antennas`.
|
||||||
|
Determine whether the corresponding part is recorded in the actions. True if not set.
|
||||||
|
|
||||||
|
> **Important:** In a given session, the **enabled parts must match** on both the robot and the teleoperator.
|
||||||
|
For example, if the robot runs with `--robot.with_mobile_base=false`, the teleoperator must disable the same part `--teleoperator.with_mobile_base=false`.
|
||||||
|
|
||||||
|
##### Use the relevant cameras
|
||||||
|
|
||||||
|
You can do the same for **cameras**. By default, only the **teleoperation cameras** are recorded (both `left_teleop_camera` and `right_teleop_camera`). Enable or disable each camera with:
|
||||||
|
|
||||||
|
```
|
||||||
|
|
||||||
|
--robot.with_left_teleop_camera=<true|false>
|
||||||
|
--robot.with_right_teleop_camera=<true|false>
|
||||||
|
--robot.with_torso_camera=<true|false>
|
||||||
|
|
||||||
|
````
|
||||||
|
|
||||||
|
|
||||||
|
## Step 2: Replay
|
||||||
|
|
||||||
|
Make sure the robot is configured with the same parts as the dataset:
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m lerobot.replay \
|
||||||
|
--robot.type=reachy2 \
|
||||||
|
--robot.ip_address=192.168.0.200 \
|
||||||
|
--robot.use_external_commands=false \
|
||||||
|
--robot.with_mobile_base=false \
|
||||||
|
--dataset.repo_id=pollen_robotics/record_test \
|
||||||
|
--dataset.episode=0
|
||||||
|
--display_data=true
|
||||||
|
````
|
||||||
|
|
||||||
|
## Step 3: Train
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m lerobot.scripts.train \
|
||||||
|
--dataset.repo_id=pollen_robotics/record_test \
|
||||||
|
--policy.type=act \
|
||||||
|
--output_dir=outputs/train/reachy2_test \
|
||||||
|
--job_name=reachy2 \
|
||||||
|
--policy.device=mps \
|
||||||
|
--wandb.enable=true \
|
||||||
|
--policy.repo_id=pollen_robotics/record_test_policy
|
||||||
|
```
|
||||||
|
|
||||||
|
## Step 4: Evaluate
|
||||||
|
|
||||||
|
```bash
|
||||||
|
python -m lerobot.record \
|
||||||
|
--robot.type=reachy2 \
|
||||||
|
--robot.ip_address=192.168.0.200 \
|
||||||
|
--display_data=false \
|
||||||
|
--dataset.repo_id=pollen_robotics/eval_record_test \
|
||||||
|
--dataset.single_task="Evaluate reachy2 policy" \
|
||||||
|
--dataset.num_episodes=10 \
|
||||||
|
--policy.path=outputs/train/reachy2_test/checkpoints/last/pretrained_model
|
||||||
|
```
|
||||||
47
examples/aloha_calibrate.py
Normal file
47
examples/aloha_calibrate.py
Normal file
@@ -0,0 +1,47 @@
|
|||||||
|
# ------------------------------------------------------------
|
||||||
|
|
||||||
|
# config_follower_right = ViperXConfig(
|
||||||
|
# port="/dev/tty.usbserial-FT891KBG",
|
||||||
|
# id="viperx_right",
|
||||||
|
# )
|
||||||
|
|
||||||
|
# follower_right = ViperX(config_follower_right)
|
||||||
|
# follower_right.connect(calibrate=False)
|
||||||
|
# follower_right.calibrate()
|
||||||
|
# follower_right.disconnect()
|
||||||
|
|
||||||
|
# ------------------------------------------------------------
|
||||||
|
|
||||||
|
# config_leader_right = WidowXConfig(
|
||||||
|
# port="/dev/tty.usbserial-FT89FM77",
|
||||||
|
# id="widowx_right",
|
||||||
|
# )
|
||||||
|
|
||||||
|
# leader_right = WidowX(config_leader_right)
|
||||||
|
# leader_right.connect(calibrate=False)
|
||||||
|
# leader_right.calibrate()
|
||||||
|
# leader_right.disconnect()
|
||||||
|
|
||||||
|
# ------------------------------------------------------------
|
||||||
|
|
||||||
|
# config_follower_left = ViperXConfig(
|
||||||
|
# port="/dev/tty.usbserial-FT89FM09",
|
||||||
|
# id="viperx_left",
|
||||||
|
# )
|
||||||
|
|
||||||
|
# follower_left = ViperX(config_follower_left)
|
||||||
|
# follower_left.connect(calibrate=False)
|
||||||
|
# follower_left.calibrate()
|
||||||
|
# follower_left.disconnect()
|
||||||
|
|
||||||
|
# ------------------------------------------------------------
|
||||||
|
|
||||||
|
# config_leader_left = WidowXConfig(
|
||||||
|
# port="/dev/tty.usbserial-FT891KPN",
|
||||||
|
# id="widowx_left",
|
||||||
|
# )
|
||||||
|
|
||||||
|
# leader_left = WidowX(config_leader_left)
|
||||||
|
# leader_left.connect(calibrate=False)
|
||||||
|
# leader_left.calibrate()
|
||||||
|
# leader_left.disconnect()
|
||||||
172
examples/aloha_record.py
Normal file
172
examples/aloha_record.py
Normal file
@@ -0,0 +1,172 @@
|
|||||||
|
"""
|
||||||
|
ALOHA Bimanual Recording Script
|
||||||
|
|
||||||
|
This script records episodes using ALOHA dual-arm system (ViperX followers + WidowX leaders).
|
||||||
|
|
||||||
|
Usage:
|
||||||
|
1. New dataset: Set RESUME = False
|
||||||
|
2. Resume/append: Set RESUME = True (will continue from existing episodes)
|
||||||
|
|
||||||
|
The script will:
|
||||||
|
- Record NUM_EPISODES new episodes
|
||||||
|
- Show progress with total episode count
|
||||||
|
- Push dataset to HuggingFace Hub when complete
|
||||||
|
"""
|
||||||
|
|
||||||
|
from lerobot.cameras.opencv.configuration_opencv import OpenCVCameraConfig
|
||||||
|
from lerobot.datasets.lerobot_dataset import LeRobotDataset
|
||||||
|
from lerobot.datasets.utils import hw_to_dataset_features
|
||||||
|
from lerobot.record import record_loop
|
||||||
|
from lerobot.robots.aloha import Aloha, AlohaConfig
|
||||||
|
from lerobot.teleoperators.aloha_teleop import AlohaTeleop, AlohaTeleopConfig
|
||||||
|
from lerobot.utils.control_utils import (
|
||||||
|
init_keyboard_listener,
|
||||||
|
sanity_check_dataset_name,
|
||||||
|
sanity_check_dataset_robot_compatibility,
|
||||||
|
)
|
||||||
|
from lerobot.utils.utils import log_say
|
||||||
|
from lerobot.utils.visualization_utils import _init_rerun
|
||||||
|
|
||||||
|
# Recording configuration
|
||||||
|
NUM_EPISODES = 0
|
||||||
|
FPS = 30
|
||||||
|
EPISODE_TIME_SEC = 200
|
||||||
|
RESET_TIME_SEC = 30
|
||||||
|
TASK_DESCRIPTION = "First put the Hugging Face t shirt with both arms in the box, then place the hat with the right arm in the box."
|
||||||
|
REPO_ID = "pepijn223/aloha_box_2"
|
||||||
|
RESUME = True # Set to True to resume/append to existing dataset
|
||||||
|
|
||||||
|
# Create camera configuration
|
||||||
|
camera_config = {
|
||||||
|
"front": OpenCVCameraConfig(index_or_path=0, width=640, height=480, fps=FPS),
|
||||||
|
"wrist_right": OpenCVCameraConfig(index_or_path=1, width=640, height=480, fps=FPS),
|
||||||
|
"wrist_left": OpenCVCameraConfig(index_or_path=2, width=640, height=480, fps=FPS),
|
||||||
|
}
|
||||||
|
|
||||||
|
# ALOHA Robot Configuration (dual ViperX followers)
|
||||||
|
aloha_robot_config = AlohaConfig(
|
||||||
|
id="aloha",
|
||||||
|
left_arm_port="/dev/tty.usbserial-FT89FM09",
|
||||||
|
right_arm_port="/dev/tty.usbserial-FT891KBG",
|
||||||
|
left_arm_max_relative_target=20.0,
|
||||||
|
right_arm_max_relative_target=20.0,
|
||||||
|
left_arm_use_degrees=True,
|
||||||
|
right_arm_use_degrees=True,
|
||||||
|
cameras=camera_config,
|
||||||
|
)
|
||||||
|
|
||||||
|
# ALOHA Teleoperator Configuration (dual WidowX leaders)
|
||||||
|
aloha_teleop_config = AlohaTeleopConfig(
|
||||||
|
id="aloha_teleop",
|
||||||
|
left_arm_port="/dev/tty.usbserial-FT891KPN",
|
||||||
|
right_arm_port="/dev/tty.usbserial-FT89FM77",
|
||||||
|
left_arm_gripper_motor="xl430-w250",
|
||||||
|
right_arm_gripper_motor="xc430-w150",
|
||||||
|
left_arm_use_degrees=True,
|
||||||
|
right_arm_use_degrees=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
# Initialize the robot and teleoperator
|
||||||
|
robot = Aloha(aloha_robot_config)
|
||||||
|
teleop = AlohaTeleop(aloha_teleop_config)
|
||||||
|
|
||||||
|
# Configure the dataset features
|
||||||
|
action_features = hw_to_dataset_features(robot.action_features, "action")
|
||||||
|
obs_features = hw_to_dataset_features(robot.observation_features, "observation")
|
||||||
|
dataset_features = {**action_features, **obs_features}
|
||||||
|
|
||||||
|
# Create or resume the dataset
|
||||||
|
if RESUME:
|
||||||
|
print(f"Resuming existing dataset: {REPO_ID}")
|
||||||
|
dataset = LeRobotDataset(
|
||||||
|
repo_id=REPO_ID,
|
||||||
|
root=None, # Use default root
|
||||||
|
)
|
||||||
|
|
||||||
|
# Start image writer for cameras
|
||||||
|
if hasattr(robot, "cameras") and len(robot.cameras) > 0:
|
||||||
|
dataset.start_image_writer(
|
||||||
|
num_processes=0, # Use threads only
|
||||||
|
num_threads=4 * len(robot.cameras), # 4 threads per camera
|
||||||
|
)
|
||||||
|
|
||||||
|
# Sanity check compatibility
|
||||||
|
sanity_check_dataset_robot_compatibility(dataset, robot, FPS, dataset_features)
|
||||||
|
print(f"Resumed dataset with {dataset.num_episodes} existing episodes")
|
||||||
|
else:
|
||||||
|
print(f"Creating new dataset: {REPO_ID}")
|
||||||
|
# Sanity check dataset name
|
||||||
|
sanity_check_dataset_name(REPO_ID, None)
|
||||||
|
|
||||||
|
# Create new dataset
|
||||||
|
dataset = LeRobotDataset.create(
|
||||||
|
repo_id=REPO_ID,
|
||||||
|
fps=FPS,
|
||||||
|
features=dataset_features,
|
||||||
|
robot_type=robot.name,
|
||||||
|
use_videos=True,
|
||||||
|
image_writer_threads=4 * len(robot.cameras), # 4 threads per camera
|
||||||
|
)
|
||||||
|
|
||||||
|
# Initialize the keyboard listener and rerun visualization
|
||||||
|
_, events = init_keyboard_listener()
|
||||||
|
_init_rerun(session_name="aloha_recording")
|
||||||
|
|
||||||
|
# Connect the robot and teleoperator
|
||||||
|
robot.connect()
|
||||||
|
teleop.connect()
|
||||||
|
|
||||||
|
episode_idx = 0
|
||||||
|
total_episodes_to_record = NUM_EPISODES
|
||||||
|
existing_episodes = dataset.num_episodes if RESUME else 0
|
||||||
|
|
||||||
|
while episode_idx < NUM_EPISODES and not events["stop_recording"]:
|
||||||
|
current_episode = existing_episodes + episode_idx + 1
|
||||||
|
log_say(f"Recording episode {current_episode} (batch: {episode_idx + 1}/{NUM_EPISODES})")
|
||||||
|
|
||||||
|
record_loop(
|
||||||
|
robot=robot,
|
||||||
|
events=events,
|
||||||
|
fps=FPS,
|
||||||
|
teleop=teleop,
|
||||||
|
dataset=dataset,
|
||||||
|
control_time_s=EPISODE_TIME_SEC,
|
||||||
|
single_task=TASK_DESCRIPTION,
|
||||||
|
display_data=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
# Reset the environment if not stopping or re-recording
|
||||||
|
if not events["stop_recording"] and (episode_idx < NUM_EPISODES - 1 or events["rerecord_episode"]):
|
||||||
|
log_say("Reset the environment")
|
||||||
|
record_loop(
|
||||||
|
robot=robot,
|
||||||
|
events=events,
|
||||||
|
fps=FPS,
|
||||||
|
teleop=teleop,
|
||||||
|
control_time_s=RESET_TIME_SEC,
|
||||||
|
single_task=TASK_DESCRIPTION,
|
||||||
|
display_data=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
if events["rerecord_episode"]:
|
||||||
|
log_say("Re-recording episode")
|
||||||
|
events["rerecord_episode"] = False
|
||||||
|
events["exit_early"] = False
|
||||||
|
dataset.clear_episode_buffer()
|
||||||
|
continue
|
||||||
|
|
||||||
|
dataset.save_episode()
|
||||||
|
episode_idx += 1
|
||||||
|
|
||||||
|
# Clean up
|
||||||
|
log_say("Stop recording")
|
||||||
|
robot.disconnect()
|
||||||
|
teleop.disconnect()
|
||||||
|
|
||||||
|
# Summary
|
||||||
|
final_episodes = dataset.num_episodes
|
||||||
|
log_say(f"Dataset now contains {final_episodes} episodes total")
|
||||||
|
|
||||||
|
# Push to hub
|
||||||
|
dataset.push_to_hub()
|
||||||
|
log_say(f"Dataset '{REPO_ID}' pushed to HuggingFace Hub")
|
||||||
93
examples/aloha_teleop.py
Normal file
93
examples/aloha_teleop.py
Normal file
@@ -0,0 +1,93 @@
|
|||||||
|
import time
|
||||||
|
|
||||||
|
from lerobot.cameras.opencv.configuration_opencv import OpenCVCameraConfig
|
||||||
|
from lerobot.robots.viperx import ViperX, ViperXConfig
|
||||||
|
from lerobot.teleoperators.widowx import WidowX, WidowXConfig
|
||||||
|
from lerobot.utils.visualization_utils import _init_rerun, log_rerun_data
|
||||||
|
|
||||||
|
camera_config = {
|
||||||
|
"front": OpenCVCameraConfig(index_or_path=0, width=640, height=480, fps=30),
|
||||||
|
"wrist_right": OpenCVCameraConfig(index_or_path=1, width=640, height=480, fps=30),
|
||||||
|
"wrist_left": OpenCVCameraConfig(index_or_path=2, width=640, height=480, fps=30),
|
||||||
|
}
|
||||||
|
|
||||||
|
config_follower_right = ViperXConfig(
|
||||||
|
port="/dev/tty.usbserial-FT891KBG",
|
||||||
|
id="viperx_right",
|
||||||
|
max_relative_target=10.0, # increased from default 5.0 to 10.0
|
||||||
|
use_degrees=True,
|
||||||
|
cameras=camera_config,
|
||||||
|
)
|
||||||
|
|
||||||
|
config_leader_right = WidowXConfig(
|
||||||
|
port="/dev/tty.usbserial-FT89FM77",
|
||||||
|
id="widowx_right",
|
||||||
|
gripper_motor="xc430-w150",
|
||||||
|
use_degrees=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
config_follower_left = ViperXConfig(
|
||||||
|
port="/dev/tty.usbserial-FT89FM09",
|
||||||
|
id="viperx_left",
|
||||||
|
max_relative_target=10.0, # increased from default 5.0 to 10.0
|
||||||
|
use_degrees=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
config_leader_left = WidowXConfig(
|
||||||
|
port="/dev/tty.usbserial-FT891KPN",
|
||||||
|
id="widowx_left",
|
||||||
|
gripper_motor="xl430-w250",
|
||||||
|
use_degrees=True,
|
||||||
|
)
|
||||||
|
|
||||||
|
_init_rerun(session_name="teleop")
|
||||||
|
|
||||||
|
follower_right = ViperX(config_follower_right)
|
||||||
|
follower_right.connect()
|
||||||
|
|
||||||
|
leader_right = WidowX(config_leader_right)
|
||||||
|
leader_right.connect()
|
||||||
|
|
||||||
|
follower_left = ViperX(config_follower_left)
|
||||||
|
follower_left.connect()
|
||||||
|
|
||||||
|
leader_left = WidowX(config_leader_left)
|
||||||
|
leader_left.connect()
|
||||||
|
|
||||||
|
|
||||||
|
while True:
|
||||||
|
act_right = leader_right.get_action()
|
||||||
|
obs_right = follower_right.get_observation()
|
||||||
|
|
||||||
|
act_left = leader_left.get_action()
|
||||||
|
obs_left = follower_left.get_observation()
|
||||||
|
|
||||||
|
print("=" * 60)
|
||||||
|
print("ACTION (Leader Right):")
|
||||||
|
for key, value in act_right.items():
|
||||||
|
if key.endswith(".pos"):
|
||||||
|
print(f" {key:20}: {value:8.3f}")
|
||||||
|
|
||||||
|
print("\nOBSERVATION (Follower Right):")
|
||||||
|
for key, value in obs_right.items():
|
||||||
|
if key.endswith(".pos"):
|
||||||
|
print(f" {key:20}: {value:8.3f}")
|
||||||
|
|
||||||
|
print("=" * 60)
|
||||||
|
print("ACTION (Leader Left):")
|
||||||
|
for key, value in act_left.items():
|
||||||
|
if key.endswith(".pos"):
|
||||||
|
print(f" {key:20}: {value:8.3f}")
|
||||||
|
|
||||||
|
print("\nOBSERVATION (Follower Left):")
|
||||||
|
for key, value in obs_left.items():
|
||||||
|
if key.endswith(".pos"):
|
||||||
|
print(f" {key:20}: {value:8.3f}")
|
||||||
|
print("=" * 60)
|
||||||
|
|
||||||
|
log_rerun_data({**obs_right, **obs_left}, {**act_right, **act_left})
|
||||||
|
|
||||||
|
follower_right.send_action(act_right)
|
||||||
|
follower_left.send_action(act_left)
|
||||||
|
|
||||||
|
time.sleep(0.02)
|
||||||
@@ -106,6 +106,7 @@ dynamixel = ["dynamixel-sdk>=3.7.31"]
|
|||||||
gamepad = ["lerobot[pygame-dep]", "hidapi>=0.14.0"]
|
gamepad = ["lerobot[pygame-dep]", "hidapi>=0.14.0"]
|
||||||
hopejr = ["lerobot[feetech]", "lerobot[pygame-dep]"]
|
hopejr = ["lerobot[feetech]", "lerobot[pygame-dep]"]
|
||||||
lekiwi = ["lerobot[feetech]", "pyzmq>=26.2.1"]
|
lekiwi = ["lerobot[feetech]", "pyzmq>=26.2.1"]
|
||||||
|
reachy2 = ["reachy2_sdk>=1.0.14"]
|
||||||
kinematics = ["lerobot[placo-dep]"]
|
kinematics = ["lerobot[placo-dep]"]
|
||||||
intelrealsense = [
|
intelrealsense = [
|
||||||
"pyrealsense2>=2.55.1.6486 ; sys_platform != 'darwin'",
|
"pyrealsense2>=2.55.1.6486 ; sys_platform != 'darwin'",
|
||||||
@@ -141,6 +142,7 @@ all = [
|
|||||||
"lerobot[gamepad]",
|
"lerobot[gamepad]",
|
||||||
"lerobot[hopejr]",
|
"lerobot[hopejr]",
|
||||||
"lerobot[lekiwi]",
|
"lerobot[lekiwi]",
|
||||||
|
"lerobot[reachy2]",
|
||||||
"lerobot[kinematics]",
|
"lerobot[kinematics]",
|
||||||
"lerobot[intelrealsense]",
|
"lerobot[intelrealsense]",
|
||||||
"lerobot[pi0]",
|
"lerobot[pi0]",
|
||||||
|
|||||||
16
src/lerobot/cameras/reachy2_camera/__init__.py
Normal file
16
src/lerobot/cameras/reachy2_camera/__init__.py
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
# 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 .configuration_reachy2_camera import Reachy2CameraConfig
|
||||||
|
from .reachy2_camera import Reachy2Camera
|
||||||
@@ -0,0 +1,78 @@
|
|||||||
|
# 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
|
||||||
|
|
||||||
|
from ..configs import CameraConfig, ColorMode
|
||||||
|
|
||||||
|
|
||||||
|
@CameraConfig.register_subclass("reachy2_camera")
|
||||||
|
@dataclass
|
||||||
|
class Reachy2CameraConfig(CameraConfig):
|
||||||
|
"""Configuration class for Reachy 2 camera devices.
|
||||||
|
|
||||||
|
This class provides configuration options for Reachy 2 cameras,
|
||||||
|
supporting both the teleop and depth cameras. It includes settings
|
||||||
|
for resolution, frame rate, color mode, and the selection of the cameras.
|
||||||
|
|
||||||
|
Example configurations:
|
||||||
|
```python
|
||||||
|
# Basic configurations
|
||||||
|
Reachy2CameraConfig(
|
||||||
|
name="teleop",
|
||||||
|
image_type="left",
|
||||||
|
ip_address="192.168.0.200", # IP address of the robot
|
||||||
|
fps=15,
|
||||||
|
width=640,
|
||||||
|
height=480,
|
||||||
|
color_mode=ColorMode.RGB,
|
||||||
|
) # Left teleop camera, 640x480 @ 15FPS
|
||||||
|
```
|
||||||
|
|
||||||
|
Attributes:
|
||||||
|
name: Name of the camera device. Can be "teleop" or "depth".
|
||||||
|
image_type: Type of image stream. For "teleop" camera, can be "left" or "right".
|
||||||
|
For "depth" camera, can be "rgb" or "depth". (depth is not supported yet)
|
||||||
|
fps: Requested frames per second for the color stream.
|
||||||
|
width: Requested frame width in pixels for the color stream.
|
||||||
|
height: Requested frame height in pixels for the color stream.
|
||||||
|
color_mode: Color mode for image output (RGB or BGR). Defaults to RGB.
|
||||||
|
ip_address: IP address of the robot. Defaults to "localhost".
|
||||||
|
port: Port number for the camera server. Defaults to 50065.
|
||||||
|
|
||||||
|
Note:
|
||||||
|
- Only 3-channel color output (RGB/BGR) is currently supported.
|
||||||
|
"""
|
||||||
|
|
||||||
|
name: str
|
||||||
|
image_type: str
|
||||||
|
color_mode: ColorMode = ColorMode.RGB
|
||||||
|
ip_address: str | None = "localhost"
|
||||||
|
port: int = 50065
|
||||||
|
# use_depth: bool = False
|
||||||
|
|
||||||
|
def __post_init__(self):
|
||||||
|
if self.name not in ["teleop", "depth"]:
|
||||||
|
raise ValueError(f"`name` is expected to be 'teleop' or 'depth', but {self.name} is provided.")
|
||||||
|
if (self.name == "teleop" and self.image_type not in ["left", "right"]) or (
|
||||||
|
self.name == "depth" and self.image_type not in ["rgb", "depth"]
|
||||||
|
):
|
||||||
|
raise ValueError(
|
||||||
|
f"`image_type` is expected to be 'left' or 'right' for teleop camera, and 'rgb' or 'depth' for depth camera, but {self.image_type} is provided."
|
||||||
|
)
|
||||||
|
|
||||||
|
if self.color_mode not in ["rgb", "bgr"]:
|
||||||
|
raise ValueError(
|
||||||
|
f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided."
|
||||||
|
)
|
||||||
288
src/lerobot/cameras/reachy2_camera/reachy2_camera.py
Normal file
288
src/lerobot/cameras/reachy2_camera/reachy2_camera.py
Normal file
@@ -0,0 +1,288 @@
|
|||||||
|
# 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.
|
||||||
|
|
||||||
|
"""
|
||||||
|
Provides the Reachy2Camera class for capturing frames from Reachy 2 cameras using Reachy 2's CameraManager.
|
||||||
|
"""
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import os
|
||||||
|
import platform
|
||||||
|
import time
|
||||||
|
from threading import Event, Lock, Thread
|
||||||
|
from typing import Any
|
||||||
|
|
||||||
|
# Fix MSMF hardware transform compatibility for Windows before importing cv2
|
||||||
|
if platform.system() == "Windows" and "OPENCV_VIDEOIO_MSMF_ENABLE_HW_TRANSFORMS" not in os.environ:
|
||||||
|
os.environ["OPENCV_VIDEOIO_MSMF_ENABLE_HW_TRANSFORMS"] = "0"
|
||||||
|
import cv2
|
||||||
|
import numpy as np
|
||||||
|
from reachy2_sdk.media.camera import CameraView
|
||||||
|
from reachy2_sdk.media.camera_manager import CameraManager
|
||||||
|
|
||||||
|
from lerobot.errors import DeviceNotConnectedError
|
||||||
|
|
||||||
|
from ..camera import Camera
|
||||||
|
from .configuration_reachy2_camera import ColorMode, Reachy2CameraConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
class Reachy2Camera(Camera):
|
||||||
|
"""
|
||||||
|
Manages Reachy 2 camera using Reachy 2 CameraManager.
|
||||||
|
|
||||||
|
This class provides a high-level interface to connect to, configure, and read
|
||||||
|
frames from Reachy 2 cameras. It supports both synchronous and asynchronous
|
||||||
|
frame reading.
|
||||||
|
|
||||||
|
An Reachy2Camera instance requires a camera name (e.g., "teleop") and an image
|
||||||
|
type (e.g., "left") to be specified in the configuration.
|
||||||
|
|
||||||
|
The camera's default settings (FPS, resolution, color mode) are used unless
|
||||||
|
overridden in the configuration.
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self, config: Reachy2CameraConfig):
|
||||||
|
"""
|
||||||
|
Initializes the Reachy2Camera instance.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
config: The configuration settings for the camera.
|
||||||
|
"""
|
||||||
|
super().__init__(config)
|
||||||
|
|
||||||
|
self.config = config
|
||||||
|
|
||||||
|
self.fps = config.fps
|
||||||
|
self.color_mode = config.color_mode
|
||||||
|
|
||||||
|
self.cam_manager: CameraManager | None = None
|
||||||
|
|
||||||
|
self.thread: Thread | None = None
|
||||||
|
self.stop_event: Event | None = None
|
||||||
|
self.frame_lock: Lock = Lock()
|
||||||
|
self.latest_frame: np.ndarray | None = None
|
||||||
|
self.new_frame_event: Event = Event()
|
||||||
|
|
||||||
|
def __str__(self) -> str:
|
||||||
|
return f"{self.__class__.__name__}({self.config.name}, {self.config.image_type})"
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
"""Checks if the camera is currently connected and opened."""
|
||||||
|
if self.config.name == "teleop":
|
||||||
|
return self.cam_manager._grpc_connected and self.cam_manager.teleop if self.cam_manager else False
|
||||||
|
elif self.config.name == "depth":
|
||||||
|
return self.cam_manager._grpc_connected and self.cam_manager.depth if self.cam_manager else False
|
||||||
|
else:
|
||||||
|
raise ValueError(f"Invalid camera name '{self.config.name}'. Expected 'teleop' or 'depth'.")
|
||||||
|
|
||||||
|
def connect(self, warmup: bool = True):
|
||||||
|
"""
|
||||||
|
Connects to the Reachy2 CameraManager as specified in the configuration.
|
||||||
|
"""
|
||||||
|
self.cam_manager = CameraManager(host=self.config.ip_address, port=self.config.port)
|
||||||
|
self.cam_manager.initialize_cameras()
|
||||||
|
|
||||||
|
logger.info(f"{self} connected.")
|
||||||
|
|
||||||
|
@staticmethod
|
||||||
|
def find_cameras(ip_address: str = "localhost", port: int = 50065) -> list[dict[str, Any]]:
|
||||||
|
"""
|
||||||
|
Detects available Reachy 2 cameras.
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
List[Dict[str, Any]]: A list of dictionaries,
|
||||||
|
where each dictionary contains 'name', 'stereo',
|
||||||
|
and the default profile properties (width, height, fps).
|
||||||
|
"""
|
||||||
|
initialized_cameras = []
|
||||||
|
camera_manager = CameraManager(host=ip_address, port=port)
|
||||||
|
|
||||||
|
for camera in [camera_manager.teleop, camera_manager.depth]:
|
||||||
|
if camera is None:
|
||||||
|
continue
|
||||||
|
|
||||||
|
height, width, _, _, _, _, _ = camera.get_parameters()
|
||||||
|
|
||||||
|
camera_info = {
|
||||||
|
"name": camera._cam_info.name,
|
||||||
|
"stereo": camera._cam_info.stereo,
|
||||||
|
"default_profile": {
|
||||||
|
"width": width,
|
||||||
|
"height": height,
|
||||||
|
"fps": 30,
|
||||||
|
},
|
||||||
|
}
|
||||||
|
initialized_cameras.append(camera_info)
|
||||||
|
|
||||||
|
camera_manager.disconnect()
|
||||||
|
return initialized_cameras
|
||||||
|
|
||||||
|
def read(self, color_mode: ColorMode | None = None) -> np.ndarray:
|
||||||
|
"""
|
||||||
|
Reads a single frame synchronously from the camera.
|
||||||
|
|
||||||
|
This is a blocking call.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
color_mode (Optional[ColorMode]): If specified, overrides the default
|
||||||
|
color mode (`self.color_mode`) for this read operation (e.g.,
|
||||||
|
request RGB even if default is BGR).
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
np.ndarray: The captured frame as a NumPy array in the format
|
||||||
|
(height, width, channels), using the specified or default
|
||||||
|
color mode and applying any configured rotation.
|
||||||
|
"""
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
start_time = time.perf_counter()
|
||||||
|
|
||||||
|
frame = None
|
||||||
|
|
||||||
|
if self.cam_manager is None:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
else:
|
||||||
|
if self.config.name == "teleop" and hasattr(self.cam_manager, "teleop"):
|
||||||
|
if self.config.image_type == "left":
|
||||||
|
frame = self.cam_manager.teleop.get_frame(CameraView.LEFT, size=(640, 480))[0]
|
||||||
|
elif self.config.image_type == "right":
|
||||||
|
frame = self.cam_manager.teleop.get_frame(CameraView.RIGHT, size=(640, 480))[0]
|
||||||
|
elif self.config.name == "depth" and hasattr(self.cam_manager, "depth"):
|
||||||
|
if self.config.image_type == "depth":
|
||||||
|
frame = self.cam_manager.depth.get_depth_frame()[0]
|
||||||
|
elif self.config.image_type == "rgb":
|
||||||
|
frame = self.cam_manager.depth.get_frame(size=(640, 480))[0]
|
||||||
|
|
||||||
|
if frame is None:
|
||||||
|
return np.empty((0, 0, 3), dtype=np.uint8)
|
||||||
|
|
||||||
|
if self.config.color_mode == "rgb":
|
||||||
|
frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)
|
||||||
|
|
||||||
|
read_duration_ms = (time.perf_counter() - start_time) * 1e3
|
||||||
|
logger.debug(f"{self} read took: {read_duration_ms:.1f}ms")
|
||||||
|
|
||||||
|
return frame
|
||||||
|
|
||||||
|
def _read_loop(self):
|
||||||
|
"""
|
||||||
|
Internal loop run by the background thread for asynchronous reading.
|
||||||
|
|
||||||
|
On each iteration:
|
||||||
|
1. Reads a color frame
|
||||||
|
2. Stores result in latest_frame (thread-safe)
|
||||||
|
3. Sets new_frame_event to notify listeners
|
||||||
|
|
||||||
|
Stops on DeviceNotConnectedError, logs other errors and continues.
|
||||||
|
"""
|
||||||
|
while not self.stop_event.is_set():
|
||||||
|
try:
|
||||||
|
color_image = self.read()
|
||||||
|
|
||||||
|
with self.frame_lock:
|
||||||
|
self.latest_frame = color_image
|
||||||
|
self.new_frame_event.set()
|
||||||
|
|
||||||
|
except DeviceNotConnectedError:
|
||||||
|
break
|
||||||
|
except Exception as e:
|
||||||
|
logger.warning(f"Error reading frame in background thread for {self}: {e}")
|
||||||
|
|
||||||
|
def _start_read_thread(self) -> None:
|
||||||
|
"""Starts or restarts the background read thread if it's not running."""
|
||||||
|
if self.thread is not None and self.thread.is_alive():
|
||||||
|
self.thread.join(timeout=0.1)
|
||||||
|
if self.stop_event is not None:
|
||||||
|
self.stop_event.set()
|
||||||
|
|
||||||
|
self.stop_event = Event()
|
||||||
|
self.thread = Thread(target=self._read_loop, args=(), name=f"{self}_read_loop")
|
||||||
|
self.thread.daemon = True
|
||||||
|
self.thread.start()
|
||||||
|
|
||||||
|
def _stop_read_thread(self) -> None:
|
||||||
|
"""Signals the background read thread to stop and waits for it to join."""
|
||||||
|
if self.stop_event is not None:
|
||||||
|
self.stop_event.set()
|
||||||
|
|
||||||
|
if self.thread is not None and self.thread.is_alive():
|
||||||
|
self.thread.join(timeout=2.0)
|
||||||
|
|
||||||
|
self.thread = None
|
||||||
|
self.stop_event = None
|
||||||
|
|
||||||
|
def async_read(self, timeout_ms: float = 200) -> np.ndarray:
|
||||||
|
"""
|
||||||
|
Reads the latest available frame asynchronously.
|
||||||
|
|
||||||
|
This method retrieves the most recent frame captured by the background
|
||||||
|
read thread. It does not block waiting for the camera hardware directly,
|
||||||
|
but may wait up to timeout_ms for the background thread to provide a frame.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
timeout_ms (float): Maximum time in milliseconds to wait for a frame
|
||||||
|
to become available. Defaults to 200ms (0.2 seconds).
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
np.ndarray: The latest captured frame as a NumPy array in the format
|
||||||
|
(height, width, channels), processed according to configuration.
|
||||||
|
|
||||||
|
Raises:
|
||||||
|
DeviceNotConnectedError: If the camera is not connected.
|
||||||
|
TimeoutError: If no frame becomes available within the specified timeout.
|
||||||
|
RuntimeError: If an unexpected error occurs.
|
||||||
|
"""
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
if self.thread is None or not self.thread.is_alive():
|
||||||
|
self._start_read_thread()
|
||||||
|
|
||||||
|
if not self.new_frame_event.wait(timeout=timeout_ms / 1000.0):
|
||||||
|
thread_alive = self.thread is not None and self.thread.is_alive()
|
||||||
|
raise TimeoutError(
|
||||||
|
f"Timed out waiting for frame from camera {self} after {timeout_ms} ms. "
|
||||||
|
f"Read thread alive: {thread_alive}."
|
||||||
|
)
|
||||||
|
|
||||||
|
with self.frame_lock:
|
||||||
|
frame = self.latest_frame
|
||||||
|
self.new_frame_event.clear()
|
||||||
|
|
||||||
|
if frame is None:
|
||||||
|
raise RuntimeError(f"Internal error: Event set but no frame available for {self}.")
|
||||||
|
|
||||||
|
return frame
|
||||||
|
|
||||||
|
def disconnect(self):
|
||||||
|
"""
|
||||||
|
Stops the background read thread (if running).
|
||||||
|
|
||||||
|
Raises:
|
||||||
|
DeviceNotConnectedError: If the camera is already disconnected.
|
||||||
|
"""
|
||||||
|
if not self.is_connected and self.thread is None:
|
||||||
|
raise DeviceNotConnectedError(f"{self} not connected.")
|
||||||
|
|
||||||
|
if self.thread is not None:
|
||||||
|
self._stop_read_thread()
|
||||||
|
|
||||||
|
if self.cam_manager is not None:
|
||||||
|
self.cam_manager.disconnect()
|
||||||
|
|
||||||
|
logger.info(f"{self} disconnected.")
|
||||||
@@ -37,8 +37,14 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> dict[s
|
|||||||
from .realsense.camera_realsense import RealSenseCamera
|
from .realsense.camera_realsense import RealSenseCamera
|
||||||
|
|
||||||
cameras[key] = RealSenseCamera(cfg)
|
cameras[key] = RealSenseCamera(cfg)
|
||||||
|
|
||||||
|
elif cfg.type == "reachy2_camera":
|
||||||
|
from .reachy2_camera.reachy2_camera import Reachy2Camera
|
||||||
|
|
||||||
|
cameras[key] = Reachy2Camera(cfg)
|
||||||
|
|
||||||
else:
|
else:
|
||||||
raise ValueError(f"The motor type '{cfg.type}' is not valid.")
|
raise ValueError(f"The camera type '{cfg.type}' is not valid.")
|
||||||
|
|
||||||
return cameras
|
return cameras
|
||||||
|
|
||||||
|
|||||||
@@ -209,7 +209,14 @@ def record_loop(
|
|||||||
(
|
(
|
||||||
t
|
t
|
||||||
for t in teleop
|
for t in teleop
|
||||||
if isinstance(t, (so100_leader.SO100Leader, so101_leader.SO101Leader, koch_leader.KochLeader))
|
if isinstance(
|
||||||
|
t,
|
||||||
|
(
|
||||||
|
so100_leader.SO100Leader,
|
||||||
|
so101_leader.SO101Leader,
|
||||||
|
koch_leader.KochLeader,
|
||||||
|
),
|
||||||
|
)
|
||||||
),
|
),
|
||||||
None,
|
None,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -55,6 +55,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
hope_jr,
|
hope_jr,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
reachy2,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
|
|||||||
4
src/lerobot/robots/aloha/__init__.py
Normal file
4
src/lerobot/robots/aloha/__init__.py
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
from .aloha import Aloha
|
||||||
|
from .config_aloha import AlohaConfig
|
||||||
|
|
||||||
|
__all__ = ["Aloha", "AlohaConfig"]
|
||||||
161
src/lerobot/robots/aloha/aloha.py
Normal file
161
src/lerobot/robots/aloha/aloha.py
Normal file
@@ -0,0 +1,161 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import time
|
||||||
|
from functools import cached_property
|
||||||
|
from typing import Any
|
||||||
|
|
||||||
|
from lerobot.cameras.utils import make_cameras_from_configs
|
||||||
|
from lerobot.robots.viperx import ViperX
|
||||||
|
from lerobot.robots.viperx.config_viperx import ViperXConfig
|
||||||
|
|
||||||
|
from ..robot import Robot
|
||||||
|
from .config_aloha import AlohaConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
class Aloha(Robot):
|
||||||
|
"""
|
||||||
|
ALOHA Bimanual Robot System using dual ViperX follower arms.
|
||||||
|
Based on the ALOHA (A Low-cost Open-source Hardware System for Bimanual Teleoperation) design.
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = AlohaConfig
|
||||||
|
name = "aloha"
|
||||||
|
|
||||||
|
def __init__(self, config: AlohaConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
self.config = config
|
||||||
|
|
||||||
|
left_arm_config = ViperXConfig(
|
||||||
|
id=f"{config.id}_left" if config.id else None,
|
||||||
|
calibration_dir=config.calibration_dir,
|
||||||
|
port=config.left_arm_port,
|
||||||
|
max_relative_target=config.left_arm_max_relative_target,
|
||||||
|
use_degrees=config.left_arm_use_degrees,
|
||||||
|
cameras={},
|
||||||
|
)
|
||||||
|
|
||||||
|
right_arm_config = ViperXConfig(
|
||||||
|
id=f"{config.id}_right" if config.id else None,
|
||||||
|
calibration_dir=config.calibration_dir,
|
||||||
|
port=config.right_arm_port,
|
||||||
|
max_relative_target=config.right_arm_max_relative_target,
|
||||||
|
use_degrees=config.right_arm_use_degrees,
|
||||||
|
cameras={},
|
||||||
|
)
|
||||||
|
|
||||||
|
self.left_arm = ViperX(left_arm_config)
|
||||||
|
self.right_arm = ViperX(right_arm_config)
|
||||||
|
self.cameras = make_cameras_from_configs(config.cameras)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def _motors_ft(self) -> dict[str, type]:
|
||||||
|
return {f"left_{motor}.pos": float for motor in self.left_arm.bus.motors} | {
|
||||||
|
f"right_{motor}.pos": float for motor in self.right_arm.bus.motors
|
||||||
|
}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def _cameras_ft(self) -> dict[str, tuple]:
|
||||||
|
return {
|
||||||
|
cam: (self.config.cameras[cam].height, self.config.cameras[cam].width, 3) for cam in self.cameras
|
||||||
|
}
|
||||||
|
|
||||||
|
@cached_property
|
||||||
|
def observation_features(self) -> dict[str, type | tuple]:
|
||||||
|
return {**self._motors_ft, **self._cameras_ft}
|
||||||
|
|
||||||
|
@cached_property
|
||||||
|
def action_features(self) -> dict[str, type]:
|
||||||
|
return self._motors_ft
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
return (
|
||||||
|
self.left_arm.bus.is_connected
|
||||||
|
and self.right_arm.bus.is_connected
|
||||||
|
and all(cam.is_connected for cam in self.cameras.values())
|
||||||
|
)
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = True) -> None:
|
||||||
|
self.left_arm.connect(calibrate)
|
||||||
|
self.right_arm.connect(calibrate)
|
||||||
|
|
||||||
|
for cam in self.cameras.values():
|
||||||
|
cam.connect()
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_calibrated(self) -> bool:
|
||||||
|
return self.left_arm.is_calibrated and self.right_arm.is_calibrated
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
self.left_arm.calibrate()
|
||||||
|
self.right_arm.calibrate()
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
self.left_arm.configure()
|
||||||
|
self.right_arm.configure()
|
||||||
|
|
||||||
|
def setup_motors(self) -> None:
|
||||||
|
self.left_arm.setup_motors()
|
||||||
|
self.right_arm.setup_motors()
|
||||||
|
|
||||||
|
def get_observation(self) -> dict[str, Any]:
|
||||||
|
obs_dict = {}
|
||||||
|
|
||||||
|
# Add "left_" prefix
|
||||||
|
left_obs = self.left_arm.get_observation()
|
||||||
|
obs_dict.update({f"left_{key}": value for key, value in left_obs.items()})
|
||||||
|
|
||||||
|
# Add "right_" prefix
|
||||||
|
right_obs = self.right_arm.get_observation()
|
||||||
|
obs_dict.update({f"right_{key}": value for key, value in right_obs.items()})
|
||||||
|
|
||||||
|
for cam_key, cam in self.cameras.items():
|
||||||
|
start = time.perf_counter()
|
||||||
|
obs_dict[cam_key] = cam.async_read()
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
|
||||||
|
|
||||||
|
return obs_dict
|
||||||
|
|
||||||
|
def send_action(self, action: dict[str, Any]) -> dict[str, Any]:
|
||||||
|
# Remove "left_" prefix
|
||||||
|
left_action = {
|
||||||
|
key.removeprefix("left_"): value for key, value in action.items() if key.startswith("left_")
|
||||||
|
}
|
||||||
|
# Remove "right_" prefix
|
||||||
|
right_action = {
|
||||||
|
key.removeprefix("right_"): value for key, value in action.items() if key.startswith("right_")
|
||||||
|
}
|
||||||
|
|
||||||
|
send_action_left = self.left_arm.send_action(left_action)
|
||||||
|
send_action_right = self.right_arm.send_action(right_action)
|
||||||
|
|
||||||
|
# Add prefixes back
|
||||||
|
prefixed_send_action_left = {f"left_{key}": value for key, value in send_action_left.items()}
|
||||||
|
prefixed_send_action_right = {f"right_{key}": value for key, value in send_action_right.items()}
|
||||||
|
|
||||||
|
return {**prefixed_send_action_left, **prefixed_send_action_right}
|
||||||
|
|
||||||
|
def disconnect(self):
|
||||||
|
self.left_arm.disconnect()
|
||||||
|
self.right_arm.disconnect()
|
||||||
|
|
||||||
|
for cam in self.cameras.values():
|
||||||
|
cam.disconnect()
|
||||||
39
src/lerobot/robots/aloha/config_aloha.py
Normal file
39
src/lerobot/robots/aloha/config_aloha.py
Normal file
@@ -0,0 +1,39 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.cameras import CameraConfig
|
||||||
|
|
||||||
|
from ..config import RobotConfig
|
||||||
|
|
||||||
|
|
||||||
|
@RobotConfig.register_subclass("aloha")
|
||||||
|
@dataclass
|
||||||
|
class AlohaConfig(RobotConfig):
|
||||||
|
left_arm_port: str
|
||||||
|
right_arm_port: str
|
||||||
|
|
||||||
|
# Optional parameters for left arm (ViperX)
|
||||||
|
left_arm_max_relative_target: float | dict[str, float] = 20.0
|
||||||
|
left_arm_use_degrees: bool = True
|
||||||
|
|
||||||
|
# Optional parameters for right arm (ViperX)
|
||||||
|
right_arm_max_relative_target: float | dict[str, float] = 20.0
|
||||||
|
right_arm_use_degrees: bool = True
|
||||||
|
|
||||||
|
# cameras (shared between both arms)
|
||||||
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
@@ -29,10 +29,10 @@ class BiSO100FollowerConfig(RobotConfig):
|
|||||||
|
|
||||||
# Optional
|
# Optional
|
||||||
left_arm_disable_torque_on_disconnect: bool = True
|
left_arm_disable_torque_on_disconnect: bool = True
|
||||||
left_arm_max_relative_target: int | None = None
|
left_arm_max_relative_target: float | dict[str, float] | None = None
|
||||||
left_arm_use_degrees: bool = False
|
left_arm_use_degrees: bool = False
|
||||||
right_arm_disable_torque_on_disconnect: bool = True
|
right_arm_disable_torque_on_disconnect: bool = True
|
||||||
right_arm_max_relative_target: int | None = None
|
right_arm_max_relative_target: float | dict[str, float] | None = None
|
||||||
right_arm_use_degrees: bool = False
|
right_arm_use_degrees: bool = False
|
||||||
|
|
||||||
# cameras (shared between both arms)
|
# cameras (shared between both arms)
|
||||||
|
|||||||
@@ -44,8 +44,8 @@ class HopeJrArmConfig(RobotConfig):
|
|||||||
disable_torque_on_disconnect: bool = True
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
max_relative_target: int | None = None
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|||||||
@@ -28,9 +28,9 @@ class KochFollowerConfig(RobotConfig):
|
|||||||
disable_torque_on_disconnect: bool = True
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
max_relative_target: int | None = None
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
# cameras
|
# cameras
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|||||||
@@ -110,6 +110,7 @@ class KochFollower(Robot):
|
|||||||
return self.bus.is_calibrated
|
return self.bus.is_calibrated
|
||||||
|
|
||||||
def calibrate(self) -> None:
|
def calibrate(self) -> None:
|
||||||
|
self.bus.disable_torque()
|
||||||
if self.calibration:
|
if self.calibration:
|
||||||
# Calibration file exists, ask user whether to use it or run new calibration
|
# Calibration file exists, ask user whether to use it or run new calibration
|
||||||
user_input = input(
|
user_input = input(
|
||||||
@@ -120,7 +121,6 @@ class KochFollower(Robot):
|
|||||||
self.bus.write_calibration(self.calibration)
|
self.bus.write_calibration(self.calibration)
|
||||||
return
|
return
|
||||||
logger.info(f"\nRunning calibration of {self}")
|
logger.info(f"\nRunning calibration of {self}")
|
||||||
self.bus.disable_torque()
|
|
||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
|||||||
@@ -39,9 +39,9 @@ class LeKiwiConfig(RobotConfig):
|
|||||||
disable_torque_on_disconnect: bool = True
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
max_relative_target: int | None = None
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=lekiwi_cameras_config)
|
cameras: dict[str, CameraConfig] = field(default_factory=lekiwi_cameras_config)
|
||||||
|
|
||||||
|
|||||||
25
src/lerobot/robots/reachy2/__init__.py
Normal file
25
src/lerobot/robots/reachy2/__init__.py
Normal file
@@ -0,0 +1,25 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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 .configuration_reachy2 import Reachy2RobotConfig
|
||||||
|
from .robot_reachy2 import (
|
||||||
|
REACHY2_ANTENNAS_JOINTS,
|
||||||
|
REACHY2_L_ARM_JOINTS,
|
||||||
|
REACHY2_NECK_JOINTS,
|
||||||
|
REACHY2_R_ARM_JOINTS,
|
||||||
|
REACHY2_VEL,
|
||||||
|
Reachy2Robot,
|
||||||
|
)
|
||||||
107
src/lerobot/robots/reachy2/configuration_reachy2.py
Normal file
107
src/lerobot/robots/reachy2/configuration_reachy2.py
Normal file
@@ -0,0 +1,107 @@
|
|||||||
|
# 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.cameras import CameraConfig
|
||||||
|
from lerobot.cameras.configs import ColorMode
|
||||||
|
from lerobot.cameras.reachy2_camera import Reachy2CameraConfig
|
||||||
|
|
||||||
|
from ..config import RobotConfig
|
||||||
|
|
||||||
|
|
||||||
|
@RobotConfig.register_subclass("reachy2")
|
||||||
|
@dataclass
|
||||||
|
class Reachy2RobotConfig(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.
|
||||||
|
max_relative_target: float | None = None
|
||||||
|
|
||||||
|
# IP address of the Reachy 2 robot
|
||||||
|
ip_address: str | None = "localhost"
|
||||||
|
|
||||||
|
# If True, turn_off_smoothly() will be sent to the robot before disconnecting.
|
||||||
|
disable_torque_on_disconnect: bool = False
|
||||||
|
|
||||||
|
# Tag for external commands control
|
||||||
|
# Set to True if you use an external commands system to control the robot,
|
||||||
|
# such as the official teleoperation application: https://github.com/pollen-robotics/Reachy2Teleoperation
|
||||||
|
# If True, robot.send_action() will not send commands to the robot.
|
||||||
|
use_external_commands: bool = False
|
||||||
|
|
||||||
|
# Robot parts
|
||||||
|
# Set to False to not add the corresponding joints part to the robot list of joints.
|
||||||
|
# By default, all parts are set to True.
|
||||||
|
with_mobile_base: bool = True
|
||||||
|
with_l_arm: bool = True
|
||||||
|
with_r_arm: bool = True
|
||||||
|
with_neck: bool = True
|
||||||
|
with_antennas: bool = True
|
||||||
|
|
||||||
|
# Robot cameras
|
||||||
|
# Set to True if you want to use the corresponding cameras in the observations.
|
||||||
|
# By default, only the teleop cameras are used.
|
||||||
|
with_left_teleop_camera: bool = True
|
||||||
|
with_right_teleop_camera: bool = True
|
||||||
|
with_torso_camera: bool = False
|
||||||
|
|
||||||
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|
||||||
|
def __post_init__(self) -> None:
|
||||||
|
# Add cameras with same ip_address as the robot
|
||||||
|
if self.with_left_teleop_camera:
|
||||||
|
self.cameras["teleop_left"] = Reachy2CameraConfig(
|
||||||
|
name="teleop",
|
||||||
|
image_type="left",
|
||||||
|
ip_address=self.ip_address,
|
||||||
|
fps=15,
|
||||||
|
width=640,
|
||||||
|
height=480,
|
||||||
|
color_mode=ColorMode.RGB,
|
||||||
|
)
|
||||||
|
if self.with_right_teleop_camera:
|
||||||
|
self.cameras["teleop_right"] = Reachy2CameraConfig(
|
||||||
|
name="teleop",
|
||||||
|
image_type="right",
|
||||||
|
ip_address=self.ip_address,
|
||||||
|
fps=15,
|
||||||
|
width=640,
|
||||||
|
height=480,
|
||||||
|
color_mode=ColorMode.RGB,
|
||||||
|
)
|
||||||
|
if self.with_torso_camera:
|
||||||
|
self.cameras["torso_rgb"] = Reachy2CameraConfig(
|
||||||
|
name="depth",
|
||||||
|
image_type="rgb",
|
||||||
|
ip_address=self.ip_address,
|
||||||
|
fps=15,
|
||||||
|
width=640,
|
||||||
|
height=480,
|
||||||
|
color_mode=ColorMode.RGB,
|
||||||
|
)
|
||||||
|
|
||||||
|
super().__post_init__()
|
||||||
|
|
||||||
|
if not (
|
||||||
|
self.with_mobile_base
|
||||||
|
or self.with_l_arm
|
||||||
|
or self.with_r_arm
|
||||||
|
or self.with_neck
|
||||||
|
or self.with_antennas
|
||||||
|
):
|
||||||
|
raise ValueError(
|
||||||
|
"No Reachy2Robot part used.\n"
|
||||||
|
"At least one part of the robot must be set to True "
|
||||||
|
"(with_mobile_base, with_l_arm, with_r_arm, with_neck, with_antennas)"
|
||||||
|
)
|
||||||
230
src/lerobot/robots/reachy2/robot_reachy2.py
Normal file
230
src/lerobot/robots/reachy2/robot_reachy2.py
Normal file
@@ -0,0 +1,230 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
import time
|
||||||
|
from typing import Any
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
from reachy2_sdk import ReachySDK
|
||||||
|
|
||||||
|
from lerobot.cameras.utils import make_cameras_from_configs
|
||||||
|
|
||||||
|
from ..robot import Robot
|
||||||
|
from ..utils import ensure_safe_goal_position
|
||||||
|
from .configuration_reachy2 import Reachy2RobotConfig
|
||||||
|
|
||||||
|
# {lerobot_keys: reachy2_sdk_keys}
|
||||||
|
REACHY2_NECK_JOINTS = {
|
||||||
|
"neck_yaw.pos": "head.neck.yaw",
|
||||||
|
"neck_pitch.pos": "head.neck.pitch",
|
||||||
|
"neck_roll.pos": "head.neck.roll",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_ANTENNAS_JOINTS = {
|
||||||
|
"l_antenna.pos": "head.l_antenna",
|
||||||
|
"r_antenna.pos": "head.r_antenna",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_R_ARM_JOINTS = {
|
||||||
|
"r_shoulder_pitch.pos": "r_arm.shoulder.pitch",
|
||||||
|
"r_shoulder_roll.pos": "r_arm.shoulder.roll",
|
||||||
|
"r_elbow_yaw.pos": "r_arm.elbow.yaw",
|
||||||
|
"r_elbow_pitch.pos": "r_arm.elbow.pitch",
|
||||||
|
"r_wrist_roll.pos": "r_arm.wrist.roll",
|
||||||
|
"r_wrist_pitch.pos": "r_arm.wrist.pitch",
|
||||||
|
"r_wrist_yaw.pos": "r_arm.wrist.yaw",
|
||||||
|
"r_gripper.pos": "r_arm.gripper",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_L_ARM_JOINTS = {
|
||||||
|
"l_shoulder_pitch.pos": "l_arm.shoulder.pitch",
|
||||||
|
"l_shoulder_roll.pos": "l_arm.shoulder.roll",
|
||||||
|
"l_elbow_yaw.pos": "l_arm.elbow.yaw",
|
||||||
|
"l_elbow_pitch.pos": "l_arm.elbow.pitch",
|
||||||
|
"l_wrist_roll.pos": "l_arm.wrist.roll",
|
||||||
|
"l_wrist_pitch.pos": "l_arm.wrist.pitch",
|
||||||
|
"l_wrist_yaw.pos": "l_arm.wrist.yaw",
|
||||||
|
"l_gripper.pos": "l_arm.gripper",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_VEL = {
|
||||||
|
"mobile_base.vx": "vx",
|
||||||
|
"mobile_base.vy": "vy",
|
||||||
|
"mobile_base.vtheta": "vtheta",
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
class Reachy2Robot(Robot):
|
||||||
|
"""
|
||||||
|
[Reachy 2](https://www.pollen-robotics.com/reachy/), by Pollen Robotics.
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = Reachy2RobotConfig
|
||||||
|
name = "reachy2"
|
||||||
|
|
||||||
|
def __init__(self, config: Reachy2RobotConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
|
||||||
|
self.config = config
|
||||||
|
self.robot_type = self.config.type
|
||||||
|
self.use_external_commands = self.config.use_external_commands
|
||||||
|
|
||||||
|
self.reachy: None | ReachySDK = None
|
||||||
|
self.cameras = make_cameras_from_configs(config.cameras)
|
||||||
|
|
||||||
|
self.logs: dict[str, float] = {}
|
||||||
|
|
||||||
|
self.joints_dict: dict[str, str] = self._generate_joints_dict()
|
||||||
|
|
||||||
|
@property
|
||||||
|
def observation_features(self) -> dict[str, Any]:
|
||||||
|
return {**self.motors_features, **self.camera_features}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def action_features(self) -> dict[str, type]:
|
||||||
|
return self.motors_features
|
||||||
|
|
||||||
|
@property
|
||||||
|
def camera_features(self) -> dict[str, tuple[int | None, int | None, int]]:
|
||||||
|
return {cam: (self.cameras[cam].height, self.cameras[cam].width, 3) for cam in self.cameras}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def motors_features(self) -> dict[str, type]:
|
||||||
|
if self.config.with_mobile_base:
|
||||||
|
return {
|
||||||
|
**dict.fromkeys(
|
||||||
|
self.joints_dict.keys(),
|
||||||
|
float,
|
||||||
|
),
|
||||||
|
**dict.fromkeys(
|
||||||
|
REACHY2_VEL.keys(),
|
||||||
|
float,
|
||||||
|
),
|
||||||
|
}
|
||||||
|
else:
|
||||||
|
return dict.fromkeys(self.joints_dict.keys(), float)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
return self.reachy.is_connected() if self.reachy is not None else False
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = False) -> None:
|
||||||
|
self.reachy = ReachySDK(self.config.ip_address)
|
||||||
|
if not self.is_connected:
|
||||||
|
raise ConnectionError()
|
||||||
|
|
||||||
|
for cam in self.cameras.values():
|
||||||
|
cam.connect()
|
||||||
|
|
||||||
|
self.configure()
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
if self.reachy is not None:
|
||||||
|
self.reachy.turn_on()
|
||||||
|
self.reachy.reset_default_limits()
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_calibrated(self) -> bool:
|
||||||
|
return True
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def _generate_joints_dict(self) -> dict[str, str]:
|
||||||
|
joints = {}
|
||||||
|
if self.config.with_neck:
|
||||||
|
joints.update(REACHY2_NECK_JOINTS)
|
||||||
|
if self.config.with_l_arm:
|
||||||
|
joints.update(REACHY2_L_ARM_JOINTS)
|
||||||
|
if self.config.with_r_arm:
|
||||||
|
joints.update(REACHY2_R_ARM_JOINTS)
|
||||||
|
if self.config.with_antennas:
|
||||||
|
joints.update(REACHY2_ANTENNAS_JOINTS)
|
||||||
|
return joints
|
||||||
|
|
||||||
|
def _get_state(self) -> dict[str, float]:
|
||||||
|
if self.reachy is not None:
|
||||||
|
pos_dict = {k: self.reachy.joints[v].present_position for k, v in self.joints_dict.items()}
|
||||||
|
if not self.config.with_mobile_base:
|
||||||
|
return pos_dict
|
||||||
|
vel_dict = {k: self.reachy.mobile_base.odometry[v] for k, v in REACHY2_VEL.items()}
|
||||||
|
return {**pos_dict, **vel_dict}
|
||||||
|
else:
|
||||||
|
return {}
|
||||||
|
|
||||||
|
def get_observation(self) -> dict[str, np.ndarray]:
|
||||||
|
obs_dict: dict[str, Any] = {}
|
||||||
|
|
||||||
|
# Read Reachy 2 state
|
||||||
|
before_read_t = time.perf_counter()
|
||||||
|
obs_dict.update(self._get_state())
|
||||||
|
self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
|
||||||
|
|
||||||
|
# Capture images from cameras
|
||||||
|
for cam_key, cam in self.cameras.items():
|
||||||
|
obs_dict[cam_key] = cam.async_read()
|
||||||
|
|
||||||
|
return obs_dict
|
||||||
|
|
||||||
|
def send_action(self, action: dict[str, Any]) -> dict[str, Any]:
|
||||||
|
if self.reachy is not None:
|
||||||
|
if not self.is_connected:
|
||||||
|
raise ConnectionError()
|
||||||
|
|
||||||
|
before_write_t = time.perf_counter()
|
||||||
|
|
||||||
|
vel = {}
|
||||||
|
goal_pos = {}
|
||||||
|
for key, val in action.items():
|
||||||
|
if key not in self.joints_dict:
|
||||||
|
if key not in REACHY2_VEL:
|
||||||
|
raise KeyError(f"Key '{key}' is not a valid motor key in Reachy 2.")
|
||||||
|
else:
|
||||||
|
vel[REACHY2_VEL[key]] = float(val)
|
||||||
|
else:
|
||||||
|
if not self.use_external_commands and self.config.max_relative_target is not None:
|
||||||
|
goal_pos[key] = float(val)
|
||||||
|
goal_present_pos = {
|
||||||
|
key: (
|
||||||
|
goal_pos[key],
|
||||||
|
self.reachy.joints[self.joints_dict[key]].present_position,
|
||||||
|
)
|
||||||
|
}
|
||||||
|
safe_goal_pos = ensure_safe_goal_position(
|
||||||
|
goal_present_pos, float(self.config.max_relative_target)
|
||||||
|
)
|
||||||
|
val = safe_goal_pos[key]
|
||||||
|
self.reachy.joints[self.joints_dict[key]].goal_position = float(val)
|
||||||
|
|
||||||
|
if self.config.with_mobile_base:
|
||||||
|
self.reachy.mobile_base.set_goal_speed(vel["vx"], vel["vy"], vel["vtheta"])
|
||||||
|
|
||||||
|
# We don't send the goal positions if we control Reachy 2 externally
|
||||||
|
if not self.use_external_commands:
|
||||||
|
self.reachy.send_goal_positions()
|
||||||
|
if self.config.with_mobile_base:
|
||||||
|
self.reachy.mobile_base.send_speed_command()
|
||||||
|
|
||||||
|
self.logs["write_pos_dt_s"] = time.perf_counter() - before_write_t
|
||||||
|
return action
|
||||||
|
|
||||||
|
def disconnect(self) -> None:
|
||||||
|
if self.reachy is not None:
|
||||||
|
for cam in self.cameras.values():
|
||||||
|
cam.disconnect()
|
||||||
|
if self.config.disable_torque_on_disconnect:
|
||||||
|
self.reachy.turn_off_smoothly()
|
||||||
|
self.reachy.disconnect()
|
||||||
@@ -30,9 +30,9 @@ class SO100FollowerConfig(RobotConfig):
|
|||||||
disable_torque_on_disconnect: bool = True
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
max_relative_target: int | None = None
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
# cameras
|
# cameras
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|||||||
@@ -30,9 +30,9 @@ class SO101FollowerConfig(RobotConfig):
|
|||||||
disable_torque_on_disconnect: bool = True
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
max_relative_target: int | None = None
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
# cameras
|
# cameras
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|||||||
@@ -24,11 +24,6 @@ from ..config import RobotConfig
|
|||||||
@RobotConfig.register_subclass("stretch3")
|
@RobotConfig.register_subclass("stretch3")
|
||||||
@dataclass
|
@dataclass
|
||||||
class Stretch3RobotConfig(RobotConfig):
|
class Stretch3RobotConfig(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
|
||||||
cameras: dict[str, CameraConfig] = field(
|
cameras: dict[str, CameraConfig] = field(
|
||||||
default_factory=lambda: {
|
default_factory=lambda: {
|
||||||
|
|||||||
@@ -61,6 +61,10 @@ def make_robot_from_config(config: RobotConfig) -> Robot:
|
|||||||
from .bi_so100_follower import BiSO100Follower
|
from .bi_so100_follower import BiSO100Follower
|
||||||
|
|
||||||
return BiSO100Follower(config)
|
return BiSO100Follower(config)
|
||||||
|
elif config.type == "reachy2":
|
||||||
|
from .reachy2 import Reachy2Robot
|
||||||
|
|
||||||
|
return Reachy2Robot(config)
|
||||||
elif config.type == "mock_robot":
|
elif config.type == "mock_robot":
|
||||||
from tests.mocks.mock_robot import MockRobot
|
from tests.mocks.mock_robot import MockRobot
|
||||||
|
|
||||||
@@ -70,7 +74,7 @@ def make_robot_from_config(config: RobotConfig) -> Robot:
|
|||||||
|
|
||||||
|
|
||||||
def ensure_safe_goal_position(
|
def ensure_safe_goal_position(
|
||||||
goal_present_pos: dict[str, tuple[float, float]], max_relative_target: float | dict[float]
|
goal_present_pos: dict[str, tuple[float, float]], max_relative_target: float | dict[str, float]
|
||||||
) -> dict[str, float]:
|
) -> dict[str, float]:
|
||||||
"""Caps relative action target magnitude for safety."""
|
"""Caps relative action target magnitude for safety."""
|
||||||
|
|
||||||
|
|||||||
@@ -28,18 +28,21 @@ class ViperXConfig(RobotConfig):
|
|||||||
|
|
||||||
# /!\ FOR SAFETY, READ THIS /!\
|
# /!\ FOR SAFETY, READ THIS /!\
|
||||||
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
# `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
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
# the number of motors in your follower arms.
|
# names to the max_relative_target value for that motor.
|
||||||
# For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default.
|
# For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default.
|
||||||
# When you feel more confident with teleoperation or running the policy, you can extend
|
# When you feel more confident with teleoperation or running the policy, you can extend
|
||||||
# this safety limit and even removing it by setting it to `null`.
|
# this safety limit and even removing it by setting it to `null`.
|
||||||
# Also, everything is expected to work safely out-of-the-box, but we highly advise to
|
# Also, everything is expected to work safely out-of-the-box, but we highly advise to
|
||||||
# first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml),
|
# first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml),
|
||||||
# then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully
|
# then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully
|
||||||
max_relative_target: int | None = 5
|
max_relative_target: float | dict[str, float] = 5.0
|
||||||
|
|
||||||
# cameras
|
# cameras
|
||||||
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
# Troubleshooting: If one of your IntelRealSense cameras freeze during
|
# Troubleshooting: If one of your IntelRealSense cameras freeze during
|
||||||
# data recording due to bandwidth limit, you might need to plug the camera
|
# data recording due to bandwidth limit, you might need to plug the camera
|
||||||
# on another USB hub or PCIe card.
|
# on another USB hub or PCIe card.
|
||||||
|
|
||||||
|
# Set to `True` for backward compatibility with previous policies/dataset
|
||||||
|
use_degrees: bool = False
|
||||||
|
|||||||
@@ -18,7 +18,6 @@ from functools import cached_property
|
|||||||
from typing import Any
|
from typing import Any
|
||||||
|
|
||||||
from lerobot.cameras.utils import make_cameras_from_configs
|
from lerobot.cameras.utils import make_cameras_from_configs
|
||||||
from lerobot.constants import OBS_STATE
|
|
||||||
from lerobot.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
from lerobot.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
||||||
from lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
from lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
||||||
from lerobot.motors.dynamixel import (
|
from lerobot.motors.dynamixel import (
|
||||||
@@ -45,22 +44,23 @@ class ViperX(Robot):
|
|||||||
self,
|
self,
|
||||||
config: ViperXConfig,
|
config: ViperXConfig,
|
||||||
):
|
):
|
||||||
raise NotImplementedError
|
|
||||||
super().__init__(config)
|
super().__init__(config)
|
||||||
self.config = config
|
self.config = config
|
||||||
|
norm_mode_body = MotorNormMode.DEGREES if config.use_degrees else MotorNormMode.RANGE_M100_100
|
||||||
self.bus = DynamixelMotorsBus(
|
self.bus = DynamixelMotorsBus(
|
||||||
port=self.config.port,
|
port=self.config.port,
|
||||||
motors={
|
motors={
|
||||||
"waist": Motor(1, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"waist": Motor(1, "xm540-w270", norm_mode_body),
|
||||||
"shoulder": Motor(2, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"shoulder": Motor(2, "xm540-w270", norm_mode_body),
|
||||||
"shoulder_shadow": Motor(3, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"shoulder_shadow": Motor(3, "xm540-w270", norm_mode_body),
|
||||||
"elbow": Motor(4, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"elbow": Motor(4, "xm540-w270", norm_mode_body),
|
||||||
"elbow_shadow": Motor(5, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"elbow_shadow": Motor(5, "xm540-w270", norm_mode_body),
|
||||||
"forearm_roll": Motor(6, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"forearm_roll": Motor(6, "xm540-w270", norm_mode_body),
|
||||||
"wrist_angle": Motor(7, "xm540-w270", MotorNormMode.RANGE_M100_100),
|
"wrist_angle": Motor(7, "xm540-w270", norm_mode_body),
|
||||||
"wrist_rotate": Motor(8, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"wrist_rotate": Motor(8, "xm430-w350", norm_mode_body),
|
||||||
"gripper": Motor(9, "xm430-w350", MotorNormMode.RANGE_0_100),
|
"gripper": Motor(9, "xm430-w350", MotorNormMode.RANGE_0_100),
|
||||||
},
|
},
|
||||||
|
calibration=self.calibration,
|
||||||
)
|
)
|
||||||
self.cameras = make_cameras_from_configs(config.cameras)
|
self.cameras = make_cameras_from_configs(config.cameras)
|
||||||
|
|
||||||
@@ -96,6 +96,9 @@ class ViperX(Robot):
|
|||||||
|
|
||||||
self.bus.connect()
|
self.bus.connect()
|
||||||
if not self.is_calibrated and calibrate:
|
if not self.is_calibrated and calibrate:
|
||||||
|
logger.info(
|
||||||
|
"Mismatch between calibration values in the motor and the calibration file or no calibration file found"
|
||||||
|
)
|
||||||
self.calibrate()
|
self.calibrate()
|
||||||
|
|
||||||
for cam in self.cameras.values():
|
for cam in self.cameras.values():
|
||||||
@@ -109,16 +112,24 @@ class ViperX(Robot):
|
|||||||
return self.bus.is_calibrated
|
return self.bus.is_calibrated
|
||||||
|
|
||||||
def calibrate(self) -> None:
|
def calibrate(self) -> None:
|
||||||
raise NotImplementedError # TODO(aliberts): adapt code below (copied from koch
|
|
||||||
logger.info(f"\nRunning calibration of {self}")
|
|
||||||
self.bus.disable_torque()
|
self.bus.disable_torque()
|
||||||
|
if self.calibration:
|
||||||
|
# Calibration file exists, ask user whether to use it or run new calibration
|
||||||
|
user_input = input(
|
||||||
|
f"Press ENTER to use provided calibration file associated with the id {self.id}, or type 'c' and press ENTER to run calibration: "
|
||||||
|
)
|
||||||
|
if user_input.strip().lower() != "c":
|
||||||
|
logger.info(f"Writing calibration file associated with the id {self.id} to the motors")
|
||||||
|
self.bus.write_calibration(self.calibration)
|
||||||
|
return
|
||||||
|
logger.info(f"\nRunning calibration of {self}")
|
||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
input("Move robot to the middle of its range of motion and press ENTER....")
|
input(f"Move {self} to the middle of its range of motion and press ENTER....")
|
||||||
homing_offsets = self.bus.set_half_turn_homings()
|
homing_offsets = self.bus.set_half_turn_homings()
|
||||||
|
|
||||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
full_turn_motors = ["shoulder", "forearm_roll", "wrist_rotate"]
|
||||||
unknown_range_motors = [motor for motor in self.bus.motors if motor not in full_turn_motors]
|
unknown_range_motors = [motor for motor in self.bus.motors if motor not in full_turn_motors]
|
||||||
print(
|
print(
|
||||||
f"Move all joints except {full_turn_motors} sequentially through their entire "
|
f"Move all joints except {full_turn_motors} sequentially through their entire "
|
||||||
@@ -153,33 +164,23 @@ class ViperX(Robot):
|
|||||||
self.bus.write("Secondary_ID", "shoulder_shadow", 2)
|
self.bus.write("Secondary_ID", "shoulder_shadow", 2)
|
||||||
self.bus.write("Secondary_ID", "elbow_shadow", 4)
|
self.bus.write("Secondary_ID", "elbow_shadow", 4)
|
||||||
|
|
||||||
# Set a velocity limit of 131 as advised by Trossen Robotics
|
|
||||||
# TODO(aliberts): remove as it's actually useless in position control
|
|
||||||
self.bus.write("Velocity_Limit", 131)
|
|
||||||
|
|
||||||
# Use 'extended position mode' for all motors except gripper, because in joint mode the servos
|
|
||||||
# can't rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling
|
|
||||||
# the arm, you could end up with a servo with a position 0 or 4095 at a crucial point.
|
|
||||||
# See: https://emanual.robotis.com/docs/en/dxl/x/x_series/#operating-mode11
|
|
||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
if motor != "gripper":
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
|
||||||
|
|
||||||
|
# TODO(pepijn): Re enable this
|
||||||
# Use 'position control current based' for follower gripper to be limited by the limit of the
|
# Use 'position control current based' for follower gripper to be limited by the limit of the
|
||||||
# current. It can grasp an object without forcing too much even tho, it's goal position is a
|
# current. It can grasp an object without forcing too much even tho, it's goal position is a
|
||||||
# complete grasp (both gripper fingers are ordered to join and reach a touch).
|
# complete grasp (both gripper fingers are ordered to join and reach a touch).
|
||||||
self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
|
# self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
|
||||||
|
|
||||||
def get_observation(self) -> dict[str, Any]:
|
def get_observation(self) -> dict[str, Any]:
|
||||||
"""The returned observations do not have a batch dimension."""
|
"""The returned observations do not have a batch dimension."""
|
||||||
if not self.is_connected:
|
if not self.is_connected:
|
||||||
raise DeviceNotConnectedError(f"{self} is not connected.")
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
obs_dict = {}
|
|
||||||
|
|
||||||
# Read arm position
|
# Read arm position
|
||||||
start = time.perf_counter()
|
start = time.perf_counter()
|
||||||
obs_dict[OBS_STATE] = self.bus.sync_read("Present_Position")
|
obs_dict = self.bus.sync_read("Present_Position")
|
||||||
obs_dict = {f"{motor}.pos": val for motor, val in obs_dict.items()}
|
obs_dict = {f"{motor}.pos": val for motor, val in obs_dict.items()}
|
||||||
dt_ms = (time.perf_counter() - start) * 1e3
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
logger.debug(f"{self} read state: {dt_ms:.1f}ms")
|
logger.debug(f"{self} read state: {dt_ms:.1f}ms")
|
||||||
|
|||||||
4
src/lerobot/teleoperators/aloha_teleop/__init__.py
Normal file
4
src/lerobot/teleoperators/aloha_teleop/__init__.py
Normal file
@@ -0,0 +1,4 @@
|
|||||||
|
from .aloha_teleop import AlohaTeleop
|
||||||
|
from .config_aloha_teleop import AlohaTeleopConfig
|
||||||
|
|
||||||
|
__all__ = ["AlohaTeleop", "AlohaTeleopConfig"]
|
||||||
125
src/lerobot/teleoperators/aloha_teleop/aloha_teleop.py
Normal file
125
src/lerobot/teleoperators/aloha_teleop/aloha_teleop.py
Normal file
@@ -0,0 +1,125 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
import logging
|
||||||
|
from functools import cached_property
|
||||||
|
|
||||||
|
from lerobot.teleoperators.widowx.config_widowx import WidowXConfig
|
||||||
|
from lerobot.teleoperators.widowx.widowx import WidowX
|
||||||
|
|
||||||
|
from ..teleoperator import Teleoperator
|
||||||
|
from .config_aloha_teleop import AlohaTeleopConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
class AlohaTeleop(Teleoperator):
|
||||||
|
"""
|
||||||
|
ALOHA Bimanual Teleoperator System using dual WidowX leader arms.
|
||||||
|
Based on the ALOHA (A Low-cost Open-source Hardware System for Bimanual Teleoperation) design.
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = AlohaTeleopConfig
|
||||||
|
name = "aloha_teleop"
|
||||||
|
|
||||||
|
def __init__(self, config: AlohaTeleopConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
self.config = config
|
||||||
|
|
||||||
|
left_arm_config = WidowXConfig(
|
||||||
|
id=f"{config.id}_left" if config.id else None,
|
||||||
|
calibration_dir=config.calibration_dir,
|
||||||
|
port=config.left_arm_port,
|
||||||
|
gripper_motor=config.left_arm_gripper_motor,
|
||||||
|
use_degrees=config.left_arm_use_degrees,
|
||||||
|
)
|
||||||
|
|
||||||
|
right_arm_config = WidowXConfig(
|
||||||
|
id=f"{config.id}_right" if config.id else None,
|
||||||
|
calibration_dir=config.calibration_dir,
|
||||||
|
port=config.right_arm_port,
|
||||||
|
gripper_motor=config.right_arm_gripper_motor,
|
||||||
|
use_degrees=config.right_arm_use_degrees,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.left_arm = WidowX(left_arm_config)
|
||||||
|
self.right_arm = WidowX(right_arm_config)
|
||||||
|
|
||||||
|
@cached_property
|
||||||
|
def action_features(self) -> dict[str, type]:
|
||||||
|
return {f"left_{motor}.pos": float for motor in self.left_arm.bus.motors} | {
|
||||||
|
f"right_{motor}.pos": float for motor in self.right_arm.bus.motors
|
||||||
|
}
|
||||||
|
|
||||||
|
@cached_property
|
||||||
|
def feedback_features(self) -> dict[str, type]:
|
||||||
|
return {}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
return self.left_arm.is_connected and self.right_arm.is_connected
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = True) -> None:
|
||||||
|
self.left_arm.connect(calibrate)
|
||||||
|
self.right_arm.connect(calibrate)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_calibrated(self) -> bool:
|
||||||
|
return self.left_arm.is_calibrated and self.right_arm.is_calibrated
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
self.left_arm.calibrate()
|
||||||
|
self.right_arm.calibrate()
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
self.left_arm.configure()
|
||||||
|
self.right_arm.configure()
|
||||||
|
|
||||||
|
def setup_motors(self) -> None:
|
||||||
|
self.left_arm.setup_motors()
|
||||||
|
self.right_arm.setup_motors()
|
||||||
|
|
||||||
|
def get_action(self) -> dict[str, float]:
|
||||||
|
action_dict = {}
|
||||||
|
|
||||||
|
# Add "left_" prefix
|
||||||
|
left_action = self.left_arm.get_action()
|
||||||
|
action_dict.update({f"left_{key}": value for key, value in left_action.items()})
|
||||||
|
|
||||||
|
# Add "right_" prefix
|
||||||
|
right_action = self.right_arm.get_action()
|
||||||
|
action_dict.update({f"right_{key}": value for key, value in right_action.items()})
|
||||||
|
|
||||||
|
return action_dict
|
||||||
|
|
||||||
|
def send_feedback(self, feedback: dict[str, float]) -> None:
|
||||||
|
# Remove "left_" prefix
|
||||||
|
left_feedback = {
|
||||||
|
key.removeprefix("left_"): value for key, value in feedback.items() if key.startswith("left_")
|
||||||
|
}
|
||||||
|
# Remove "right_" prefix
|
||||||
|
right_feedback = {
|
||||||
|
key.removeprefix("right_"): value for key, value in feedback.items() if key.startswith("right_")
|
||||||
|
}
|
||||||
|
|
||||||
|
if left_feedback:
|
||||||
|
self.left_arm.send_feedback(left_feedback)
|
||||||
|
if right_feedback:
|
||||||
|
self.right_arm.send_feedback(right_feedback)
|
||||||
|
|
||||||
|
def disconnect(self) -> None:
|
||||||
|
self.left_arm.disconnect()
|
||||||
|
self.right_arm.disconnect()
|
||||||
@@ -0,0 +1,34 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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
|
||||||
|
|
||||||
|
from ..config import TeleoperatorConfig
|
||||||
|
|
||||||
|
|
||||||
|
@TeleoperatorConfig.register_subclass("aloha_teleop")
|
||||||
|
@dataclass
|
||||||
|
class AlohaTeleopConfig(TeleoperatorConfig):
|
||||||
|
left_arm_port: str
|
||||||
|
right_arm_port: str
|
||||||
|
|
||||||
|
# Parameters for left arm (WidowX)
|
||||||
|
left_arm_gripper_motor: str = "xl430-w250"
|
||||||
|
left_arm_use_degrees: bool = True
|
||||||
|
|
||||||
|
# Parameters for right arm (WidowX)
|
||||||
|
right_arm_gripper_motor: str = "xc430-w150"
|
||||||
|
right_arm_use_degrees: bool = True
|
||||||
@@ -88,6 +88,7 @@ class KochLeader(Teleoperator):
|
|||||||
return self.bus.is_calibrated
|
return self.bus.is_calibrated
|
||||||
|
|
||||||
def calibrate(self) -> None:
|
def calibrate(self) -> None:
|
||||||
|
self.bus.disable_torque()
|
||||||
if self.calibration:
|
if self.calibration:
|
||||||
# Calibration file exists, ask user whether to use it or run new calibration
|
# Calibration file exists, ask user whether to use it or run new calibration
|
||||||
user_input = input(
|
user_input = input(
|
||||||
@@ -98,7 +99,6 @@ class KochLeader(Teleoperator):
|
|||||||
self.bus.write_calibration(self.calibration)
|
self.bus.write_calibration(self.calibration)
|
||||||
return
|
return
|
||||||
logger.info(f"\nRunning calibration of {self}")
|
logger.info(f"\nRunning calibration of {self}")
|
||||||
self.bus.disable_torque()
|
|
||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
|||||||
25
src/lerobot/teleoperators/reachy2_teleoperator/__init__.py
Normal file
25
src/lerobot/teleoperators/reachy2_teleoperator/__init__.py
Normal file
@@ -0,0 +1,25 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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 .config_reachy2_teleoperator import Reachy2TeleoperatorConfig
|
||||||
|
from .reachy2_teleoperator import (
|
||||||
|
REACHY2_ANTENNAS_JOINTS,
|
||||||
|
REACHY2_L_ARM_JOINTS,
|
||||||
|
REACHY2_NECK_JOINTS,
|
||||||
|
REACHY2_R_ARM_JOINTS,
|
||||||
|
REACHY2_VEL,
|
||||||
|
Reachy2Teleoperator,
|
||||||
|
)
|
||||||
@@ -0,0 +1,51 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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
|
||||||
|
|
||||||
|
from ..config import TeleoperatorConfig
|
||||||
|
|
||||||
|
|
||||||
|
@TeleoperatorConfig.register_subclass("reachy2_teleoperator")
|
||||||
|
@dataclass
|
||||||
|
class Reachy2TeleoperatorConfig(TeleoperatorConfig):
|
||||||
|
# IP address of the Reachy 2 robot used as teleoperator
|
||||||
|
ip_address: str | None = "localhost"
|
||||||
|
|
||||||
|
# Whether to use the present position of the joints as actions
|
||||||
|
# if False, the goal position of the joints will be used
|
||||||
|
use_present_position: bool = False
|
||||||
|
|
||||||
|
# Which parts of the robot to use
|
||||||
|
with_mobile_base: bool = True
|
||||||
|
with_l_arm: bool = True
|
||||||
|
with_r_arm: bool = True
|
||||||
|
with_neck: bool = True
|
||||||
|
with_antennas: bool = True
|
||||||
|
|
||||||
|
def __post_init__(self):
|
||||||
|
if not (
|
||||||
|
self.with_mobile_base
|
||||||
|
or self.with_l_arm
|
||||||
|
or self.with_r_arm
|
||||||
|
or self.with_neck
|
||||||
|
or self.with_antennas
|
||||||
|
):
|
||||||
|
raise ValueError(
|
||||||
|
"No Reachy2Teleoperator part used.\n"
|
||||||
|
"At least one part of the robot must be set to True "
|
||||||
|
"(with_mobile_base, with_l_arm, with_r_arm, with_neck, with_antennas)"
|
||||||
|
)
|
||||||
@@ -0,0 +1,164 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
import logging
|
||||||
|
import time
|
||||||
|
|
||||||
|
from reachy2_sdk import ReachySDK
|
||||||
|
|
||||||
|
from ..teleoperator import Teleoperator
|
||||||
|
from .config_reachy2_teleoperator import Reachy2TeleoperatorConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
# {lerobot_keys: reachy2_sdk_keys}
|
||||||
|
REACHY2_NECK_JOINTS = {
|
||||||
|
"neck_yaw.pos": "head.neck.yaw",
|
||||||
|
"neck_pitch.pos": "head.neck.pitch",
|
||||||
|
"neck_roll.pos": "head.neck.roll",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_ANTENNAS_JOINTS = {
|
||||||
|
"l_antenna.pos": "head.l_antenna",
|
||||||
|
"r_antenna.pos": "head.r_antenna",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_R_ARM_JOINTS = {
|
||||||
|
"r_shoulder_pitch.pos": "r_arm.shoulder.pitch",
|
||||||
|
"r_shoulder_roll.pos": "r_arm.shoulder.roll",
|
||||||
|
"r_elbow_yaw.pos": "r_arm.elbow.yaw",
|
||||||
|
"r_elbow_pitch.pos": "r_arm.elbow.pitch",
|
||||||
|
"r_wrist_roll.pos": "r_arm.wrist.roll",
|
||||||
|
"r_wrist_pitch.pos": "r_arm.wrist.pitch",
|
||||||
|
"r_wrist_yaw.pos": "r_arm.wrist.yaw",
|
||||||
|
"r_gripper.pos": "r_arm.gripper",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_L_ARM_JOINTS = {
|
||||||
|
"l_shoulder_pitch.pos": "l_arm.shoulder.pitch",
|
||||||
|
"l_shoulder_roll.pos": "l_arm.shoulder.roll",
|
||||||
|
"l_elbow_yaw.pos": "l_arm.elbow.yaw",
|
||||||
|
"l_elbow_pitch.pos": "l_arm.elbow.pitch",
|
||||||
|
"l_wrist_roll.pos": "l_arm.wrist.roll",
|
||||||
|
"l_wrist_pitch.pos": "l_arm.wrist.pitch",
|
||||||
|
"l_wrist_yaw.pos": "l_arm.wrist.yaw",
|
||||||
|
"l_gripper.pos": "l_arm.gripper",
|
||||||
|
}
|
||||||
|
|
||||||
|
REACHY2_VEL = {
|
||||||
|
"mobile_base.vx": "vx",
|
||||||
|
"mobile_base.vy": "vy",
|
||||||
|
"mobile_base.vtheta": "vtheta",
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
class Reachy2Teleoperator(Teleoperator):
|
||||||
|
"""
|
||||||
|
[Reachy 2](https://www.pollen-robotics.com/reachy/), by Pollen Robotics.
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = Reachy2TeleoperatorConfig
|
||||||
|
name = "reachy2_specific"
|
||||||
|
|
||||||
|
def __init__(self, config: Reachy2TeleoperatorConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
self.config = config
|
||||||
|
self.reachy: None | ReachySDK = None
|
||||||
|
|
||||||
|
self.joints_dict: dict[str, str] = self._generate_joints_dict()
|
||||||
|
|
||||||
|
def _generate_joints_dict(self) -> dict[str, str]:
|
||||||
|
joints = {}
|
||||||
|
if self.config.with_neck:
|
||||||
|
joints.update(REACHY2_NECK_JOINTS)
|
||||||
|
if self.config.with_l_arm:
|
||||||
|
joints.update(REACHY2_L_ARM_JOINTS)
|
||||||
|
if self.config.with_r_arm:
|
||||||
|
joints.update(REACHY2_R_ARM_JOINTS)
|
||||||
|
if self.config.with_antennas:
|
||||||
|
joints.update(REACHY2_ANTENNAS_JOINTS)
|
||||||
|
return joints
|
||||||
|
|
||||||
|
@property
|
||||||
|
def action_features(self) -> dict[str, type]:
|
||||||
|
if self.config.with_mobile_base:
|
||||||
|
return {
|
||||||
|
**dict.fromkeys(
|
||||||
|
self.joints_dict.keys(),
|
||||||
|
float,
|
||||||
|
),
|
||||||
|
**dict.fromkeys(
|
||||||
|
REACHY2_VEL.keys(),
|
||||||
|
float,
|
||||||
|
),
|
||||||
|
}
|
||||||
|
else:
|
||||||
|
return dict.fromkeys(self.joints_dict.keys(), float)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def feedback_features(self) -> dict[str, type]:
|
||||||
|
return {}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
return self.reachy.is_connected() if self.reachy is not None else False
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = True) -> None:
|
||||||
|
self.reachy = ReachySDK(self.config.ip_address)
|
||||||
|
if not self.is_connected:
|
||||||
|
raise ConnectionError()
|
||||||
|
logger.info(f"{self} connected.")
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_calibrated(self) -> bool:
|
||||||
|
return True
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def get_action(self) -> dict[str, float]:
|
||||||
|
start = time.perf_counter()
|
||||||
|
|
||||||
|
if self.reachy and self.is_connected:
|
||||||
|
if self.config.use_present_position:
|
||||||
|
joint_action = {
|
||||||
|
k: self.reachy.joints[v].present_position for k, v in self.joints_dict.items()
|
||||||
|
}
|
||||||
|
else:
|
||||||
|
joint_action = {k: self.reachy.joints[v].goal_position for k, v in self.joints_dict.items()}
|
||||||
|
|
||||||
|
if not self.config.with_mobile_base:
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read action: {dt_ms:.1f}ms")
|
||||||
|
return joint_action
|
||||||
|
|
||||||
|
if self.config.use_present_position:
|
||||||
|
vel_action = {k: self.reachy.mobile_base.odometry[v] for k, v in REACHY2_VEL.items()}
|
||||||
|
else:
|
||||||
|
vel_action = {k: self.reachy.mobile_base.last_cmd_vel[v] for k, v in REACHY2_VEL.items()}
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read action: {dt_ms:.1f}ms")
|
||||||
|
return {**joint_action, **vel_action}
|
||||||
|
|
||||||
|
def send_feedback(self, feedback: dict[str, float]) -> None:
|
||||||
|
raise NotImplementedError
|
||||||
|
|
||||||
|
def disconnect(self) -> None:
|
||||||
|
if self.reachy and self.is_connected:
|
||||||
|
self.reachy.disconnect()
|
||||||
@@ -65,5 +65,9 @@ def make_teleoperator_from_config(config: TeleoperatorConfig) -> Teleoperator:
|
|||||||
from .bi_so100_leader import BiSO100Leader
|
from .bi_so100_leader import BiSO100Leader
|
||||||
|
|
||||||
return BiSO100Leader(config)
|
return BiSO100Leader(config)
|
||||||
|
elif config.type == "reachy2_teleoperator":
|
||||||
|
from .reachy2_teleoperator import Reachy2Teleoperator
|
||||||
|
|
||||||
|
return Reachy2Teleoperator(config)
|
||||||
else:
|
else:
|
||||||
raise ValueError(config.type)
|
raise ValueError(config.type)
|
||||||
|
|||||||
@@ -23,3 +23,7 @@ from ..config import TeleoperatorConfig
|
|||||||
@dataclass
|
@dataclass
|
||||||
class WidowXConfig(TeleoperatorConfig):
|
class WidowXConfig(TeleoperatorConfig):
|
||||||
port: str # Port to connect to the arm
|
port: str # Port to connect to the arm
|
||||||
|
|
||||||
|
gripper_motor: str = "xl430-w250" # This could be xc430-w150 or xl430-w250
|
||||||
|
|
||||||
|
use_degrees: bool = False
|
||||||
|
|||||||
@@ -20,7 +20,6 @@ import time
|
|||||||
from lerobot.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
from lerobot.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
||||||
from lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
from lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
||||||
from lerobot.motors.dynamixel import (
|
from lerobot.motors.dynamixel import (
|
||||||
DriveMode,
|
|
||||||
DynamixelMotorsBus,
|
DynamixelMotorsBus,
|
||||||
OperatingMode,
|
OperatingMode,
|
||||||
)
|
)
|
||||||
@@ -40,22 +39,27 @@ class WidowX(Teleoperator):
|
|||||||
name = "widowx"
|
name = "widowx"
|
||||||
|
|
||||||
def __init__(self, config: WidowXConfig):
|
def __init__(self, config: WidowXConfig):
|
||||||
raise NotImplementedError
|
|
||||||
super().__init__(config)
|
super().__init__(config)
|
||||||
self.config = config
|
self.config = config
|
||||||
|
norm_mode_body = MotorNormMode.DEGREES if config.use_degrees else MotorNormMode.RANGE_M100_100
|
||||||
self.bus = DynamixelMotorsBus(
|
self.bus = DynamixelMotorsBus(
|
||||||
port=self.config.port,
|
port=self.config.port,
|
||||||
motors={
|
motors={
|
||||||
"waist": Motor(1, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"waist": Motor(1, "xm430-w350", norm_mode_body),
|
||||||
"shoulder": Motor(2, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"shoulder": Motor(2, "xm430-w350", norm_mode_body),
|
||||||
"shoulder_shadow": Motor(3, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"shoulder_shadow": Motor(3, "xm430-w350", norm_mode_body),
|
||||||
"elbow": Motor(4, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"elbow": Motor(4, "xm430-w350", norm_mode_body),
|
||||||
"elbow_shadow": Motor(5, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"elbow_shadow": Motor(5, "xm430-w350", norm_mode_body),
|
||||||
"forearm_roll": Motor(6, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"forearm_roll": Motor(6, "xm430-w350", norm_mode_body),
|
||||||
"wrist_angle": Motor(7, "xm430-w350", MotorNormMode.RANGE_M100_100),
|
"wrist_angle": Motor(7, "xm430-w350", norm_mode_body),
|
||||||
"wrist_rotate": Motor(8, "xl430-w250", MotorNormMode.RANGE_M100_100),
|
"wrist_rotate": Motor(
|
||||||
"gripper": Motor(9, "xc430-w150", MotorNormMode.RANGE_0_100),
|
8, "xm430-w350", norm_mode_body
|
||||||
|
), # This could be xl430-w250 or xm430-w350
|
||||||
|
"gripper": Motor(
|
||||||
|
9, self.config.gripper_motor, MotorNormMode.RANGE_0_100
|
||||||
|
), # This could be xc430-w150 or xl430-w250
|
||||||
},
|
},
|
||||||
|
calibration=self.calibration,
|
||||||
)
|
)
|
||||||
|
|
||||||
@property
|
@property
|
||||||
@@ -76,6 +80,9 @@ class WidowX(Teleoperator):
|
|||||||
|
|
||||||
self.bus.connect()
|
self.bus.connect()
|
||||||
if not self.is_calibrated and calibrate:
|
if not self.is_calibrated and calibrate:
|
||||||
|
logger.info(
|
||||||
|
"Mismatch between calibration values in the motor and the calibration file or no calibration file found"
|
||||||
|
)
|
||||||
self.calibrate()
|
self.calibrate()
|
||||||
|
|
||||||
self.configure()
|
self.configure()
|
||||||
@@ -86,19 +93,27 @@ class WidowX(Teleoperator):
|
|||||||
return self.bus.is_calibrated
|
return self.bus.is_calibrated
|
||||||
|
|
||||||
def calibrate(self) -> None:
|
def calibrate(self) -> None:
|
||||||
raise NotImplementedError # TODO(aliberts): adapt code below (copied from koch)
|
|
||||||
logger.info(f"\nRunning calibration of {self}")
|
|
||||||
self.bus.disable_torque()
|
self.bus.disable_torque()
|
||||||
|
if self.calibration:
|
||||||
|
# Calibration file exists, ask user whether to use it or run new calibration
|
||||||
|
user_input = input(
|
||||||
|
f"Press ENTER to use provided calibration file associated with the id {self.id}, or type 'c' and press ENTER to run calibration: "
|
||||||
|
)
|
||||||
|
if user_input.strip().lower() != "c":
|
||||||
|
logger.info(f"Writing calibration file associated with the id {self.id} to the motors")
|
||||||
|
self.bus.write_calibration(self.calibration)
|
||||||
|
return
|
||||||
|
logger.info(f"\nRunning calibration of {self}")
|
||||||
for motor in self.bus.motors:
|
for motor in self.bus.motors:
|
||||||
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
self.bus.write("Drive_Mode", "elbow_flex", DriveMode.INVERTED.value)
|
# self.bus.write("Drive_Mode", "el", DriveMode.INVERTED.value)
|
||||||
drive_modes = {motor: 1 if motor == "elbow_flex" else 0 for motor in self.bus.motors}
|
# drive_modes = {motor: 1 if motor == ["elbow_shadow", "shoulder_shadow"] else 0 for motor in self.bus.motors}
|
||||||
|
|
||||||
input("Move robot to the middle of its range of motion and press ENTER....")
|
input(f"Move {self} to the middle of its range of motion and press ENTER....")
|
||||||
homing_offsets = self.bus.set_half_turn_homings()
|
homing_offsets = self.bus.set_half_turn_homings()
|
||||||
|
|
||||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
full_turn_motors = ["shoulder", "forearm_roll", "wrist_rotate"]
|
||||||
unknown_range_motors = [motor for motor in self.bus.motors if motor not in full_turn_motors]
|
unknown_range_motors = [motor for motor in self.bus.motors if motor not in full_turn_motors]
|
||||||
print(
|
print(
|
||||||
f"Move all joints except {full_turn_motors} sequentially through their "
|
f"Move all joints except {full_turn_motors} sequentially through their "
|
||||||
@@ -113,7 +128,7 @@ class WidowX(Teleoperator):
|
|||||||
for motor, m in self.bus.motors.items():
|
for motor, m in self.bus.motors.items():
|
||||||
self.calibration[motor] = MotorCalibration(
|
self.calibration[motor] = MotorCalibration(
|
||||||
id=m.id,
|
id=m.id,
|
||||||
drive_mode=drive_modes[motor],
|
drive_mode=0,
|
||||||
homing_offset=homing_offsets[motor],
|
homing_offset=homing_offsets[motor],
|
||||||
range_min=range_mins[motor],
|
range_min=range_mins[motor],
|
||||||
range_max=range_maxes[motor],
|
range_max=range_maxes[motor],
|
||||||
@@ -133,6 +148,22 @@ class WidowX(Teleoperator):
|
|||||||
self.bus.write("Secondary_ID", "shoulder_shadow", 2)
|
self.bus.write("Secondary_ID", "shoulder_shadow", 2)
|
||||||
self.bus.write("Secondary_ID", "elbow_shadow", 4)
|
self.bus.write("Secondary_ID", "elbow_shadow", 4)
|
||||||
|
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
# TODO(pepijn): Re enable this
|
||||||
|
# Use 'position control current based' for gripper to be limited by the limit of the current.
|
||||||
|
# For the follower gripper, it means it can grasp an object without forcing too much even tho,
|
||||||
|
# its goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch).
|
||||||
|
# For the leader gripper, it means we can use it as a physical trigger, since we can force with our finger
|
||||||
|
# to make it move, and it will move back to its original target position when we release the force.
|
||||||
|
# self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
|
||||||
|
# Set gripper's goal pos in current position mode so that we can use it as a trigger.
|
||||||
|
# self.bus.enable_torque("gripper")
|
||||||
|
|
||||||
|
if self.is_calibrated:
|
||||||
|
self.bus.write("Goal_Position", "gripper", self.config.gripper_open_pos)
|
||||||
|
|
||||||
def get_action(self) -> dict[str, float]:
|
def get_action(self) -> dict[str, float]:
|
||||||
if not self.is_connected:
|
if not self.is_connected:
|
||||||
raise DeviceNotConnectedError(f"{self} is not connected.")
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|||||||
177
tests/cameras/test_reachy2_camera.py
Normal file
177
tests/cameras/test_reachy2_camera.py
Normal file
@@ -0,0 +1,177 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# 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.
|
||||||
|
|
||||||
|
import time
|
||||||
|
from unittest.mock import MagicMock, patch
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
from lerobot.cameras.reachy2_camera import Reachy2Camera, Reachy2CameraConfig
|
||||||
|
from lerobot.errors import DeviceNotConnectedError
|
||||||
|
|
||||||
|
PARAMS = [
|
||||||
|
("teleop", "left"),
|
||||||
|
("teleop", "right"),
|
||||||
|
("depth", "rgb"),
|
||||||
|
# ("depth", "depth"), # Depth camera is not available yet
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
def _make_cam_manager_mock():
|
||||||
|
c = MagicMock(name="CameraManagerMock")
|
||||||
|
|
||||||
|
teleop = MagicMock(name="TeleopCam")
|
||||||
|
teleop.width = 640
|
||||||
|
teleop.height = 480
|
||||||
|
teleop.get_frame = MagicMock(
|
||||||
|
side_effect=lambda *_, **__: (
|
||||||
|
np.zeros((480, 640, 3), dtype=np.uint8),
|
||||||
|
time.time(),
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
depth = MagicMock(name="DepthCam")
|
||||||
|
depth.width = 640
|
||||||
|
depth.height = 480
|
||||||
|
depth.get_frame = MagicMock(
|
||||||
|
side_effect=lambda *_, **__: (
|
||||||
|
np.zeros((480, 640, 3), dtype=np.uint8),
|
||||||
|
time.time(),
|
||||||
|
)
|
||||||
|
)
|
||||||
|
|
||||||
|
c.is_connected.return_value = True
|
||||||
|
c.teleop = teleop
|
||||||
|
c.depth = depth
|
||||||
|
|
||||||
|
def _connect():
|
||||||
|
c.teleop = teleop
|
||||||
|
c.depth = depth
|
||||||
|
c.is_connected.return_value = True
|
||||||
|
|
||||||
|
def _disconnect():
|
||||||
|
c.teleop = None
|
||||||
|
c.depth = None
|
||||||
|
c.is_connected.return_value = False
|
||||||
|
|
||||||
|
c.connect = MagicMock(side_effect=_connect)
|
||||||
|
c.disconnect = MagicMock(side_effect=_disconnect)
|
||||||
|
|
||||||
|
# Mock methods
|
||||||
|
c.initialize_cameras = MagicMock()
|
||||||
|
|
||||||
|
return c
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.fixture(
|
||||||
|
params=PARAMS,
|
||||||
|
# ids=["teleop-left", "teleop-right", "torso-rgb", "torso-depth"],
|
||||||
|
ids=["teleop-left", "teleop-right", "torso-rgb"],
|
||||||
|
)
|
||||||
|
def camera(request):
|
||||||
|
name, image_type = request.param
|
||||||
|
with (
|
||||||
|
patch(
|
||||||
|
"lerobot.cameras.reachy2_camera.reachy2_camera.CameraManager",
|
||||||
|
side_effect=lambda *a, **k: _make_cam_manager_mock(),
|
||||||
|
),
|
||||||
|
):
|
||||||
|
config = Reachy2CameraConfig(name=name, image_type=image_type)
|
||||||
|
cam = Reachy2Camera(config)
|
||||||
|
yield cam
|
||||||
|
if cam.is_connected:
|
||||||
|
cam.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_connect(camera):
|
||||||
|
camera.connect()
|
||||||
|
assert camera.is_connected
|
||||||
|
camera.cam_manager.initialize_cameras.assert_called_once()
|
||||||
|
|
||||||
|
|
||||||
|
def test_read(camera):
|
||||||
|
camera.connect()
|
||||||
|
|
||||||
|
img = camera.read()
|
||||||
|
if camera.config.name == "teleop":
|
||||||
|
camera.cam_manager.teleop.get_frame.assert_called_once()
|
||||||
|
elif camera.config.name == "depth":
|
||||||
|
camera.cam_manager.depth.get_frame.assert_called_once()
|
||||||
|
assert isinstance(img, np.ndarray)
|
||||||
|
assert img.shape == (480, 640, 3)
|
||||||
|
|
||||||
|
|
||||||
|
def test_disconnect(camera):
|
||||||
|
camera.connect()
|
||||||
|
|
||||||
|
camera.disconnect()
|
||||||
|
assert not camera.is_connected
|
||||||
|
|
||||||
|
|
||||||
|
def test_async_read(camera):
|
||||||
|
camera.connect()
|
||||||
|
try:
|
||||||
|
img = camera.async_read()
|
||||||
|
|
||||||
|
assert camera.thread is not None
|
||||||
|
assert camera.thread.is_alive()
|
||||||
|
assert isinstance(img, np.ndarray)
|
||||||
|
finally:
|
||||||
|
if camera.is_connected:
|
||||||
|
camera.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_async_read_timeout(camera):
|
||||||
|
camera.connect()
|
||||||
|
try:
|
||||||
|
with pytest.raises(TimeoutError):
|
||||||
|
camera.async_read(timeout_ms=0)
|
||||||
|
finally:
|
||||||
|
if camera.is_connected:
|
||||||
|
camera.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_read_before_connect(camera):
|
||||||
|
with pytest.raises(DeviceNotConnectedError):
|
||||||
|
_ = camera.read()
|
||||||
|
|
||||||
|
|
||||||
|
def test_disconnect_before_connect(camera):
|
||||||
|
with pytest.raises(DeviceNotConnectedError):
|
||||||
|
camera.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_async_read_before_connect(camera):
|
||||||
|
with pytest.raises(DeviceNotConnectedError):
|
||||||
|
_ = camera.async_read()
|
||||||
|
|
||||||
|
|
||||||
|
def test_wrong_camera_name():
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2CameraConfig(name="wrong-name", image_type="left")
|
||||||
|
|
||||||
|
|
||||||
|
def test_wrong_image_type():
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2CameraConfig(name="teleop", image_type="rgb")
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2CameraConfig(name="depth", image_type="left")
|
||||||
|
|
||||||
|
|
||||||
|
def test_wrong_color_mode():
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2CameraConfig(name="teleop", image_type="left", color_mode="wrong-color")
|
||||||
@@ -28,6 +28,7 @@ pytest_plugins = [
|
|||||||
"tests.fixtures.files",
|
"tests.fixtures.files",
|
||||||
"tests.fixtures.hub",
|
"tests.fixtures.hub",
|
||||||
"tests.fixtures.optimizers",
|
"tests.fixtures.optimizers",
|
||||||
|
"tests.plugins.reachy2_sdk",
|
||||||
]
|
]
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
30
tests/plugins/reachy2_sdk.py
Normal file
30
tests/plugins/reachy2_sdk.py
Normal file
@@ -0,0 +1,30 @@
|
|||||||
|
import sys
|
||||||
|
import types
|
||||||
|
from unittest.mock import MagicMock
|
||||||
|
|
||||||
|
|
||||||
|
def _install_reachy2_sdk_stub():
|
||||||
|
sdk = types.ModuleType("reachy2_sdk")
|
||||||
|
sdk.__path__ = []
|
||||||
|
sdk.ReachySDK = MagicMock(name="ReachySDK")
|
||||||
|
|
||||||
|
media = types.ModuleType("reachy2_sdk.media")
|
||||||
|
media.__path__ = []
|
||||||
|
camera = types.ModuleType("reachy2_sdk.media.camera")
|
||||||
|
camera.CameraView = MagicMock(name="CameraView")
|
||||||
|
camera_manager = types.ModuleType("reachy2_sdk.media.camera_manager")
|
||||||
|
camera_manager.CameraManager = MagicMock(name="CameraManager")
|
||||||
|
|
||||||
|
sdk.media = media
|
||||||
|
media.camera = camera
|
||||||
|
media.camera_manager = camera_manager
|
||||||
|
|
||||||
|
# Register in sys.modules
|
||||||
|
sys.modules.setdefault("reachy2_sdk", sdk)
|
||||||
|
sys.modules.setdefault("reachy2_sdk.media", media)
|
||||||
|
sys.modules.setdefault("reachy2_sdk.media.camera", camera)
|
||||||
|
sys.modules.setdefault("reachy2_sdk.media.camera_manager", camera_manager)
|
||||||
|
|
||||||
|
|
||||||
|
def pytest_sessionstart(session):
|
||||||
|
_install_reachy2_sdk_stub()
|
||||||
326
tests/robots/test_reachy2.py
Normal file
326
tests/robots/test_reachy2.py
Normal file
@@ -0,0 +1,326 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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 unittest.mock import MagicMock, patch
|
||||||
|
|
||||||
|
import numpy as np
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
from lerobot.robots.reachy2 import (
|
||||||
|
REACHY2_ANTENNAS_JOINTS,
|
||||||
|
REACHY2_L_ARM_JOINTS,
|
||||||
|
REACHY2_NECK_JOINTS,
|
||||||
|
REACHY2_R_ARM_JOINTS,
|
||||||
|
REACHY2_VEL,
|
||||||
|
Reachy2Robot,
|
||||||
|
Reachy2RobotConfig,
|
||||||
|
)
|
||||||
|
|
||||||
|
# {lerobot_keys: reachy2_sdk_keys}
|
||||||
|
REACHY2_JOINTS = {
|
||||||
|
**REACHY2_NECK_JOINTS,
|
||||||
|
**REACHY2_ANTENNAS_JOINTS,
|
||||||
|
**REACHY2_R_ARM_JOINTS,
|
||||||
|
**REACHY2_L_ARM_JOINTS,
|
||||||
|
}
|
||||||
|
|
||||||
|
PARAMS = [
|
||||||
|
{}, # default config
|
||||||
|
{"with_mobile_base": False},
|
||||||
|
{"with_mobile_base": False, "with_l_arm": False, "with_antennas": False},
|
||||||
|
{"with_r_arm": False, "with_neck": False, "with_antennas": False},
|
||||||
|
{"use_external_commands": True, "disable_torque_on_disconnect": True},
|
||||||
|
{"use_external_commands": True, "with_mobile_base": False, "with_neck": False},
|
||||||
|
{"disable_torque_on_disconnect": False},
|
||||||
|
{"max_relative_target": 5},
|
||||||
|
{"with_right_teleop_camera": False},
|
||||||
|
{"with_left_teleop_camera": False, "with_right_teleop_camera": False},
|
||||||
|
{"with_left_teleop_camera": False, "with_torso_camera": True},
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
def _make_reachy2_sdk_mock():
|
||||||
|
class JointSpy:
|
||||||
|
__slots__ = (
|
||||||
|
"present_position",
|
||||||
|
"_goal_position",
|
||||||
|
"_on_set",
|
||||||
|
)
|
||||||
|
|
||||||
|
def __init__(self, present_position=0.0, on_set=None):
|
||||||
|
self.present_position = present_position
|
||||||
|
self._goal_position = present_position
|
||||||
|
self._on_set = on_set
|
||||||
|
|
||||||
|
@property
|
||||||
|
def goal_position(self):
|
||||||
|
return self._goal_position
|
||||||
|
|
||||||
|
@goal_position.setter
|
||||||
|
def goal_position(self, v):
|
||||||
|
self._goal_position = v
|
||||||
|
if self._on_set:
|
||||||
|
self._on_set()
|
||||||
|
|
||||||
|
r = MagicMock(name="ReachySDKMock")
|
||||||
|
r.is_connected.return_value = True
|
||||||
|
|
||||||
|
def _connect():
|
||||||
|
r.is_connected.return_value = True
|
||||||
|
|
||||||
|
def _disconnect():
|
||||||
|
r.is_connected.return_value = False
|
||||||
|
|
||||||
|
# Global counter of goal_position sets
|
||||||
|
r._goal_position_set_total = 0
|
||||||
|
|
||||||
|
def _on_any_goal_set():
|
||||||
|
r._goal_position_set_total += 1
|
||||||
|
|
||||||
|
# Mock joints with some dummy positions
|
||||||
|
joints = {
|
||||||
|
k: JointSpy(
|
||||||
|
present_position=float(i),
|
||||||
|
on_set=_on_any_goal_set,
|
||||||
|
)
|
||||||
|
for i, k in enumerate(REACHY2_JOINTS.values())
|
||||||
|
}
|
||||||
|
r.joints = joints
|
||||||
|
|
||||||
|
# Mock mobile base with some dummy odometry
|
||||||
|
r.mobile_base = MagicMock()
|
||||||
|
r.mobile_base.odometry = {
|
||||||
|
"x": 0.1,
|
||||||
|
"y": -0.2,
|
||||||
|
"theta": 21.3,
|
||||||
|
"vx": 0.001,
|
||||||
|
"vy": 0.002,
|
||||||
|
"vtheta": 0.0,
|
||||||
|
}
|
||||||
|
|
||||||
|
r.connect = MagicMock(side_effect=_connect)
|
||||||
|
r.disconnect = MagicMock(side_effect=_disconnect)
|
||||||
|
|
||||||
|
# Mock methods
|
||||||
|
r.turn_on = MagicMock()
|
||||||
|
r.reset_default_limits = MagicMock()
|
||||||
|
r.send_goal_positions = MagicMock()
|
||||||
|
r.turn_off_smoothly = MagicMock()
|
||||||
|
r.mobile_base.set_goal_speed = MagicMock()
|
||||||
|
r.mobile_base.send_speed_command = MagicMock()
|
||||||
|
|
||||||
|
return r
|
||||||
|
|
||||||
|
|
||||||
|
def _make_reachy2_camera_mock(*args, **kwargs):
|
||||||
|
cfg = args[0] if args else kwargs.get("config")
|
||||||
|
name = getattr(cfg, "name", kwargs.get("name", "cam"))
|
||||||
|
image_type = getattr(cfg, "image_type", kwargs.get("image_type", "cam"))
|
||||||
|
width = getattr(cfg, "width", kwargs.get("width", 640))
|
||||||
|
height = getattr(cfg, "height", kwargs.get("height", 480))
|
||||||
|
|
||||||
|
cam = MagicMock(name=f"Reachy2CameraMock:{name}")
|
||||||
|
cam.name = name
|
||||||
|
cam.image_type = image_type
|
||||||
|
cam.width = width
|
||||||
|
cam.height = height
|
||||||
|
cam.connect = MagicMock()
|
||||||
|
cam.disconnect = MagicMock()
|
||||||
|
cam.async_read = MagicMock(side_effect=lambda: np.zeros((height, width, 3), dtype=np.uint8))
|
||||||
|
return cam
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.fixture(params=PARAMS, ids=lambda p: "default" if not p else ",".join(p.keys()))
|
||||||
|
def reachy2(request):
|
||||||
|
with (
|
||||||
|
patch(
|
||||||
|
"lerobot.robots.reachy2.robot_reachy2.ReachySDK",
|
||||||
|
side_effect=lambda *a, **k: _make_reachy2_sdk_mock(),
|
||||||
|
),
|
||||||
|
patch(
|
||||||
|
"lerobot.cameras.reachy2_camera.reachy2_camera.Reachy2Camera",
|
||||||
|
side_effect=_make_reachy2_camera_mock,
|
||||||
|
),
|
||||||
|
):
|
||||||
|
overrides = request.param
|
||||||
|
cfg = Reachy2RobotConfig(ip_address="192.168.0.200", **overrides)
|
||||||
|
robot = Reachy2Robot(cfg)
|
||||||
|
yield robot
|
||||||
|
if robot.is_connected:
|
||||||
|
robot.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_connect_disconnect(reachy2):
|
||||||
|
assert not reachy2.is_connected
|
||||||
|
|
||||||
|
reachy2.connect()
|
||||||
|
assert reachy2.is_connected
|
||||||
|
|
||||||
|
reachy2.reachy.turn_on.assert_called_once()
|
||||||
|
reachy2.reachy.reset_default_limits.assert_called_once()
|
||||||
|
|
||||||
|
reachy2.disconnect()
|
||||||
|
assert not reachy2.is_connected
|
||||||
|
|
||||||
|
if reachy2.config.disable_torque_on_disconnect:
|
||||||
|
reachy2.reachy.turn_off_smoothly.assert_called_once()
|
||||||
|
else:
|
||||||
|
reachy2.reachy.turn_off_smoothly.assert_not_called()
|
||||||
|
reachy2.reachy.disconnect.assert_called_once()
|
||||||
|
|
||||||
|
|
||||||
|
def test_get_joints_dict(reachy2):
|
||||||
|
reachy2.connect()
|
||||||
|
|
||||||
|
if reachy2.config.with_neck:
|
||||||
|
assert "neck_yaw.pos" in reachy2.joints_dict
|
||||||
|
assert "neck_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "neck_roll.pos" in reachy2.joints_dict
|
||||||
|
else:
|
||||||
|
assert "neck_yaw.pos" not in reachy2.joints_dict
|
||||||
|
assert "neck_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "neck_roll.pos" not in reachy2.joints_dict
|
||||||
|
|
||||||
|
if reachy2.config.with_antennas:
|
||||||
|
assert "l_antenna.pos" in reachy2.joints_dict
|
||||||
|
assert "r_antenna.pos" in reachy2.joints_dict
|
||||||
|
else:
|
||||||
|
assert "l_antenna.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_antenna.pos" not in reachy2.joints_dict
|
||||||
|
|
||||||
|
if reachy2.config.with_r_arm:
|
||||||
|
assert "r_shoulder_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "r_shoulder_roll.pos" in reachy2.joints_dict
|
||||||
|
assert "r_elbow_yaw.pos" in reachy2.joints_dict
|
||||||
|
assert "r_elbow_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "r_wrist_roll.pos" in reachy2.joints_dict
|
||||||
|
assert "r_wrist_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "r_wrist_yaw.pos" in reachy2.joints_dict
|
||||||
|
assert "r_gripper.pos" in reachy2.joints_dict
|
||||||
|
else:
|
||||||
|
assert "r_shoulder_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_shoulder_roll.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_elbow_yaw.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_elbow_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_wrist_roll.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_wrist_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_wrist_yaw.pos" not in reachy2.joints_dict
|
||||||
|
assert "r_gripper.pos" not in reachy2.joints_dict
|
||||||
|
|
||||||
|
if reachy2.config.with_l_arm:
|
||||||
|
assert "l_shoulder_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "l_shoulder_roll.pos" in reachy2.joints_dict
|
||||||
|
assert "l_elbow_yaw.pos" in reachy2.joints_dict
|
||||||
|
assert "l_elbow_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "l_wrist_roll.pos" in reachy2.joints_dict
|
||||||
|
assert "l_wrist_pitch.pos" in reachy2.joints_dict
|
||||||
|
assert "l_wrist_yaw.pos" in reachy2.joints_dict
|
||||||
|
assert "l_gripper.pos" in reachy2.joints_dict
|
||||||
|
else:
|
||||||
|
assert "l_shoulder_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_shoulder_roll.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_elbow_yaw.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_elbow_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_wrist_roll.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_wrist_pitch.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_wrist_yaw.pos" not in reachy2.joints_dict
|
||||||
|
assert "l_gripper.pos" not in reachy2.joints_dict
|
||||||
|
|
||||||
|
|
||||||
|
def test_get_observation(reachy2):
|
||||||
|
reachy2.connect()
|
||||||
|
obs = reachy2.get_observation()
|
||||||
|
|
||||||
|
expected_keys = set(reachy2.joints_dict)
|
||||||
|
expected_keys.update(f"{v}" for v in REACHY2_VEL.keys() if reachy2.config.with_mobile_base)
|
||||||
|
expected_keys.update(reachy2.cameras.keys())
|
||||||
|
assert set(obs.keys()) == expected_keys
|
||||||
|
|
||||||
|
for motor in reachy2.joints_dict.keys():
|
||||||
|
assert obs[motor] == reachy2.reachy.joints[REACHY2_JOINTS[motor]].present_position
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
for vel in REACHY2_VEL.keys():
|
||||||
|
assert obs[vel] == reachy2.reachy.mobile_base.odometry[REACHY2_VEL[vel]]
|
||||||
|
if reachy2.config.with_left_teleop_camera:
|
||||||
|
assert obs["teleop_left"].shape == (
|
||||||
|
reachy2.config.cameras["teleop_left"].height,
|
||||||
|
reachy2.config.cameras["teleop_left"].width,
|
||||||
|
3,
|
||||||
|
)
|
||||||
|
if reachy2.config.with_right_teleop_camera:
|
||||||
|
assert obs["teleop_right"].shape == (
|
||||||
|
reachy2.config.cameras["teleop_right"].height,
|
||||||
|
reachy2.config.cameras["teleop_right"].width,
|
||||||
|
3,
|
||||||
|
)
|
||||||
|
if reachy2.config.with_torso_camera:
|
||||||
|
assert obs["torso_rgb"].shape == (
|
||||||
|
reachy2.config.cameras["torso_rgb"].height,
|
||||||
|
reachy2.config.cameras["torso_rgb"].width,
|
||||||
|
3,
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def test_send_action(reachy2):
|
||||||
|
reachy2.connect()
|
||||||
|
|
||||||
|
action = {k: i * 10.0 for i, k in enumerate(reachy2.joints_dict.keys(), start=1)}
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
action.update({k: i * 0.1 for i, k in enumerate(REACHY2_VEL.keys(), start=1)})
|
||||||
|
|
||||||
|
previous_present_position = {
|
||||||
|
k: reachy2.reachy.joints[REACHY2_JOINTS[k]].present_position for k in reachy2.joints_dict.keys()
|
||||||
|
}
|
||||||
|
returned = reachy2.send_action(action)
|
||||||
|
|
||||||
|
if reachy2.config.max_relative_target is None:
|
||||||
|
assert returned == action
|
||||||
|
|
||||||
|
assert reachy2.reachy._goal_position_set_total == len(reachy2.joints_dict)
|
||||||
|
for motor in reachy2.joints_dict.keys():
|
||||||
|
expected_pos = action[motor]
|
||||||
|
real_pos = reachy2.reachy.joints[REACHY2_JOINTS[motor]].goal_position
|
||||||
|
if reachy2.config.max_relative_target is None:
|
||||||
|
assert real_pos == expected_pos
|
||||||
|
else:
|
||||||
|
assert real_pos == previous_present_position[motor] + np.sign(expected_pos) * min(
|
||||||
|
abs(expected_pos - real_pos), reachy2.config.max_relative_target
|
||||||
|
)
|
||||||
|
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
goal_speed = [i * 0.1 for i, _ in enumerate(REACHY2_VEL.keys(), start=1)]
|
||||||
|
reachy2.reachy.mobile_base.set_goal_speed.assert_called_once_with(*goal_speed)
|
||||||
|
|
||||||
|
if reachy2.config.use_external_commands:
|
||||||
|
reachy2.reachy.send_goal_positions.assert_not_called()
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
reachy2.reachy.mobile_base.send_speed_command.assert_not_called()
|
||||||
|
else:
|
||||||
|
reachy2.reachy.send_goal_positions.assert_called_once()
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
reachy2.reachy.mobile_base.send_speed_command.assert_called_once()
|
||||||
|
|
||||||
|
|
||||||
|
def test_no_part_declared():
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2RobotConfig(
|
||||||
|
ip_address="192.168.0.200",
|
||||||
|
with_mobile_base=False,
|
||||||
|
with_l_arm=False,
|
||||||
|
with_r_arm=False,
|
||||||
|
with_neck=False,
|
||||||
|
with_antennas=False,
|
||||||
|
)
|
||||||
150
tests/teleoperators/test_reachy2_teleoperator.py
Normal file
150
tests/teleoperators/test_reachy2_teleoperator.py
Normal file
@@ -0,0 +1,150 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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 unittest.mock import MagicMock, patch
|
||||||
|
|
||||||
|
import pytest
|
||||||
|
|
||||||
|
from lerobot.teleoperators.reachy2_teleoperator import (
|
||||||
|
REACHY2_ANTENNAS_JOINTS,
|
||||||
|
REACHY2_L_ARM_JOINTS,
|
||||||
|
REACHY2_NECK_JOINTS,
|
||||||
|
REACHY2_R_ARM_JOINTS,
|
||||||
|
REACHY2_VEL,
|
||||||
|
Reachy2Teleoperator,
|
||||||
|
Reachy2TeleoperatorConfig,
|
||||||
|
)
|
||||||
|
|
||||||
|
# {lerobot_keys: reachy2_sdk_keys}
|
||||||
|
REACHY2_JOINTS = {
|
||||||
|
**REACHY2_NECK_JOINTS,
|
||||||
|
**REACHY2_ANTENNAS_JOINTS,
|
||||||
|
**REACHY2_R_ARM_JOINTS,
|
||||||
|
**REACHY2_L_ARM_JOINTS,
|
||||||
|
}
|
||||||
|
|
||||||
|
PARAMS = [
|
||||||
|
{}, # default config
|
||||||
|
{"with_mobile_base": False},
|
||||||
|
{"with_mobile_base": False, "with_l_arm": False, "with_antennas": False},
|
||||||
|
{"with_r_arm": False, "with_neck": False, "with_antennas": False},
|
||||||
|
{"with_mobile_base": False, "with_neck": False},
|
||||||
|
{"use_present_position": True},
|
||||||
|
]
|
||||||
|
|
||||||
|
|
||||||
|
def _make_reachy2_sdk_mock():
|
||||||
|
r = MagicMock(name="ReachySDKMock")
|
||||||
|
r.is_connected.return_value = True
|
||||||
|
|
||||||
|
def _connect():
|
||||||
|
r.is_connected.return_value = True
|
||||||
|
|
||||||
|
def _disconnect():
|
||||||
|
r.is_connected.return_value = False
|
||||||
|
|
||||||
|
# Mock joints with some dummy positions
|
||||||
|
joints = {
|
||||||
|
k: MagicMock(
|
||||||
|
present_position=float(i),
|
||||||
|
goal_position=float(i) + 0.5,
|
||||||
|
)
|
||||||
|
for i, k in enumerate(REACHY2_JOINTS.values())
|
||||||
|
}
|
||||||
|
r.joints = joints
|
||||||
|
|
||||||
|
# Mock mobile base with some dummy odometry
|
||||||
|
r.mobile_base = MagicMock()
|
||||||
|
r.mobile_base.last_cmd_vel = {
|
||||||
|
"vx": -0.2,
|
||||||
|
"vy": 0.2,
|
||||||
|
"vtheta": 11.0,
|
||||||
|
}
|
||||||
|
r.mobile_base.odometry = {
|
||||||
|
"x": 1.0,
|
||||||
|
"y": 2.0,
|
||||||
|
"theta": 20.0,
|
||||||
|
"vx": 0.1,
|
||||||
|
"vy": -0.1,
|
||||||
|
"vtheta": 8.0,
|
||||||
|
}
|
||||||
|
|
||||||
|
r.connect = MagicMock(side_effect=_connect)
|
||||||
|
r.disconnect = MagicMock(side_effect=_disconnect)
|
||||||
|
|
||||||
|
return r
|
||||||
|
|
||||||
|
|
||||||
|
@pytest.fixture(params=PARAMS, ids=lambda p: "default" if not p else ",".join(p.keys()))
|
||||||
|
def reachy2(request):
|
||||||
|
with (
|
||||||
|
patch(
|
||||||
|
"lerobot.teleoperators.reachy2_teleoperator.reachy2_teleoperator.ReachySDK",
|
||||||
|
side_effect=lambda *a, **k: _make_reachy2_sdk_mock(),
|
||||||
|
),
|
||||||
|
):
|
||||||
|
overrides = request.param
|
||||||
|
cfg = Reachy2TeleoperatorConfig(ip_address="192.168.0.200", **overrides)
|
||||||
|
robot = Reachy2Teleoperator(cfg)
|
||||||
|
yield robot
|
||||||
|
if robot.is_connected:
|
||||||
|
robot.disconnect()
|
||||||
|
|
||||||
|
|
||||||
|
def test_connect_disconnect(reachy2):
|
||||||
|
assert not reachy2.is_connected
|
||||||
|
|
||||||
|
reachy2.connect()
|
||||||
|
assert reachy2.is_connected
|
||||||
|
|
||||||
|
reachy2.disconnect()
|
||||||
|
assert not reachy2.is_connected
|
||||||
|
|
||||||
|
reachy2.reachy.disconnect.assert_called_once()
|
||||||
|
|
||||||
|
|
||||||
|
def test_get_action(reachy2):
|
||||||
|
reachy2.connect()
|
||||||
|
action = reachy2.get_action()
|
||||||
|
|
||||||
|
expected_keys = set(reachy2.joints_dict)
|
||||||
|
expected_keys.update(f"{v}" for v in REACHY2_VEL.keys() if reachy2.config.with_mobile_base)
|
||||||
|
assert set(action.keys()) == expected_keys
|
||||||
|
|
||||||
|
for motor in reachy2.joints_dict.keys():
|
||||||
|
if reachy2.config.use_present_position:
|
||||||
|
assert action[motor] == reachy2.reachy.joints[REACHY2_JOINTS[motor]].present_position
|
||||||
|
else:
|
||||||
|
assert action[motor] == reachy2.reachy.joints[REACHY2_JOINTS[motor]].goal_position
|
||||||
|
if reachy2.config.with_mobile_base:
|
||||||
|
if reachy2.config.use_present_position:
|
||||||
|
for vel in REACHY2_VEL.keys():
|
||||||
|
assert action[vel] == reachy2.reachy.mobile_base.odometry[REACHY2_VEL[vel]]
|
||||||
|
else:
|
||||||
|
for vel in REACHY2_VEL.keys():
|
||||||
|
assert action[vel] == reachy2.reachy.mobile_base.last_cmd_vel[REACHY2_VEL[vel]]
|
||||||
|
|
||||||
|
|
||||||
|
def test_no_part_declared():
|
||||||
|
with pytest.raises(ValueError):
|
||||||
|
_ = Reachy2TeleoperatorConfig(
|
||||||
|
ip_address="192.168.0.200",
|
||||||
|
with_mobile_base=False,
|
||||||
|
with_l_arm=False,
|
||||||
|
with_r_arm=False,
|
||||||
|
with_neck=False,
|
||||||
|
with_antennas=False,
|
||||||
|
)
|
||||||
Reference in New Issue
Block a user