diff --git a/README.md b/README.md
index 703e64881..b505c545d 100644
--- a/README.md
+++ b/README.md
@@ -23,15 +23,15 @@
-
Hot new tutorial: Getting started with real-world robots
+ New robot in town: SO-100
-
-
We just dropped an in-depth tutorial on how to build your own robot!
+
+
We just added a new tutorial on how to build a more affordable robot, at the price of $110 per arm!
Teach it new skills by showing it a few moves with just a laptop.
Then watch your homemade robot act autonomously 🤯
-
For more info, see our thread on X or our tutorial page.
+
Follow the link to the full tutorial for SO-100.
diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md
new file mode 100644
index 000000000..ffadb1f3e
--- /dev/null
+++ b/examples/10_use_so100.md
@@ -0,0 +1,280 @@
+This tutorial explains how to use [SO-100](https://github.com/TheRobotStudio/SO-ARM100) with LeRobot.
+
+## Source the parts
+
+Follow this [README](https://github.com/TheRobotStudio/SO-ARM100). It contains the bill of materials, with link to source the parts, as well as the instructions to 3D print the parts, and advices if it's your first time printing or if you don't own a 3D printer already.
+
+**Important**: Before assembling, you will first need to configure your motors. To this end, we provide a nice script, so let's first install LeRobot. After configuration, we will also guide you through assembly.
+
+## Install LeRobot
+
+On your computer:
+
+1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install):
+```bash
+mkdir -p ~/miniconda3
+wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh
+bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3
+rm ~/miniconda3/miniconda.sh
+~/miniconda3/bin/conda init bash
+```
+
+2. Restart shell or `source ~/.bashrc`
+
+3. Create and activate a fresh conda environment for lerobot
+```bash
+conda create -y -n lerobot python=3.10 && conda activate lerobot
+```
+
+4. Clone LeRobot:
+```bash
+git clone https://github.com/huggingface/lerobot.git ~/lerobot
+```
+
+5. Install LeRobot with dependencies for the feetech motors:
+```bash
+cd ~/lerobot && pip install -e ".[feetech]"
+```
+
+For Linux only (not Mac), install extra dependencies for recording datasets:
+```bash
+conda install -y -c conda-forge ffmpeg
+pip uninstall -y opencv-python
+conda install -y -c conda-forge "opencv>=4.10.0"
+```
+
+## Configure the motors
+
+Follow steps 1 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the use of our scripts below.
+
+**Find USB ports associated to your arms**
+To find the correct ports for each arm, run the utility script twice:
+```bash
+python lerobot/scripts/find_motors_bus_port.py
+```
+
+Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux):
+```
+Finding all available ports for the MotorBus.
+['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
+
+[...Disconnect leader arm and press Enter...]
+
+The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751
+Reconnect the usb cable.
+```
+
+Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux):
+```
+Finding all available ports for the MotorBus.
+['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
+
+[...Disconnect follower arm and press Enter...]
+
+The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0032081
+Reconnect the usb cable.
+```
+
+Troubleshooting: On Linux, you might need to give access to the USB ports by running:
+```bash
+sudo chmod 666 /dev/ttyACM0
+sudo chmod 666 /dev/ttyACM1
+```
+
+**Configure your motors**
+Plug your first motor and run this script to set its ID to 1. It will also set its present position to 2048, so expect your motor to rotate:
+```bash
+python lerobot/scripts/configure_motor.py \
+ --port /dev/tty.usbmodem58760432961 \
+ --brand feetech \
+ --model sts3215 \
+ --baudrate 1000000 \
+ --ID 1
+```
+
+Note: These motors are currently limitated. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees).
+
+Then unplug your motor and plug the second motor and set its ID to 2.
+```bash
+python lerobot/scripts/configure_motor.py \
+ --port /dev/tty.usbmodem58760432961 \
+ --brand feetech \
+ --model sts3215 \
+ --baudrate 1000000 \
+ --ID 2
+```
+
+Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm.
+
+**Remove the gears of the 6 leader motors**
+Follow step 2 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). You need to remove the gear for the motors of the leader arm. As a result, you will only use the position encoding of the motor and reduce friction to more easily operate the leader arm.
+
+**Add motor horn to the motors**
+Follow step 3 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). For SO-100, you need to align the holes on the motor horn to the motor spline to be approximately 1:30, 4:30, 7:30 and 10:30.
+Try to avoid rotating the motor while doing so to keep position 2048 set during configuration. It is especially tricky for the leader motors as it is more sensible without the gears, but it's ok if it's a bit rotated.
+
+## Assemble the arms
+
+Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). The first arm should take a bit more than 1 hour to assemble, but once you get use to it, you can do it under 1 hour for the second arm.
+
+## Calibrate
+
+Next, you'll need to calibrate your SO-100 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one SO-100 robot to work on another.
+
+**Auto-calibration of follower arm**
+Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position:
+
+
+
+
+
+Then run this script to launch auto-calibration:
+```bash
+python lerobot/scripts/control_robot.py calibrate \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --robot-overrides '~cameras' --arms main_follower
+```
+
+Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm.
+
+**Manual calibration of leader arm**
+Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially:
+
+| 1. Zero position | 2. Rotated position | 3. Rest position |
+|---|---|---|
+| | | |
+
+Run this script to launch manual calibration:
+```bash
+python lerobot/scripts/control_robot.py calibrate \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --robot-overrides '~cameras' --arms main_leader
+```
+
+## Teleoperate
+
+**Simple teleop**
+Then you are ready to teleoperate your robot! Run this simple script (it won't connect and display the cameras):
+```bash
+python lerobot/scripts/control_robot.py teleoperate \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --robot-overrides '~cameras' \
+ --display-cameras 0
+```
+
+
+**Teleop with displaying cameras**
+Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset.
+```bash
+python lerobot/scripts/control_robot.py teleoperate \
+ --robot-path lerobot/configs/robot/so100.yaml
+```
+
+## Record a dataset
+
+Once you're familiar with teleoperation, you can record your first dataset with SO-100.
+
+If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens):
+```bash
+huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential
+```
+
+Store your Hugging Face repository name in a variable to run these commands:
+```bash
+HF_USER=$(huggingface-cli whoami | head -n 1)
+echo $HF_USER
+```
+
+Record 2 episodes and upload your dataset to the hub:
+```bash
+python lerobot/scripts/control_robot.py record \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/so100_test \
+ --tags so100 tutorial \
+ --warmup-time-s 5 \
+ --episode-time-s 40 \
+ --reset-time-s 10 \
+ --num-episodes 2 \
+ --push-to-hub 1
+```
+
+## Visualize a dataset
+
+If you uploaded your dataset to the hub with `--push-to-hub 1`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by:
+```bash
+echo ${HF_USER}/so100_test
+```
+
+If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with:
+```bash
+python lerobot/scripts/visualize_dataset_html.py \
+ --root data \
+ --repo-id ${HF_USER}/so100_test
+```
+
+## Replay an episode
+
+Now try to replay the first episode on your robot:
+```bash
+DATA_DIR=data python lerobot/scripts/control_robot.py replay \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/so100_test \
+ --episode 0
+```
+
+## Train a policy
+
+To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command:
+```bash
+DATA_DIR=data python lerobot/scripts/train.py \
+ dataset_repo_id=${HF_USER}/so100_test \
+ policy=act_so100_real \
+ env=so100_real \
+ hydra.run.dir=outputs/train/act_so100_test \
+ hydra.job.name=act_so100_test \
+ device=cuda \
+ wandb.enable=true
+```
+
+Let's explain it:
+1. We provided the dataset as argument with `dataset_repo_id=${HF_USER}/so100_test`.
+2. We provided the policy with `policy=act_so100_real`. This loads configurations from [`lerobot/configs/policy/act_so100_real.yaml`](../lerobot/configs/policy/act_so100_real.yaml). Importantly, this policy uses 2 cameras as input `laptop`, `phone`.
+3. We provided an environment as argument with `env=so100_real`. This loads configurations from [`lerobot/configs/env/so100_real.yaml`](../lerobot/configs/env/so100_real.yaml).
+4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise.
+5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`.
+6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync.
+
+Training should take several hours. You will find checkpoints in `outputs/train/act_so100_test/checkpoints`.
+
+## Evaluate your policy
+
+You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes:
+```bash
+python lerobot/scripts/control_robot.py record \
+ --robot-path lerobot/configs/robot/so100.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/eval_act_so100_test \
+ --tags so100 tutorial eval \
+ --warmup-time-s 5 \
+ --episode-time-s 40 \
+ --reset-time-s 10 \
+ --num-episodes 10 \
+ -p outputs/train/act_so100_test/checkpoints/last/pretrained_model
+```
+
+As you can see, it's almost the same command as previously used to record your training dataset. Two things changed:
+1. There is an additional `-p` argument which indicates the path to your policy checkpoint with (e.g. `-p outputs/train/eval_so100_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `-p ${HF_USER}/act_so100_test`).
+2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_so100_test`).
+
+## More
+
+Follow this [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) for a more in-depth tutorial on controlling real robots with LeRobot.
+
+If you have any question or need help, please reach out on Discord in the channel [`#so100-arm`](https://discord.com/channels/1216765309076115607/1237741463832363039).
diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md
new file mode 100644
index 000000000..4286fb8bc
--- /dev/null
+++ b/examples/11_use_moss.md
@@ -0,0 +1,280 @@
+This tutorial explains how to use [Moss v1](https://github.com/jess-moss/moss-robot-arms) with LeRobot.
+
+## Source the parts
+
+Follow this [README](https://github.com/jess-moss/moss-robot-arms). It contains the bill of materials, with link to source the parts, as well as the instructions to 3D print the parts, and advices if it's your first time printing or if you don't own a 3D printer already.
+
+**Important**: Before assembling, you will first need to configure your motors. To this end, we provide a nice script, so let's first install LeRobot. After configuration, we will also guide you through assembly.
+
+## Install LeRobot
+
+On your computer:
+
+1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install):
+```bash
+mkdir -p ~/miniconda3
+wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh
+bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3
+rm ~/miniconda3/miniconda.sh
+~/miniconda3/bin/conda init bash
+```
+
+2. Restart shell or `source ~/.bashrc`
+
+3. Create and activate a fresh conda environment for lerobot
+```bash
+conda create -y -n lerobot python=3.10 && conda activate lerobot
+```
+
+4. Clone LeRobot:
+```bash
+git clone https://github.com/huggingface/lerobot.git ~/lerobot
+```
+
+5. Install LeRobot with dependencies for the feetech motors:
+```bash
+cd ~/lerobot && pip install -e ".[feetech]"
+```
+
+For Linux only (not Mac), install extra dependencies for recording datasets:
+```bash
+conda install -y -c conda-forge ffmpeg
+pip uninstall -y opencv-python
+conda install -y -c conda-forge "opencv>=4.10.0"
+```
+
+## Configure the motors
+
+Follow steps 1 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the use of our scripts below.
+
+**Find USB ports associated to your arms**
+To find the correct ports for each arm, run the utility script twice:
+```bash
+python lerobot/scripts/find_motors_bus_port.py
+```
+
+Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux):
+```
+Finding all available ports for the MotorBus.
+['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
+
+[...Disconnect leader arm and press Enter...]
+
+The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751
+Reconnect the usb cable.
+```
+
+Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux):
+```
+Finding all available ports for the MotorBus.
+['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
+
+[...Disconnect follower arm and press Enter...]
+
+The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0032081
+Reconnect the usb cable.
+```
+
+Troubleshooting: On Linux, you might need to give access to the USB ports by running:
+```bash
+sudo chmod 666 /dev/ttyACM0
+sudo chmod 666 /dev/ttyACM1
+```
+
+**Configure your motors**
+Plug your first motor and run this script to set its ID to 1. It will also set its present position to 2048, so expect your motor to rotate:
+```bash
+python lerobot/scripts/configure_motor.py \
+ --port /dev/tty.usbmodem58760432961 \
+ --brand feetech \
+ --model sts3215 \
+ --baudrate 1000000 \
+ --ID 1
+```
+
+Note: These motors are currently limitated. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees).
+
+Then unplug your motor and plug the second motor and set its ID to 2.
+```bash
+python lerobot/scripts/configure_motor.py \
+ --port /dev/tty.usbmodem58760432961 \
+ --brand feetech \
+ --model sts3215 \
+ --baudrate 1000000 \
+ --ID 2
+```
+
+Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm.
+
+**Remove the gears of the 6 leader motors**
+Follow step 2 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). You need to remove the gear for the motors of the leader arm. As a result, you will only use the position encoding of the motor and reduce friction to more easily operate the leader arm.
+
+**Add motor horn to the motors**
+Follow step 3 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). For Moss v1, you need to align the holes on the motor horn to the motor spline to be approximately 3, 6, 9 and 12 o'clock.
+Try to avoid rotating the motor while doing so to keep position 2048 set during configuration. It is especially tricky for the leader motors as it is more sensible without the gears, but it's ok if it's a bit rotated.
+
+## Assemble the arms
+
+Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). The first arm should take a bit more than 1 hour to assemble, but once you get use to it, you can do it under 1 hour for the second arm.
+
+## Calibrate
+
+Next, you'll need to calibrate your Moss v1 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one Moss v1 robot to work on another.
+
+**Auto-calibration of follower arm**
+Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position:
+
+
+
+
+
+Then run this script to launch auto-calibration:
+```bash
+python lerobot/scripts/control_robot.py calibrate \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --robot-overrides '~cameras' --arms main_follower
+```
+
+Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm.
+
+**Manual calibration of leader arm**
+Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially:
+
+| 1. Zero position | 2. Rotated position | 3. Rest position |
+|---|---|---|
+| | | |
+
+Run this script to launch manual calibration:
+```bash
+python lerobot/scripts/control_robot.py calibrate \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --robot-overrides '~cameras' --arms main_leader
+```
+
+## Teleoperate
+
+**Simple teleop**
+Then you are ready to teleoperate your robot! Run this simple script (it won't connect and display the cameras):
+```bash
+python lerobot/scripts/control_robot.py teleoperate \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --robot-overrides '~cameras' \
+ --display-cameras 0
+```
+
+
+**Teleop with displaying cameras**
+Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset.
+```bash
+python lerobot/scripts/control_robot.py teleoperate \
+ --robot-path lerobot/configs/robot/moss.yaml
+```
+
+## Record a dataset
+
+Once you're familiar with teleoperation, you can record your first dataset with Moss v1.
+
+If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens):
+```bash
+huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential
+```
+
+Store your Hugging Face repository name in a variable to run these commands:
+```bash
+HF_USER=$(huggingface-cli whoami | head -n 1)
+echo $HF_USER
+```
+
+Record 2 episodes and upload your dataset to the hub:
+```bash
+python lerobot/scripts/control_robot.py record \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/moss_test \
+ --tags moss tutorial \
+ --warmup-time-s 5 \
+ --episode-time-s 40 \
+ --reset-time-s 10 \
+ --num-episodes 2 \
+ --push-to-hub 1
+```
+
+## Visualize a dataset
+
+If you uploaded your dataset to the hub with `--push-to-hub 1`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by:
+```bash
+echo ${HF_USER}/moss_test
+```
+
+If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with:
+```bash
+python lerobot/scripts/visualize_dataset_html.py \
+ --root data \
+ --repo-id ${HF_USER}/moss_test
+```
+
+## Replay an episode
+
+Now try to replay the first episode on your robot:
+```bash
+DATA_DIR=data python lerobot/scripts/control_robot.py replay \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/moss_test \
+ --episode 0
+```
+
+## Train a policy
+
+To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command:
+```bash
+DATA_DIR=data python lerobot/scripts/train.py \
+ dataset_repo_id=${HF_USER}/moss_test \
+ policy=act_moss_real \
+ env=moss_real \
+ hydra.run.dir=outputs/train/act_moss_test \
+ hydra.job.name=act_moss_test \
+ device=cuda \
+ wandb.enable=true
+```
+
+Let's explain it:
+1. We provided the dataset as argument with `dataset_repo_id=${HF_USER}/moss_test`.
+2. We provided the policy with `policy=act_moss_real`. This loads configurations from [`lerobot/configs/policy/act_moss_real.yaml`](../lerobot/configs/policy/act_moss_real.yaml). Importantly, this policy uses 2 cameras as input `laptop`, `phone`.
+3. We provided an environment as argument with `env=moss_real`. This loads configurations from [`lerobot/configs/env/moss_real.yaml`](../lerobot/configs/env/moss_real.yaml).
+4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise.
+5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`.
+6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync.
+
+Training should take several hours. You will find checkpoints in `outputs/train/act_moss_test/checkpoints`.
+
+## Evaluate your policy
+
+You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes:
+```bash
+python lerobot/scripts/control_robot.py record \
+ --robot-path lerobot/configs/robot/moss.yaml \
+ --fps 30 \
+ --root data \
+ --repo-id ${HF_USER}/eval_act_moss_test \
+ --tags moss tutorial eval \
+ --warmup-time-s 5 \
+ --episode-time-s 40 \
+ --reset-time-s 10 \
+ --num-episodes 10 \
+ -p outputs/train/act_moss_test/checkpoints/last/pretrained_model
+```
+
+As you can see, it's almost the same command as previously used to record your training dataset. Two things changed:
+1. There is an additional `-p` argument which indicates the path to your policy checkpoint with (e.g. `-p outputs/train/eval_moss_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `-p ${HF_USER}/act_moss_test`).
+2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_moss_test`).
+
+## More
+
+Follow this [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) for a more in-depth tutorial on controlling real robots with LeRobot.
+
+If you have any question or need help, please reach out on Discord in the channel [`#moss-arm`](https://discord.com/channels/1216765309076115607/1275374638985252925).
diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md
index 266e4f0da..9db7e2521 100644
--- a/examples/7_get_started_with_real_robot.md
+++ b/examples/7_get_started_with_real_robot.md
@@ -78,12 +78,12 @@ To begin, create two instances of the [`DynamixelMotorsBus`](../lerobot/common/
To find the correct ports for each arm, run the utility script twice:
```bash
-python lerobot/common/robot_devices/motors/dynamixel.py
+python lerobot/scripts/find_motors_bus_port.py
```
Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux):
```
-Finding all available ports for the DynamixelMotorsBus.
+Finding all available ports for the MotorBus.
['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
@@ -95,7 +95,7 @@ Reconnect the usb cable.
Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux):
```
-Finding all available ports for the DynamixelMotorsBus.
+Finding all available ports for the MotorBus.
['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md
index fcd1cacee..97caf2ba8 100644
--- a/examples/8_use_stretch.md
+++ b/examples/8_use_stretch.md
@@ -50,7 +50,7 @@ cd ~/lerobot && pip install -e ".[stretch]"
> **Note:** If you get this message, you can ignore it: `ERROR: pip's dependency resolver does not currently take into account all the packages that are installed.`
-And install extra dependencies for recording datasets on Linux:
+For Linux only (not Mac), install extra dependencies for recording datasets:
```bash
conda install -y -c conda-forge ffmpeg
pip uninstall -y opencv-python
diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md
index d161978fd..cf5e1ceca 100644
--- a/examples/9_use_aloha.md
+++ b/examples/9_use_aloha.md
@@ -35,7 +35,7 @@ git clone https://github.com/huggingface/lerobot.git ~/lerobot
cd ~/lerobot && pip install -e ".[dynamixel, intelrealsense]"
```
-And install extra dependencies for recording datasets on Linux:
+For Linux only (not Mac), install extra dependencies for recording datasets:
```bash
conda install -y -c conda-forge ffmpeg
pip uninstall -y opencv-python
diff --git a/lerobot/__init__.py b/lerobot/__init__.py
index 5acd8aaad..d462c7337 100644
--- a/lerobot/__init__.py
+++ b/lerobot/__init__.py
@@ -198,6 +198,8 @@
"koch",
"koch_bimanual",
"aloha",
+ "so100",
+ "moss",
]
# lists all available cameras from `lerobot/common/robot_devices/cameras`
@@ -209,6 +211,7 @@
# lists all available motors from `lerobot/common/robot_devices/motors`
available_motors = [
"dynamixel",
+ "feetech",
]
# keys and values refer to yaml files
diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py
index 66c7fe5cb..479694277 100644
--- a/lerobot/common/robot_devices/cameras/intelrealsense.py
+++ b/lerobot/common/robot_devices/cameras/intelrealsense.py
@@ -21,9 +21,9 @@
from lerobot.common.robot_devices.utils import (
RobotDeviceAlreadyConnectedError,
RobotDeviceNotConnectedError,
+ busy_wait,
)
from lerobot.common.utils.utils import capture_timestamp_utc
-from lerobot.scripts.control_robot import busy_wait
SERIAL_NUMBER_INDEX = 1
diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py
index 815b4986a..1e1396f76 100644
--- a/lerobot/common/robot_devices/motors/dynamixel.py
+++ b/lerobot/common/robot_devices/motors/dynamixel.py
@@ -4,7 +4,6 @@
import time
import traceback
from copy import deepcopy
-from pathlib import Path
import numpy as np
import tqdm
@@ -229,35 +228,6 @@ def assert_same_address(model_ctrl_table, motor_models, data_name):
)
-def find_available_ports():
- ports = []
- for path in Path("/dev").glob("tty*"):
- ports.append(str(path))
- return ports
-
-
-def find_port():
- print("Finding all available ports for the DynamixelMotorsBus.")
- ports_before = find_available_ports()
- print(ports_before)
-
- print("Remove the usb cable from your DynamixelMotorsBus and press Enter when done.")
- input()
-
- time.sleep(0.5)
- ports_after = find_available_ports()
- ports_diff = list(set(ports_before) - set(ports_after))
-
- if len(ports_diff) == 1:
- port = ports_diff[0]
- print(f"The port of this DynamixelMotorsBus is '{port}'")
- print("Reconnect the usb cable.")
- elif len(ports_diff) == 0:
- raise OSError(f"Could not detect the port. No difference was found ({ports_diff}).")
- else:
- raise OSError(f"Could not detect the port. More than one port was found ({ports_diff}).")
-
-
class TorqueMode(enum.Enum):
ENABLED = 1
DISABLED = 0
@@ -290,8 +260,8 @@ class DynamixelMotorsBus:
A DynamixelMotorsBus instance requires a port (e.g. `DynamixelMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
To find the port, you can run our utility script:
```bash
- python lerobot/common/robot_devices/motors/dynamixel.py
- >>> Finding all available ports for the DynamixelMotorsBus.
+ python lerobot/scripts/find_motors_bus_port.py
+ >>> Finding all available ports for the MotorBus.
>>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
>>> Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
>>> The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751.
@@ -369,7 +339,7 @@ def connect(self):
except Exception:
traceback.print_exc()
print(
- "\nTry running `python lerobot/common/robot_devices/motors/dynamixel.py` to make sure you are using the correct port.\n"
+ "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
)
raise
@@ -378,20 +348,6 @@ def connect(self):
self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
- # Set expected baudrate for the bus
- self.set_bus_baudrate(BAUDRATE)
-
- if not self.are_motors_configured():
- input(
- "\n/!\\ A configuration issue has been detected with your motors: \n"
- "If it's the first time that you use these motors, press enter to configure your motors... but before "
- "verify that all the cables are connected the proper way. If you find an issue, before making a modification, "
- "kill the python process, unplug the power cord to not damage the motors, rewire correctly, then plug the power "
- "again and relaunch the script.\n"
- )
- print()
- self.configure_motors()
-
def reconnect(self):
if self.mock:
import tests.mock_dynamixel_sdk as dxl
@@ -415,120 +371,14 @@ def are_motors_configured(self):
print(e)
return False
- def configure_motors(self):
- # TODO(rcadene): This script assumes motors follow the X_SERIES baudrates
- # TODO(rcadene): Refactor this function with intermediate high-level functions
-
- print("Scanning all baudrates and motor indices")
- all_baudrates = set(X_SERIES_BAUDRATE_TABLE.values())
- ids_per_baudrate = {}
- for baudrate in all_baudrates:
- self.set_bus_baudrate(baudrate)
- present_ids = self.find_motor_indices()
- if len(present_ids) > 0:
- ids_per_baudrate[baudrate] = present_ids
- print(f"Motor indices detected: {ids_per_baudrate}")
- print()
-
- possible_baudrates = list(ids_per_baudrate.keys())
- possible_ids = list({idx for sublist in ids_per_baudrate.values() for idx in sublist})
- untaken_ids = list(set(range(MAX_ID_RANGE)) - set(possible_ids) - set(self.motor_indices))
-
- # Connect successively one motor to the chain and write a unique random index for each
- for i in range(len(self.motors)):
- self.disconnect()
- input(
- "1. Unplug the power cord\n"
- "2. Plug/unplug minimal number of cables to only have the first "
- f"{i+1} motor(s) ({self.motor_names[:i+1]}) connected.\n"
- "3. Re-plug the power cord\n"
- "Press Enter to continue..."
- )
- print()
- self.reconnect()
-
- if i > 0:
- try:
- self._read_with_motor_ids(self.motor_models, untaken_ids[:i], "ID")
- except ConnectionError:
- print(f"Failed to read from {untaken_ids[:i+1]}. Make sure the power cord is plugged in.")
- input("Press Enter to continue...")
- print()
- self.reconnect()
-
- print("Scanning possible baudrates and motor indices")
- motor_found = False
- for baudrate in possible_baudrates:
- self.set_bus_baudrate(baudrate)
- present_ids = self.find_motor_indices(possible_ids)
- if len(present_ids) == 1:
- present_idx = present_ids[0]
- print(f"Detected motor with index {present_idx}")
-
- if baudrate != BAUDRATE:
- print(f"Setting its baudrate to {BAUDRATE}")
- baudrate_idx = list(X_SERIES_BAUDRATE_TABLE.values()).index(BAUDRATE)
-
- # The write can fail, so we allow retries
- for _ in range(NUM_WRITE_RETRY):
- self._write_with_motor_ids(
- self.motor_models, present_idx, "Baud_Rate", baudrate_idx
- )
- time.sleep(0.5)
- self.set_bus_baudrate(BAUDRATE)
- try:
- present_baudrate_idx = self._read_with_motor_ids(
- self.motor_models, present_idx, "Baud_Rate"
- )
- except ConnectionError:
- print("Failed to write baudrate. Retrying.")
- self.set_bus_baudrate(baudrate)
- continue
- break
- else:
- raise
-
- if present_baudrate_idx != baudrate_idx:
- raise OSError("Failed to write baudrate.")
-
- print(f"Setting its index to a temporary untaken index ({untaken_ids[i]})")
- self._write_with_motor_ids(self.motor_models, present_idx, "ID", untaken_ids[i])
-
- present_idx = self._read_with_motor_ids(self.motor_models, untaken_ids[i], "ID")
- if present_idx != untaken_ids[i]:
- raise OSError("Failed to write index.")
-
- motor_found = True
- break
- elif len(present_ids) > 1:
- raise OSError(f"More than one motor detected ({present_ids}), but only one was expected.")
-
- if not motor_found:
- raise OSError(
- "No motor found, but one new motor expected. Verify power cord is plugged in and retry."
- )
- print()
-
- print(f"Setting expected motor indices: {self.motor_indices}")
- self.set_bus_baudrate(BAUDRATE)
- self._write_with_motor_ids(
- self.motor_models, untaken_ids[: len(self.motors)], "ID", self.motor_indices
- )
- print()
-
- if (self.read("ID") != self.motor_indices).any():
- raise OSError("Failed to write motors indices.")
-
- print("Configuration is done!")
-
- def find_motor_indices(self, possible_ids=None):
+ def find_motor_indices(self, possible_ids=None, num_retry=2):
if possible_ids is None:
possible_ids = range(MAX_ID_RANGE)
indices = []
for idx in tqdm.tqdm(possible_ids):
try:
- present_idx = self._read_with_motor_ids(self.motor_models, [idx], "ID")[0]
+ present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
except ConnectionError:
continue
@@ -788,7 +638,7 @@ def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] |
values = np.round(values).astype(np.int32)
return values
- def _read_with_motor_ids(self, motor_models, motor_ids, data_name):
+ def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
if self.mock:
import tests.mock_dynamixel_sdk as dxl
else:
@@ -805,7 +655,11 @@ def _read_with_motor_ids(self, motor_models, motor_ids, data_name):
for idx in motor_ids:
group.addParam(idx)
- comm = group.txRxPacket()
+ for _ in range(num_retry):
+ comm = group.txRxPacket()
+ if comm == dxl.COMM_SUCCESS:
+ break
+
if comm != dxl.COMM_SUCCESS:
raise ConnectionError(
f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
@@ -895,7 +749,7 @@ def read(self, data_name, motor_names: str | list[str] | None = None):
return values
- def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values):
+ def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
if self.mock:
import tests.mock_dynamixel_sdk as dxl
else:
@@ -913,7 +767,11 @@ def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values):
data = convert_to_bytes(value, bytes, self.mock)
group.addParam(idx, data)
- comm = group.txPacket()
+ for _ in range(num_retry):
+ comm = group.txPacket()
+ if comm == dxl.COMM_SUCCESS:
+ break
+
if comm != dxl.COMM_SUCCESS:
raise ConnectionError(
f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
@@ -1007,8 +865,3 @@ def disconnect(self):
def __del__(self):
if getattr(self, "is_connected", False):
self.disconnect()
-
-
-if __name__ == "__main__":
- # Helper to find the usb port associated to all your DynamixelMotorsBus.
- find_port()
diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/robot_devices/motors/feetech.py
new file mode 100644
index 000000000..0d5480f7a
--- /dev/null
+++ b/lerobot/common/robot_devices/motors/feetech.py
@@ -0,0 +1,887 @@
+import enum
+import logging
+import math
+import time
+import traceback
+from copy import deepcopy
+
+import numpy as np
+import tqdm
+
+from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
+from lerobot.common.utils.utils import capture_timestamp_utc
+
+PROTOCOL_VERSION = 0
+BAUDRATE = 1_000_000
+TIMEOUT_MS = 1000
+
+MAX_ID_RANGE = 252
+
+# The following bounds define the lower and upper joints range (after calibration).
+# For joints in degree (i.e. revolute joints), their nominal range is [-180, 180] degrees
+# which corresponds to a half rotation on the left and half rotation on the right.
+# Some joints might require higher range, so we allow up to [-270, 270] degrees until
+# an error is raised.
+LOWER_BOUND_DEGREE = -270
+UPPER_BOUND_DEGREE = 270
+# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper),
+# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully
+# closed, and 100% is fully open. To account for slight calibration issue, we allow up to
+# [-10, 110] until an error is raised.
+LOWER_BOUND_LINEAR = -10
+UPPER_BOUND_LINEAR = 110
+
+HALF_TURN_DEGREE = 180
+
+
+# See this link for STS3215 Memory Table:
+# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
+# data_name: (address, size_byte)
+SCS_SERIES_CONTROL_TABLE = {
+ "Model": (3, 2),
+ "ID": (5, 1),
+ "Baud_Rate": (6, 1),
+ "Return_Delay": (7, 1),
+ "Response_Status_Level": (8, 1),
+ "Min_Angle_Limit": (9, 2),
+ "Max_Angle_Limit": (11, 2),
+ "Max_Temperature_Limit": (13, 1),
+ "Max_Voltage_Limit": (14, 1),
+ "Min_Voltage_Limit": (15, 1),
+ "Max_Torque_Limit": (16, 2),
+ "Phase": (18, 1),
+ "Unloading_Condition": (19, 1),
+ "LED_Alarm_Condition": (20, 1),
+ "P_Coefficient": (21, 1),
+ "D_Coefficient": (22, 1),
+ "I_Coefficient": (23, 1),
+ "Minimum_Startup_Force": (24, 2),
+ "CW_Dead_Zone": (26, 1),
+ "CCW_Dead_Zone": (27, 1),
+ "Protection_Current": (28, 2),
+ "Angular_Resolution": (30, 1),
+ "Offset": (31, 2),
+ "Mode": (33, 1),
+ "Protective_Torque": (34, 1),
+ "Protection_Time": (35, 1),
+ "Overload_Torque": (36, 1),
+ "Speed_closed_loop_P_proportional_coefficient": (37, 1),
+ "Over_Current_Protection_Time": (38, 1),
+ "Velocity_closed_loop_I_integral_coefficient": (39, 1),
+ "Torque_Enable": (40, 1),
+ "Acceleration": (41, 1),
+ "Goal_Position": (42, 2),
+ "Goal_Time": (44, 2),
+ "Goal_Speed": (46, 2),
+ "Torque_Limit": (48, 2),
+ "Lock": (55, 1),
+ "Present_Position": (56, 2),
+ "Present_Speed": (58, 2),
+ "Present_Load": (60, 2),
+ "Present_Voltage": (62, 1),
+ "Present_Temperature": (63, 1),
+ "Status": (65, 1),
+ "Moving": (66, 1),
+ "Present_Current": (69, 2),
+ # Not in the Memory Table
+ "Maximum_Acceleration": (85, 2),
+}
+
+SCS_SERIES_BAUDRATE_TABLE = {
+ 0: 1_000_000,
+ 1: 500_000,
+ 2: 250_000,
+ 3: 128_000,
+ 4: 115_200,
+ 5: 57_600,
+ 6: 38_400,
+ 7: 19_200,
+}
+
+CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
+CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
+
+
+MODEL_CONTROL_TABLE = {
+ "scs_series": SCS_SERIES_CONTROL_TABLE,
+ "sts3215": SCS_SERIES_CONTROL_TABLE,
+}
+
+MODEL_RESOLUTION = {
+ "scs_series": 4096,
+ "sts3215": 4096,
+}
+
+MODEL_BAUDRATE_TABLE = {
+ "scs_series": SCS_SERIES_BAUDRATE_TABLE,
+ "sts3215": SCS_SERIES_BAUDRATE_TABLE,
+}
+
+# High number of retries is needed for feetech compared to dynamixel motors.
+NUM_READ_RETRY = 20
+NUM_WRITE_RETRY = 20
+
+
+def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
+ """This function converts the degree range to the step range for indicating motors rotation.
+ It assumes a motor achieves a full rotation by going from -180 degree position to +180.
+ The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation.
+ """
+ resolutions = [MODEL_RESOLUTION[model] for model in models]
+ steps = degrees / 180 * np.array(resolutions) / 2
+ steps = steps.astype(int)
+ return steps
+
+
+def convert_to_bytes(value, bytes, mock=False):
+ if mock:
+ return value
+
+ import scservo_sdk as scs
+
+ # Note: No need to convert back into unsigned int, since this byte preprocessing
+ # already handles it for us.
+ if bytes == 1:
+ data = [
+ scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+ ]
+ elif bytes == 2:
+ data = [
+ scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+ scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
+ ]
+ elif bytes == 4:
+ data = [
+ scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+ scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
+ scs.SCS_LOBYTE(scs.SCS_HIWORD(value)),
+ scs.SCS_HIBYTE(scs.SCS_HIWORD(value)),
+ ]
+ else:
+ raise NotImplementedError(
+ f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
+ f"{bytes} is provided instead."
+ )
+ return data
+
+
+def get_group_sync_key(data_name, motor_names):
+ group_key = f"{data_name}_" + "_".join(motor_names)
+ return group_key
+
+
+def get_result_name(fn_name, data_name, motor_names):
+ group_key = get_group_sync_key(data_name, motor_names)
+ rslt_name = f"{fn_name}_{group_key}"
+ return rslt_name
+
+
+def get_queue_name(fn_name, data_name, motor_names):
+ group_key = get_group_sync_key(data_name, motor_names)
+ queue_name = f"{fn_name}_{group_key}"
+ return queue_name
+
+
+def get_log_name(var_name, fn_name, data_name, motor_names):
+ group_key = get_group_sync_key(data_name, motor_names)
+ log_name = f"{var_name}_{fn_name}_{group_key}"
+ return log_name
+
+
+def assert_same_address(model_ctrl_table, motor_models, data_name):
+ all_addr = []
+ all_bytes = []
+ for model in motor_models:
+ addr, bytes = model_ctrl_table[model][data_name]
+ all_addr.append(addr)
+ all_bytes.append(bytes)
+
+ if len(set(all_addr)) != 1:
+ raise NotImplementedError(
+ f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
+ )
+
+ if len(set(all_bytes)) != 1:
+ raise NotImplementedError(
+ f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
+ )
+
+
+class TorqueMode(enum.Enum):
+ ENABLED = 1
+ DISABLED = 0
+
+
+class DriveMode(enum.Enum):
+ NON_INVERTED = 0
+ INVERTED = 1
+
+
+class CalibrationMode(enum.Enum):
+ # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
+ DEGREE = 0
+ # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100]
+ LINEAR = 1
+
+
+class JointOutOfRangeError(Exception):
+ def __init__(self, message="Joint is out of range"):
+ self.message = message
+ super().__init__(self.message)
+
+
+class FeetechMotorsBus:
+ """
+ The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on
+ the python feetech sdk to communicate with the motors. For more info, see the [feetech SDK Documentation](https://emanual.robotis.com/docs/en/software/feetech/feetech_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
+
+ A FeetechMotorsBus instance requires a port (e.g. `FeetechMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
+ To find the port, you can run our utility script:
+ ```bash
+ python lerobot/scripts/find_motors_bus_port.py
+ >>> Finding all available ports for the MotorsBus.
+ >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+ >>> Remove the usb cable from your FeetechMotorsBus and press Enter when done.
+ >>> The port of this FeetechMotorsBus is /dev/tty.usbmodem575E0031751.
+ >>> Reconnect the usb cable.
+ ```
+
+ Example of usage for 1 motor connected to the bus:
+ ```python
+ motor_name = "gripper"
+ motor_index = 6
+ motor_model = "sts3215"
+
+ motors_bus = FeetechMotorsBus(
+ port="/dev/tty.usbmodem575E0031751",
+ motors={motor_name: (motor_index, motor_model)},
+ )
+ motors_bus.connect()
+
+ position = motors_bus.read("Present_Position")
+
+ # move from a few motor steps as an example
+ few_steps = 30
+ motors_bus.write("Goal_Position", position + few_steps)
+
+ # when done, consider disconnecting
+ motors_bus.disconnect()
+ ```
+ """
+
+ def __init__(
+ self,
+ port: str,
+ motors: dict[str, tuple[int, str]],
+ extra_model_control_table: dict[str, list[tuple]] | None = None,
+ extra_model_resolution: dict[str, int] | None = None,
+ mock=False,
+ ):
+ self.port = port
+ self.motors = motors
+ self.mock = mock
+
+ self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+ if extra_model_control_table:
+ self.model_ctrl_table.update(extra_model_control_table)
+
+ self.model_resolution = deepcopy(MODEL_RESOLUTION)
+ if extra_model_resolution:
+ self.model_resolution.update(extra_model_resolution)
+
+ self.port_handler = None
+ self.packet_handler = None
+ self.calibration = None
+ self.is_connected = False
+ self.group_readers = {}
+ self.group_writers = {}
+ self.logs = {}
+
+ self.track_positions = {}
+
+ def connect(self):
+ if self.is_connected:
+ raise RobotDeviceAlreadyConnectedError(
+ f"FeetechMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice."
+ )
+
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ self.port_handler = scs.PortHandler(self.port)
+ self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
+
+ try:
+ if not self.port_handler.openPort():
+ raise OSError(f"Failed to open port '{self.port}'.")
+ except Exception:
+ traceback.print_exc()
+ print(
+ "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
+ )
+ raise
+
+ # Allow to read and write
+ self.is_connected = True
+
+ self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
+
+ def reconnect(self):
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ self.port_handler = scs.PortHandler(self.port)
+ self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
+
+ if not self.port_handler.openPort():
+ raise OSError(f"Failed to open port '{self.port}'.")
+
+ self.is_connected = True
+
+ def are_motors_configured(self):
+ # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect,
+ # a ConnectionError will be raised anyway.
+ try:
+ return (self.motor_indices == self.read("ID")).all()
+ except ConnectionError as e:
+ print(e)
+ return False
+
+ def find_motor_indices(self, possible_ids=None, num_retry=2):
+ if possible_ids is None:
+ possible_ids = range(MAX_ID_RANGE)
+
+ indices = []
+ for idx in tqdm.tqdm(possible_ids):
+ try:
+ present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
+ except ConnectionError:
+ continue
+
+ if idx != present_idx:
+ # sanity check
+ raise OSError(
+ "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
+ )
+ indices.append(idx)
+
+ return indices
+
+ def set_bus_baudrate(self, baudrate):
+ present_bus_baudrate = self.port_handler.getBaudRate()
+ if present_bus_baudrate != baudrate:
+ print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
+ self.port_handler.setBaudRate(baudrate)
+
+ if self.port_handler.getBaudRate() != baudrate:
+ raise OSError("Failed to write bus baud rate.")
+
+ @property
+ def motor_names(self) -> list[str]:
+ return list(self.motors.keys())
+
+ @property
+ def motor_models(self) -> list[str]:
+ return [model for _, model in self.motors.values()]
+
+ @property
+ def motor_indices(self) -> list[int]:
+ return [idx for idx, _ in self.motors.values()]
+
+ def set_calibration(self, calibration: dict[str, list]):
+ self.calibration = calibration
+
+ def apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
+ """This function apply the calibration, automatically detects out of range errors for motors values and attempt to correct.
+
+ For more info, see docstring of `apply_calibration` and `autocorrect_calibration`.
+ """
+ try:
+ values = self.apply_calibration(values, motor_names)
+ except JointOutOfRangeError as e:
+ print(e)
+ self.autocorrect_calibration(values, motor_names)
+ values = self.apply_calibration(values, motor_names)
+ return values
+
+ def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+ """Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with
+ a "zero position" at 0 degree.
+
+ Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor
+ rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range.
+
+ Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation
+ when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and
+ at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
+ or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
+ To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
+ in the centered nominal degree range ]-180, 180[.
+ """
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
+ values = values.astype(np.float32)
+
+ for i, name in enumerate(motor_names):
+ calib_idx = self.calibration["motor_names"].index(name)
+ calib_mode = self.calibration["calib_mode"][calib_idx]
+
+ if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+ drive_mode = self.calibration["drive_mode"][calib_idx]
+ homing_offset = self.calibration["homing_offset"][calib_idx]
+ _, model = self.motors[name]
+ resolution = self.model_resolution[model]
+
+ # Update direction of rotation of the motor to match between leader and follower.
+ # In fact, the motor of the leader for a given joint can be assembled in an
+ # opposite direction in term of rotation than the motor of the follower on the same joint.
+ if drive_mode:
+ values[i] *= -1
+
+ # Convert from range [-2**31, 2**31[ to
+ # nominal range ]-resolution, resolution[ (e.g. ]-2048, 2048[)
+ values[i] += homing_offset
+
+ # Convert from range ]-resolution, resolution[ to
+ # universal float32 centered degree range ]-180, 180[
+ values[i] = values[i] / (resolution // 2) * HALF_TURN_DEGREE
+
+ if (values[i] < LOWER_BOUND_DEGREE) or (values[i] > UPPER_BOUND_DEGREE):
+ raise JointOutOfRangeError(
+ f"Wrong motor position range detected for {name}. "
+ f"Expected to be in nominal range of [-{HALF_TURN_DEGREE}, {HALF_TURN_DEGREE}] degrees (a full rotation), "
+ f"with a maximum range of [{LOWER_BOUND_DEGREE}, {UPPER_BOUND_DEGREE}] degrees to account for joints that can rotate a bit more, "
+ f"but present value is {values[i]} degree. "
+ "This might be due to a cable connection issue creating an artificial 360 degrees jump in motor values. "
+ "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
+ )
+
+ elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+ start_pos = self.calibration["start_pos"][calib_idx]
+ end_pos = self.calibration["end_pos"][calib_idx]
+
+ # Rescale the present position to a nominal range [0, 100] %,
+ # useful for joints with linear motions like Aloha gripper
+ values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
+
+ if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
+ raise JointOutOfRangeError(
+ f"Wrong motor position range detected for {name}. "
+ f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
+ f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
+ f"but present value is {values[i]} %. "
+ "This might be due to a cable connection issue creating an artificial jump in motor values. "
+ "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
+ )
+
+ return values
+
+ def autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+ """This function automatically detects issues with values of motors after calibration, and correct for these issues.
+
+ Some motors might have values outside of expected maximum bounds after calibration.
+ For instance, for a joint in degree, its value can be outside [-270, 270] degrees, which is totally unexpected given
+ a nominal range of [-180, 180] degrees, which represents half a turn to the left or right starting from zero position.
+
+ Known issues:
+ #1: Motor value randomly shifts of a full turn, caused by hardware/connection errors.
+ #2: Motor internal homing offset is shifted of a full turn, caused by using default calibration (e.g Aloha).
+ #3: motor internal homing offset is shifted of less or more than a full turn, caused by using default calibration
+ or by human error during manual calibration.
+
+ Issues #1 and #2 can be solved by shifting the calibration homing offset by a full turn.
+ Issue #3 will be visually detected by user and potentially captured by the safety feature `max_relative_target`,
+ that will slow down the motor, raise an error asking to recalibrate. Manual recalibrating will solve the issue.
+
+ Note: A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096.
+ """
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
+ values = values.astype(np.float32)
+
+ for i, name in enumerate(motor_names):
+ calib_idx = self.calibration["motor_names"].index(name)
+ calib_mode = self.calibration["calib_mode"][calib_idx]
+
+ if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+ drive_mode = self.calibration["drive_mode"][calib_idx]
+ homing_offset = self.calibration["homing_offset"][calib_idx]
+ _, model = self.motors[name]
+ resolution = self.model_resolution[model]
+
+ if drive_mode:
+ values[i] *= -1
+
+ # Convert from initial range to range [-180, 180] degrees
+ calib_val = (values[i] + homing_offset) / (resolution // 2) * HALF_TURN_DEGREE
+ in_range = (calib_val > LOWER_BOUND_DEGREE) and (calib_val < UPPER_BOUND_DEGREE)
+
+ # Solve this inequality to find the factor to shift the range into [-180, 180] degrees
+ # values[i] = (values[i] + homing_offset + resolution * factor) / (resolution // 2) * HALF_TURN_DEGREE
+ # - HALF_TURN_DEGREE <= (values[i] + homing_offset + resolution * factor) / (resolution // 2) * HALF_TURN_DEGREE <= HALF_TURN_DEGREE
+ # (- HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset) / resolution <= factor <= (HALF_TURN_DEGREE / 180 * (resolution // 2) - values[i] - homing_offset) / resolution
+ low_factor = (
+ -HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset
+ ) / resolution
+ upp_factor = (
+ HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset
+ ) / resolution
+
+ elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+ start_pos = self.calibration["start_pos"][calib_idx]
+ end_pos = self.calibration["end_pos"][calib_idx]
+
+ # Convert from initial range to range [0, 100] in %
+ calib_val = (values[i] - start_pos) / (end_pos - start_pos) * 100
+ in_range = (calib_val > LOWER_BOUND_LINEAR) and (calib_val < UPPER_BOUND_LINEAR)
+
+ # Solve this inequality to find the factor to shift the range into [0, 100] %
+ # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos + resolution * factor - start_pos - resolution * factor) * 100
+ # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100
+ # 0 <= (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100 <= 100
+ # (start_pos - values[i]) / resolution <= factor <= (end_pos - values[i]) / resolution
+ low_factor = (start_pos - values[i]) / resolution
+ upp_factor = (end_pos - values[i]) / resolution
+
+ if not in_range:
+ # Get first integer between the two bounds
+ if low_factor < upp_factor:
+ factor = math.ceil(low_factor)
+
+ if factor > upp_factor:
+ raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
+ else:
+ factor = math.ceil(upp_factor)
+
+ if factor > low_factor:
+ raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
+
+ if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+ out_of_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
+ in_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
+ elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+ out_of_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
+ in_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
+
+ logging.warning(
+ f"Auto-correct calibration of motor '{name}' by shifting value by {abs(factor)} full turns, "
+ f"from '{out_of_range_str}' to '{in_range_str}'."
+ )
+
+ # A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096.
+ self.calibration["homing_offset"][calib_idx] += resolution * factor
+
+ def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+ """Inverse of `apply_calibration`."""
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ for i, name in enumerate(motor_names):
+ calib_idx = self.calibration["motor_names"].index(name)
+ calib_mode = self.calibration["calib_mode"][calib_idx]
+
+ if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+ drive_mode = self.calibration["drive_mode"][calib_idx]
+ homing_offset = self.calibration["homing_offset"][calib_idx]
+ _, model = self.motors[name]
+ resolution = self.model_resolution[model]
+
+ # Convert from nominal 0-centered degree range [-180, 180] to
+ # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096)
+ values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2)
+
+ # Substract the homing offsets to come back to actual motor range of values
+ # which can be arbitrary.
+ values[i] -= homing_offset
+
+ # Remove drive mode, which is the rotation direction of the motor, to come back to
+ # actual motor rotation direction which can be arbitrary.
+ if drive_mode:
+ values[i] *= -1
+
+ elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+ start_pos = self.calibration["start_pos"][calib_idx]
+ end_pos = self.calibration["end_pos"][calib_idx]
+
+ # Convert from nominal lnear range of [0, 100] % to
+ # actual motor range of values which can be arbitrary.
+ values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
+
+ values = np.round(values).astype(np.int32)
+ return values
+
+ def avoid_rotation_reset(self, values, motor_names, data_name):
+ if data_name not in self.track_positions:
+ self.track_positions[data_name] = {
+ "prev": [None] * len(self.motor_names),
+ # Assume False at initialization
+ "below_zero": [False] * len(self.motor_names),
+ "above_max": [False] * len(self.motor_names),
+ }
+
+ track = self.track_positions[data_name]
+
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ for i, name in enumerate(motor_names):
+ idx = self.motor_names.index(name)
+
+ if track["prev"][idx] is None:
+ track["prev"][idx] = values[i]
+ continue
+
+ # Detect a full rotation occured
+ if abs(track["prev"][idx] - values[i]) > 2048:
+ # Position went below 0 and got reset to 4095
+ if track["prev"][idx] < values[i]:
+ # So we set negative value by adding a full rotation
+ values[i] -= 4096
+
+ # Position went above 4095 and got reset to 0
+ elif track["prev"][idx] > values[i]:
+ # So we add a full rotation
+ values[i] += 4096
+
+ track["prev"][idx] = values[i]
+
+ return values
+
+ def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ return_list = True
+ if not isinstance(motor_ids, list):
+ return_list = False
+ motor_ids = [motor_ids]
+
+ assert_same_address(self.model_ctrl_table, self.motor_models, data_name)
+ addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
+ group = scs.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes)
+ for idx in motor_ids:
+ group.addParam(idx)
+
+ for _ in range(num_retry):
+ comm = group.txRxPacket()
+ if comm == scs.COMM_SUCCESS:
+ break
+
+ if comm != scs.COMM_SUCCESS:
+ raise ConnectionError(
+ f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
+ f"{self.packet_handler.getTxRxResult(comm)}"
+ )
+
+ values = []
+ for idx in motor_ids:
+ value = group.getData(idx, addr, bytes)
+ values.append(value)
+
+ if return_list:
+ return values
+ else:
+ return values[0]
+
+ def read(self, data_name, motor_names: str | list[str] | None = None):
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ if not self.is_connected:
+ raise RobotDeviceNotConnectedError(
+ f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
+ )
+
+ start_time = time.perf_counter()
+
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ if isinstance(motor_names, str):
+ motor_names = [motor_names]
+
+ motor_ids = []
+ models = []
+ for name in motor_names:
+ motor_idx, model = self.motors[name]
+ motor_ids.append(motor_idx)
+ models.append(model)
+
+ assert_same_address(self.model_ctrl_table, models, data_name)
+ addr, bytes = self.model_ctrl_table[model][data_name]
+ group_key = get_group_sync_key(data_name, motor_names)
+
+ if data_name not in self.group_readers:
+ # create new group reader
+ self.group_readers[group_key] = scs.GroupSyncRead(
+ self.port_handler, self.packet_handler, addr, bytes
+ )
+ for idx in motor_ids:
+ self.group_readers[group_key].addParam(idx)
+
+ for _ in range(NUM_READ_RETRY):
+ comm = self.group_readers[group_key].txRxPacket()
+ if comm == scs.COMM_SUCCESS:
+ break
+
+ if comm != scs.COMM_SUCCESS:
+ raise ConnectionError(
+ f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
+ f"{self.packet_handler.getTxRxResult(comm)}"
+ )
+
+ values = []
+ for idx in motor_ids:
+ value = self.group_readers[group_key].getData(idx, addr, bytes)
+ values.append(value)
+
+ values = np.array(values)
+
+ # Convert to signed int to use range [-2048, 2048] for our motor positions.
+ if data_name in CONVERT_UINT32_TO_INT32_REQUIRED:
+ values = values.astype(np.int32)
+
+ if data_name in CALIBRATION_REQUIRED:
+ values = self.avoid_rotation_reset(values, motor_names, data_name)
+
+ if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
+ values = self.apply_calibration_autocorrect(values, motor_names)
+
+ # log the number of seconds it took to read the data from the motors
+ delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names)
+ self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+ # log the utc time at which the data was received
+ ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
+ self.logs[ts_utc_name] = capture_timestamp_utc()
+
+ return values
+
+ def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ if not isinstance(motor_ids, list):
+ motor_ids = [motor_ids]
+ if not isinstance(values, list):
+ values = [values]
+
+ assert_same_address(self.model_ctrl_table, motor_models, data_name)
+ addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
+ group = scs.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
+ for idx, value in zip(motor_ids, values, strict=True):
+ data = convert_to_bytes(value, bytes, self.mock)
+ group.addParam(idx, data)
+
+ for _ in range(num_retry):
+ comm = group.txPacket()
+ if comm == scs.COMM_SUCCESS:
+ break
+
+ if comm != scs.COMM_SUCCESS:
+ raise ConnectionError(
+ f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
+ f"{self.packet_handler.getTxRxResult(comm)}"
+ )
+
+ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None):
+ if not self.is_connected:
+ raise RobotDeviceNotConnectedError(
+ f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
+ )
+
+ start_time = time.perf_counter()
+
+ if self.mock:
+ import tests.mock_scservo_sdk as scs
+ else:
+ import scservo_sdk as scs
+
+ if motor_names is None:
+ motor_names = self.motor_names
+
+ if isinstance(motor_names, str):
+ motor_names = [motor_names]
+
+ if isinstance(values, (int, float, np.integer)):
+ values = [int(values)] * len(motor_names)
+
+ values = np.array(values)
+
+ motor_ids = []
+ models = []
+ for name in motor_names:
+ motor_idx, model = self.motors[name]
+ motor_ids.append(motor_idx)
+ models.append(model)
+
+ if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
+ values = self.revert_calibration(values, motor_names)
+
+ values = values.tolist()
+
+ assert_same_address(self.model_ctrl_table, models, data_name)
+ addr, bytes = self.model_ctrl_table[model][data_name]
+ group_key = get_group_sync_key(data_name, motor_names)
+
+ init_group = data_name not in self.group_readers
+ if init_group:
+ self.group_writers[group_key] = scs.GroupSyncWrite(
+ self.port_handler, self.packet_handler, addr, bytes
+ )
+
+ for idx, value in zip(motor_ids, values, strict=True):
+ data = convert_to_bytes(value, bytes, self.mock)
+ if init_group:
+ self.group_writers[group_key].addParam(idx, data)
+ else:
+ self.group_writers[group_key].changeParam(idx, data)
+
+ comm = self.group_writers[group_key].txPacket()
+ if comm != scs.COMM_SUCCESS:
+ raise ConnectionError(
+ f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
+ f"{self.packet_handler.getTxRxResult(comm)}"
+ )
+
+ # log the number of seconds it took to write the data to the motors
+ delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
+ self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+ # TODO(rcadene): should we log the time before sending the write command?
+ # log the utc time when the write has been completed
+ ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
+ self.logs[ts_utc_name] = capture_timestamp_utc()
+
+ def disconnect(self):
+ if not self.is_connected:
+ raise RobotDeviceNotConnectedError(
+ f"FeetechMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first."
+ )
+
+ if self.port_handler is not None:
+ self.port_handler.closePort()
+ self.port_handler = None
+
+ self.packet_handler = None
+ self.group_readers = {}
+ self.group_writers = {}
+ self.is_connected = False
+
+ def __del__(self):
+ if getattr(self, "is_connected", False):
+ self.disconnect()
diff --git a/lerobot/common/robot_devices/robots/dynamixel_calibration.py b/lerobot/common/robot_devices/robots/dynamixel_calibration.py
new file mode 100644
index 000000000..5c4932d2e
--- /dev/null
+++ b/lerobot/common/robot_devices/robots/dynamixel_calibration.py
@@ -0,0 +1,130 @@
+"""Logic to calibrate a robot arm built with dynamixel motors"""
+# TODO(rcadene, aliberts): move this logic into the robot code when refactoring
+
+import numpy as np
+
+from lerobot.common.robot_devices.motors.dynamixel import (
+ CalibrationMode,
+ TorqueMode,
+ convert_degrees_to_steps,
+)
+from lerobot.common.robot_devices.motors.utils import MotorsBus
+
+URL_TEMPLATE = (
+ "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
+)
+
+# The following positions are provided in nominal degree range ]-180, +180[
+# For more info on these constants, see comments in the code where they get used.
+ZERO_POSITION_DEGREE = 0
+ROTATED_POSITION_DEGREE = 90
+
+
+def assert_drive_mode(drive_mode):
+ # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted.
+ if not np.all(np.isin(drive_mode, [0, 1])):
+ raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})")
+
+
+def apply_drive_mode(position, drive_mode):
+ assert_drive_mode(drive_mode)
+ # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted,
+ # to [-1, 1] with 1 indicates original rotation direction and -1 inverted.
+ signed_drive_mode = -(drive_mode * 2 - 1)
+ position *= signed_drive_mode
+ return position
+
+
+def compute_nearest_rounded_position(position, models):
+ delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models)
+ nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn
+ return nearest_pos.astype(position.dtype)
+
+
+def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
+ """This function ensures that a neural network trained on data collected on a given robot
+ can work on another robot. For instance before calibration, setting a same goal position
+ for each motor of two different robots will get two very different positions. But after calibration,
+ the two robots will move to the same position.To this end, this function computes the homing offset
+ and the drive mode for each motor of a given robot.
+
+ Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps
+ to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions
+ being 0. During the calibration process, you will need to manually move the robot to this "zero position".
+
+ Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled
+ in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot
+ to the "rotated position".
+
+ After calibration, the homing offsets and drive modes are stored in a cache.
+
+ Example of usage:
+ ```python
+ run_arm_calibration(arm, "koch", "left", "follower")
+ ```
+ """
+ if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
+ raise ValueError("To run calibration, the torque must be disabled on all motors.")
+
+ print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
+
+ print("\nMove arm to zero position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero"))
+ input("Press Enter to continue...")
+
+ # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed.
+ # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will
+ # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position.
+ zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models)
+
+ # Compute homing offset so that `present_position + homing_offset ~= target_position`.
+ zero_pos = arm.read("Present_Position")
+ zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models)
+ homing_offset = zero_target_pos - zero_nearest_pos
+
+ # The rotated target position corresponds to a rotation of a quarter turn from the zero position.
+ # This allows to identify the rotation direction of each motor.
+ # For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction
+ # is inverted. However, for the calibration being successful, we need everyone to follow the same target position.
+ # Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which
+ # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view
+ # of the previous motor in the kinetic chain.
+ print("\nMove arm to rotated target position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated"))
+ input("Press Enter to continue...")
+
+ rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models)
+
+ # Find drive mode by rotating each motor by a quarter of a turn.
+ # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0).
+ rotated_pos = arm.read("Present_Position")
+ drive_mode = (rotated_pos < zero_pos).astype(np.int32)
+
+ # Re-compute homing offset to take into account drive mode
+ rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode)
+ rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models)
+ homing_offset = rotated_target_pos - rotated_nearest_pos
+
+ print("\nMove arm to rest position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest"))
+ input("Press Enter to continue...")
+ print()
+
+ # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
+ calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names)
+
+ # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml?
+ if robot_type in ["aloha"] and "gripper" in arm.motor_names:
+ # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100]
+ calib_idx = arm.motor_names.index("gripper")
+ calib_mode[calib_idx] = CalibrationMode.LINEAR.name
+
+ calib_data = {
+ "homing_offset": homing_offset.tolist(),
+ "drive_mode": drive_mode.tolist(),
+ "start_pos": zero_pos.tolist(),
+ "end_pos": rotated_pos.tolist(),
+ "calib_mode": calib_mode,
+ "motor_names": arm.motor_names,
+ }
+ return calib_data
diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/robot_devices/robots/feetech_calibration.py
new file mode 100644
index 000000000..1fca07f43
--- /dev/null
+++ b/lerobot/common/robot_devices/robots/feetech_calibration.py
@@ -0,0 +1,485 @@
+"""Logic to calibrate a robot arm built with feetech motors"""
+# TODO(rcadene, aliberts): move this logic into the robot code when refactoring
+
+import time
+
+import numpy as np
+
+from lerobot.common.robot_devices.motors.feetech import (
+ CalibrationMode,
+ TorqueMode,
+ convert_degrees_to_steps,
+)
+from lerobot.common.robot_devices.motors.utils import MotorsBus
+
+URL_TEMPLATE = (
+ "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
+)
+
+# The following positions are provided in nominal degree range ]-180, +180[
+# For more info on these constants, see comments in the code where they get used.
+ZERO_POSITION_DEGREE = 0
+ROTATED_POSITION_DEGREE = 90
+
+
+def assert_drive_mode(drive_mode):
+ # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted.
+ if not np.all(np.isin(drive_mode, [0, 1])):
+ raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})")
+
+
+def apply_drive_mode(position, drive_mode):
+ assert_drive_mode(drive_mode)
+ # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted,
+ # to [-1, 1] with 1 indicates original rotation direction and -1 inverted.
+ signed_drive_mode = -(drive_mode * 2 - 1)
+ position *= signed_drive_mode
+ return position
+
+
+def move_until_block(arm, motor_name, positive_direction=True, while_move_hook=None):
+ count = 0
+ while True:
+ present_pos = arm.read("Present_Position", motor_name)
+ if positive_direction:
+ # Move +100 steps every time. Lower the steps to lower the speed at which the arm moves.
+ arm.write("Goal_Position", present_pos + 100, motor_name)
+ else:
+ arm.write("Goal_Position", present_pos - 100, motor_name)
+
+ if while_move_hook is not None:
+ while_move_hook()
+
+ present_pos = arm.read("Present_Position", motor_name).item()
+ present_speed = arm.read("Present_Speed", motor_name).item()
+ present_current = arm.read("Present_Current", motor_name).item()
+ # present_load = arm.read("Present_Load", motor_name).item()
+ # present_voltage = arm.read("Present_Voltage", motor_name).item()
+ # present_temperature = arm.read("Present_Temperature", motor_name).item()
+
+ # print(f"{present_pos=}")
+ # print(f"{present_speed=}")
+ # print(f"{present_current=}")
+ # print(f"{present_load=}")
+ # print(f"{present_voltage=}")
+ # print(f"{present_temperature=}")
+
+ if present_speed == 0 and present_current > 50:
+ count += 1
+ if count > 100 or present_current > 300:
+ return present_pos
+ else:
+ count = 0
+
+
+def move_to_calibrate(
+ arm,
+ motor_name,
+ invert_drive_mode=False,
+ positive_first=True,
+ in_between_move_hook=None,
+ while_move_hook=None,
+):
+ initial_pos = arm.read("Present_Position", motor_name)
+
+ if positive_first:
+ p_present_pos = move_until_block(
+ arm, motor_name, positive_direction=True, while_move_hook=while_move_hook
+ )
+ else:
+ n_present_pos = move_until_block(
+ arm, motor_name, positive_direction=False, while_move_hook=while_move_hook
+ )
+
+ if in_between_move_hook is not None:
+ in_between_move_hook()
+
+ if positive_first:
+ n_present_pos = move_until_block(
+ arm, motor_name, positive_direction=False, while_move_hook=while_move_hook
+ )
+ else:
+ p_present_pos = move_until_block(
+ arm, motor_name, positive_direction=True, while_move_hook=while_move_hook
+ )
+
+ zero_pos = (n_present_pos + p_present_pos) / 2
+
+ calib_data = {
+ "initial_pos": initial_pos,
+ "homing_offset": zero_pos if invert_drive_mode else -zero_pos,
+ "invert_drive_mode": invert_drive_mode,
+ "drive_mode": -1 if invert_drive_mode else 0,
+ "zero_pos": zero_pos,
+ "start_pos": n_present_pos if invert_drive_mode else p_present_pos,
+ "end_pos": p_present_pos if invert_drive_mode else n_present_pos,
+ }
+ return calib_data
+
+
+def apply_offset(calib, offset):
+ calib["zero_pos"] += offset
+ if calib["drive_mode"]:
+ calib["homing_offset"] += offset
+ else:
+ calib["homing_offset"] -= offset
+ return calib
+
+
+def run_arm_auto_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
+ if robot_type == "so100":
+ return run_arm_auto_calibration_so100(arm, robot_type, arm_name, arm_type)
+ elif robot_type == "moss":
+ return run_arm_auto_calibration_moss(arm, robot_type, arm_name, arm_type)
+ else:
+ raise ValueError(robot_type)
+
+
+def run_arm_auto_calibration_so100(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
+ """All the offsets and magic numbers are hand tuned, and are unique to SO-100 follower arms"""
+ if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
+ raise ValueError("To run calibration, the torque must be disabled on all motors.")
+
+ if not (robot_type == "so100" and arm_type == "follower"):
+ raise NotImplementedError("Auto calibration only supports the follower of so100 arms for now.")
+
+ print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
+
+ print("\nMove arm to initial position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="initial"))
+ input("Press Enter to continue...")
+
+ # Lower the acceleration of the motors (in [0,254])
+ initial_acceleration = arm.read("Acceleration")
+ arm.write("Lock", 0)
+ arm.write("Acceleration", 10)
+ time.sleep(1)
+
+ arm.write("Torque_Enable", TorqueMode.ENABLED.value)
+
+ print(f'{arm.read("Present_Position", "elbow_flex")=}')
+
+ calib = {}
+
+ init_wf_pos = arm.read("Present_Position", "wrist_flex")
+ init_sl_pos = arm.read("Present_Position", "shoulder_lift")
+ init_ef_pos = arm.read("Present_Position", "elbow_flex")
+ arm.write("Goal_Position", init_wf_pos - 800, "wrist_flex")
+ arm.write("Goal_Position", init_sl_pos + 150 + 1024, "shoulder_lift")
+ arm.write("Goal_Position", init_ef_pos - 2048, "elbow_flex")
+ time.sleep(2)
+
+ print("Calibrate shoulder_pan")
+ calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan")
+ arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan")
+ time.sleep(1)
+
+ print("Calibrate gripper")
+ calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True)
+ time.sleep(1)
+
+ print("Calibrate wrist_flex")
+ calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex")
+ calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=80)
+
+ def in_between_move_hook():
+ nonlocal arm, calib
+ time.sleep(2)
+ ef_pos = arm.read("Present_Position", "elbow_flex")
+ sl_pos = arm.read("Present_Position", "shoulder_lift")
+ arm.write("Goal_Position", ef_pos + 1024, "elbow_flex")
+ arm.write("Goal_Position", sl_pos - 1024, "shoulder_lift")
+ time.sleep(2)
+
+ print("Calibrate elbow_flex")
+ calib["elbow_flex"] = move_to_calibrate(
+ arm, "elbow_flex", positive_first=False, in_between_move_hook=in_between_move_hook
+ )
+ calib["elbow_flex"] = apply_offset(calib["elbow_flex"], offset=80 - 1024)
+
+ arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 1024 + 512, "elbow_flex")
+ time.sleep(1)
+
+ def in_between_move_hook():
+ nonlocal arm, calib
+ arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"], "elbow_flex")
+
+ print("Calibrate shoulder_lift")
+ calib["shoulder_lift"] = move_to_calibrate(
+ arm,
+ "shoulder_lift",
+ invert_drive_mode=True,
+ positive_first=False,
+ in_between_move_hook=in_between_move_hook,
+ )
+ # add an 30 steps as offset to align with body
+ calib["shoulder_lift"] = apply_offset(calib["shoulder_lift"], offset=1024 - 50)
+
+ def while_move_hook():
+ nonlocal arm, calib
+ positions = {
+ "shoulder_lift": round(calib["shoulder_lift"]["zero_pos"] - 1600),
+ "elbow_flex": round(calib["elbow_flex"]["zero_pos"] + 1700),
+ "wrist_flex": round(calib["wrist_flex"]["zero_pos"] + 800),
+ "gripper": round(calib["gripper"]["end_pos"]),
+ }
+ arm.write("Goal_Position", list(positions.values()), list(positions.keys()))
+
+ arm.write("Goal_Position", round(calib["shoulder_lift"]["zero_pos"] - 1600), "shoulder_lift")
+ time.sleep(2)
+ arm.write("Goal_Position", round(calib["elbow_flex"]["zero_pos"] + 1700), "elbow_flex")
+ time.sleep(2)
+ arm.write("Goal_Position", round(calib["wrist_flex"]["zero_pos"] + 800), "wrist_flex")
+ time.sleep(2)
+ arm.write("Goal_Position", round(calib["gripper"]["end_pos"]), "gripper")
+ time.sleep(2)
+
+ print("Calibrate wrist_roll")
+ calib["wrist_roll"] = move_to_calibrate(
+ arm, "wrist_roll", invert_drive_mode=True, positive_first=False, while_move_hook=while_move_hook
+ )
+
+ arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"], "wrist_roll")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["gripper"]["start_pos"], "gripper")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"], "wrist_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 2048, "elbow_flex")
+ arm.write("Goal_Position", calib["shoulder_lift"]["zero_pos"] - 2048, "shoulder_lift")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan")
+ time.sleep(1)
+
+ calib_modes = []
+ for name in arm.motor_names:
+ if name == "gripper":
+ calib_modes.append(CalibrationMode.LINEAR.name)
+ else:
+ calib_modes.append(CalibrationMode.DEGREE.name)
+
+ calib_dict = {
+ "homing_offset": [calib[name]["homing_offset"] for name in arm.motor_names],
+ "drive_mode": [calib[name]["drive_mode"] for name in arm.motor_names],
+ "start_pos": [calib[name]["start_pos"] for name in arm.motor_names],
+ "end_pos": [calib[name]["end_pos"] for name in arm.motor_names],
+ "calib_mode": calib_modes,
+ "motor_names": arm.motor_names,
+ }
+
+ # Re-enable original accerlation
+ arm.write("Lock", 0)
+ arm.write("Acceleration", initial_acceleration)
+ time.sleep(1)
+
+ return calib_dict
+
+
+def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
+ """All the offsets and magic numbers are hand tuned, and are unique to SO-100 follower arms"""
+ if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
+ raise ValueError("To run calibration, the torque must be disabled on all motors.")
+
+ if not (robot_type == "moss" and arm_type == "follower"):
+ raise NotImplementedError("Auto calibration only supports the follower of moss arms for now.")
+
+ print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
+
+ print("\nMove arm to initial position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="initial"))
+ input("Press Enter to continue...")
+
+ # Lower the acceleration of the motors (in [0,254])
+ initial_acceleration = arm.read("Acceleration")
+ arm.write("Lock", 0)
+ arm.write("Acceleration", 10)
+ time.sleep(1)
+
+ arm.write("Torque_Enable", TorqueMode.ENABLED.value)
+
+ sl_pos = arm.read("Present_Position", "shoulder_lift")
+ arm.write("Goal_Position", sl_pos - 1024 - 450, "shoulder_lift")
+ ef_pos = arm.read("Present_Position", "elbow_flex")
+ arm.write("Goal_Position", ef_pos + 1024 + 450, "elbow_flex")
+ time.sleep(2)
+
+ calib = {}
+
+ print("Calibrate shoulder_pan")
+ calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan", load_threshold=350, count_threshold=200)
+ arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan")
+ time.sleep(1)
+
+ print("Calibrate gripper")
+ calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True, count_threshold=200)
+ time.sleep(1)
+
+ print("Calibrate wrist_flex")
+ calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True, count_threshold=200)
+ calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=-210 + 1024)
+
+ wr_pos = arm.read("Present_Position", "wrist_roll")
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", wr_pos - 1024, "wrist_roll")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 2048, "wrist_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["gripper"]["end_pos"], "gripper")
+ time.sleep(1)
+
+ print("Calibrate wrist_roll")
+ calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True, count_threshold=200)
+ calib["wrist_roll"] = apply_offset(calib["wrist_roll"], offset=790)
+
+ arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"] - 1024, "wrist_roll")
+ arm.write("Goal_Position", calib["gripper"]["start_pos"], "gripper")
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"], "wrist_roll")
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 2048, "wrist_flex")
+
+ def in_between_move_elbow_flex_hook():
+ nonlocal arm, calib
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"], "wrist_flex")
+
+ print("Calibrate elbow_flex")
+ calib["elbow_flex"] = move_to_calibrate(
+ arm,
+ "elbow_flex",
+ invert_drive_mode=True,
+ count_threshold=200,
+ in_between_move_hook=in_between_move_elbow_flex_hook,
+ )
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex")
+
+ def in_between_move_shoulder_lift_hook():
+ nonlocal arm, calib
+ sl = arm.read("Present_Position", "shoulder_lift")
+ arm.write("Goal_Position", sl - 1500, "shoulder_lift")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 1536, "elbow_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["wrist_flex"]["start_pos"], "wrist_flex")
+ time.sleep(1)
+
+ print("Calibrate shoulder_lift")
+ calib["shoulder_lift"] = move_to_calibrate(
+ arm, "shoulder_lift", in_between_move_hook=in_between_move_shoulder_lift_hook
+ )
+ calib["shoulder_lift"] = apply_offset(calib["shoulder_lift"], offset=-1024)
+
+ arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex")
+ time.sleep(1)
+ arm.write("Goal_Position", calib["shoulder_lift"]["zero_pos"] + 2048, "shoulder_lift")
+ arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] - 1024 - 400, "elbow_flex")
+ time.sleep(2)
+
+ calib_modes = []
+ for name in arm.motor_names:
+ if name == "gripper":
+ calib_modes.append(CalibrationMode.LINEAR.name)
+ else:
+ calib_modes.append(CalibrationMode.DEGREE.name)
+
+ calib_dict = {
+ "homing_offset": [calib[name]["homing_offset"] for name in arm.motor_names],
+ "drive_mode": [calib[name]["drive_mode"] for name in arm.motor_names],
+ "start_pos": [calib[name]["start_pos"] for name in arm.motor_names],
+ "end_pos": [calib[name]["end_pos"] for name in arm.motor_names],
+ "calib_mode": calib_modes,
+ "motor_names": arm.motor_names,
+ }
+
+ # Re-enable original accerlation
+ arm.write("Lock", 0)
+ arm.write("Acceleration", initial_acceleration)
+ time.sleep(1)
+
+ return calib_dict
+
+
+def run_arm_manual_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
+ """This function ensures that a neural network trained on data collected on a given robot
+ can work on another robot. For instance before calibration, setting a same goal position
+ for each motor of two different robots will get two very different positions. But after calibration,
+ the two robots will move to the same position.To this end, this function computes the homing offset
+ and the drive mode for each motor of a given robot.
+
+ Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps
+ to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions
+ being 0. During the calibration process, you will need to manually move the robot to this "zero position".
+
+ Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled
+ in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot
+ to the "rotated position".
+
+ After calibration, the homing offsets and drive modes are stored in a cache.
+
+ Example of usage:
+ ```python
+ run_arm_calibration(arm, "so100", "left", "follower")
+ ```
+ """
+ if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
+ raise ValueError("To run calibration, the torque must be disabled on all motors.")
+
+ print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
+
+ print("\nMove arm to zero position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero"))
+ input("Press Enter to continue...")
+
+ # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed.
+ # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will
+ # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position.
+ zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models)
+
+ # Compute homing offset so that `present_position + homing_offset ~= target_position`.
+ zero_pos = arm.read("Present_Position")
+ homing_offset = zero_target_pos - zero_pos
+
+ # The rotated target position corresponds to a rotation of a quarter turn from the zero position.
+ # This allows to identify the rotation direction of each motor.
+ # For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction
+ # is inverted. However, for the calibration being successful, we need everyone to follow the same target position.
+ # Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which
+ # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view
+ # of the previous motor in the kinetic chain.
+ print("\nMove arm to rotated target position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated"))
+ input("Press Enter to continue...")
+
+ rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models)
+
+ # Find drive mode by rotating each motor by a quarter of a turn.
+ # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0).
+ rotated_pos = arm.read("Present_Position")
+ drive_mode = (rotated_pos < zero_pos).astype(np.int32)
+
+ # Re-compute homing offset to take into account drive mode
+ rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode)
+ homing_offset = rotated_target_pos - rotated_drived_pos
+
+ print("\nMove arm to rest position")
+ print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest"))
+ input("Press Enter to continue...")
+ print()
+
+ # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
+ calib_modes = []
+ for name in arm.motor_names:
+ if name == "gripper":
+ calib_modes.append(CalibrationMode.LINEAR.name)
+ else:
+ calib_modes.append(CalibrationMode.DEGREE.name)
+
+ calib_dict = {
+ "homing_offset": homing_offset.tolist(),
+ "drive_mode": drive_mode.tolist(),
+ "start_pos": zero_pos.tolist(),
+ "end_pos": rotated_pos.tolist(),
+ "calib_mode": calib_modes,
+ "motor_names": arm.motor_names,
+ }
+ return calib_dict
diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py
index 20969c30c..2c358cb92 100644
--- a/lerobot/common/robot_devices/robots/manipulator.py
+++ b/lerobot/common/robot_devices/robots/manipulator.py
@@ -1,3 +1,9 @@
+"""Contains logic to instantiate a robot, read information from its motors and cameras,
+and send orders to its motors.
+"""
+# TODO(rcadene, aliberts): reorganize the codebase into one file per robot, with the associated
+# calibration procedure, to make it easy for people to add their own robot.
+
import json
import logging
import time
@@ -10,138 +16,10 @@
import torch
from lerobot.common.robot_devices.cameras.utils import Camera
-from lerobot.common.robot_devices.motors.dynamixel import (
- CalibrationMode,
- TorqueMode,
- convert_degrees_to_steps,
-)
from lerobot.common.robot_devices.motors.utils import MotorsBus
from lerobot.common.robot_devices.robots.utils import get_arm_id
from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
-########################################################################
-# Calibration logic
-########################################################################
-
-URL_TEMPLATE = (
- "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
-)
-
-# The following positions are provided in nominal degree range ]-180, +180[
-# For more info on these constants, see comments in the code where they get used.
-ZERO_POSITION_DEGREE = 0
-ROTATED_POSITION_DEGREE = 90
-
-
-def assert_drive_mode(drive_mode):
- # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted.
- if not np.all(np.isin(drive_mode, [0, 1])):
- raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})")
-
-
-def apply_drive_mode(position, drive_mode):
- assert_drive_mode(drive_mode)
- # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted,
- # to [-1, 1] with 1 indicates original rotation direction and -1 inverted.
- signed_drive_mode = -(drive_mode * 2 - 1)
- position *= signed_drive_mode
- return position
-
-
-def compute_nearest_rounded_position(position, models):
- delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models)
- nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn
- return nearest_pos.astype(position.dtype)
-
-
-def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str):
- """This function ensures that a neural network trained on data collected on a given robot
- can work on another robot. For instance before calibration, setting a same goal position
- for each motor of two different robots will get two very different positions. But after calibration,
- the two robots will move to the same position.To this end, this function computes the homing offset
- and the drive mode for each motor of a given robot.
-
- Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps
- to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions
- being 0. During the calibration process, you will need to manually move the robot to this "zero position".
-
- Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled
- in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot
- to the "rotated position".
-
- After calibration, the homing offsets and drive modes are stored in a cache.
-
- Example of usage:
- ```python
- run_arm_calibration(arm, "koch", "left", "follower")
- ```
- """
- if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
- raise ValueError("To run calibration, the torque must be disabled on all motors.")
-
- print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
-
- print("\nMove arm to zero position")
- print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero"))
- input("Press Enter to continue...")
-
- # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed.
- # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will
- # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position.
- zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models)
-
- # Compute homing offset so that `present_position + homing_offset ~= target_position`.
- zero_pos = arm.read("Present_Position")
- zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models)
- homing_offset = zero_target_pos - zero_nearest_pos
-
- # The rotated target position corresponds to a rotation of a quarter turn from the zero position.
- # This allows to identify the rotation direction of each motor.
- # For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction
- # is inverted. However, for the calibration being successful, we need everyone to follow the same target position.
- # Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which
- # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view
- # of the previous motor in the kinetic chain.
- print("\nMove arm to rotated target position")
- print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated"))
- input("Press Enter to continue...")
-
- rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models)
-
- # Find drive mode by rotating each motor by a quarter of a turn.
- # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0).
- rotated_pos = arm.read("Present_Position")
- drive_mode = (rotated_pos < zero_pos).astype(np.int32)
-
- # Re-compute homing offset to take into account drive mode
- rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode)
- rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models)
- homing_offset = rotated_target_pos - rotated_nearest_pos
-
- print("\nMove arm to rest position")
- print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest"))
- input("Press Enter to continue...")
- print()
-
- # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
- calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names)
-
- # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml?
- if robot_type == "aloha" and "gripper" in arm.motor_names:
- # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100]
- calib_idx = arm.motor_names.index("gripper")
- calib_mode[calib_idx] = CalibrationMode.LINEAR.name
-
- calib_data = {
- "homing_offset": homing_offset.tolist(),
- "drive_mode": drive_mode.tolist(),
- "start_pos": zero_pos.tolist(),
- "end_pos": rotated_pos.tolist(),
- "calib_mode": calib_mode,
- "motor_names": arm.motor_names,
- }
- return calib_data
-
def ensure_safe_goal_position(
goal_pos: torch.Tensor, present_pos: torch.Tensor, max_relative_target: float | list[float]
@@ -163,11 +41,6 @@ def ensure_safe_goal_position(
return safe_goal_pos
-########################################################################
-# Manipulator robot
-########################################################################
-
-
@dataclass
class ManipulatorRobotConfig:
"""
@@ -178,7 +51,7 @@ class ManipulatorRobotConfig:
"""
# Define all components of the robot
- robot_type: str | None = None
+ robot_type: str = "koch"
leader_arms: dict[str, MotorsBus] = field(default_factory=lambda: {})
follower_arms: dict[str, MotorsBus] = field(default_factory=lambda: {})
cameras: dict[str, Camera] = field(default_factory=lambda: {})
@@ -207,6 +80,10 @@ def __setattr__(self, prop: str, val):
)
super().__setattr__(prop, val)
+ def __post_init__(self):
+ if self.robot_type not in ["koch", "koch_bimanual", "aloha", "so100", "moss"]:
+ raise ValueError(f"Provided robot type ({self.robot_type}) is not supported.")
+
class ManipulatorRobot:
# TODO(rcadene): Implement force feedback
@@ -387,6 +264,11 @@ def connect(self):
print(f"Connecting {name} leader arm.")
self.leader_arms[name].connect()
+ if self.robot_type in ["koch", "koch_bimanual", "aloha"]:
+ from lerobot.common.robot_devices.motors.dynamixel import TorqueMode
+ elif self.robot_type in ["so100", "moss"]:
+ from lerobot.common.robot_devices.motors.feetech import TorqueMode
+
# We assume that at connection time, arms are in a rest position, and torque can
# be safely disabled to run calibration and/or set robot preset configurations.
for name in self.follower_arms:
@@ -397,12 +279,12 @@ def connect(self):
self.activate_calibration()
# Set robot preset (e.g. torque in leader gripper for Koch v1.1)
- if self.robot_type == "koch":
+ if self.robot_type in ["koch", "koch_bimanual"]:
self.set_koch_robot_preset()
elif self.robot_type == "aloha":
self.set_aloha_robot_preset()
- else:
- warnings.warn(f"No preset found for robot type: {self.robot_type}", stacklevel=1)
+ elif self.robot_type in ["so100", "moss"]:
+ self.set_so100_robot_preset()
# Enable torque on all motors of the follower arms
for name in self.follower_arms:
@@ -410,12 +292,22 @@ def connect(self):
self.follower_arms[name].write("Torque_Enable", 1)
if self.config.gripper_open_degree is not None:
+ if self.robot_type not in ["koch", "koch_bimanual"]:
+ raise NotImplementedError(
+ f"{self.robot_type} does not support position AND current control in the handle, which is require to set the gripper open."
+ )
# Set the leader arm in torque mode with the gripper motor set to an angle. This makes it possible
# to squeeze the gripper and have it spring back to an open position on its own.
for name in self.leader_arms:
self.leader_arms[name].write("Torque_Enable", 1, "gripper")
self.leader_arms[name].write("Goal_Position", self.config.gripper_open_degree, "gripper")
+ # Check both arms can be read
+ for name in self.follower_arms:
+ self.follower_arms[name].read("Present_Position")
+ for name in self.leader_arms:
+ self.leader_arms[name].read("Present_Position")
+
# Connect the cameras
for name in self.cameras:
self.cameras[name].connect()
@@ -436,8 +328,27 @@ def load_or_run_calibration_(name, arm, arm_type):
with open(arm_calib_path) as f:
calibration = json.load(f)
else:
+ # TODO(rcadene): display a warning in __init__ if calibration file not available
print(f"Missing calibration file '{arm_calib_path}'")
- calibration = run_arm_calibration(arm, self.robot_type, name, arm_type)
+
+ if self.robot_type in ["koch", "koch_bimanual", "aloha"]:
+ from lerobot.common.robot_devices.robots.dynamixel_calibration import run_arm_calibration
+
+ calibration = run_arm_calibration(arm, self.robot_type, name, arm_type)
+
+ elif self.robot_type in ["so100", "moss"]:
+ from lerobot.common.robot_devices.robots.feetech_calibration import (
+ run_arm_auto_calibration,
+ run_arm_manual_calibration,
+ )
+
+ # TODO(rcadene): better way to handle mocking + test run_arm_auto_calibration
+ if arm_type == "leader" or arm.mock:
+ calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type)
+ elif arm_type == "follower":
+ calibration = run_arm_auto_calibration(arm, self.robot_type, name, arm_type)
+ else:
+ raise ValueError(arm_type)
print(f"Calibration is done! Saving calibration file '{arm_calib_path}'")
arm_calib_path.parent.mkdir(parents=True, exist_ok=True)
@@ -455,6 +366,8 @@ def load_or_run_calibration_(name, arm, arm_type):
def set_koch_robot_preset(self):
def set_operating_mode_(arm):
+ from lerobot.common.robot_devices.motors.dynamixel import TorqueMode
+
if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
raise ValueError("To run set robot preset, the torque must be disabled on all motors.")
@@ -542,6 +455,23 @@ def set_shadow_(arm):
stacklevel=1,
)
+ def set_so100_robot_preset(self):
+ for name in self.follower_arms:
+ # Mode=0 for Position Control
+ self.follower_arms[name].write("Mode", 0)
+ # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
+ self.follower_arms[name].write("P_Coefficient", 16)
+ # Set I_Coefficient and D_Coefficient to default value 0 and 32
+ self.follower_arms[name].write("I_Coefficient", 0)
+ self.follower_arms[name].write("D_Coefficient", 32)
+ # Close the write lock so that Maximum_Acceleration gets written to EPROM address,
+ # which is mandatory for Maximum_Acceleration to take effect after rebooting.
+ self.follower_arms[name].write("Lock", 0)
+ # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of
+ # the motors. Note: this configuration is not in the official STS3215 Memory Table
+ self.follower_arms[name].write("Maximum_Acceleration", 254)
+ self.follower_arms[name].write("Acceleration", 254)
+
def teleop_step(
self, record_data=False
) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]:
diff --git a/lerobot/configs/env/moss_real.yaml b/lerobot/configs/env/moss_real.yaml
new file mode 100644
index 000000000..8e65d72f4
--- /dev/null
+++ b/lerobot/configs/env/moss_real.yaml
@@ -0,0 +1,10 @@
+# @package _global_
+
+fps: 30
+
+env:
+ name: real_world
+ task: null
+ state_dim: 6
+ action_dim: 6
+ fps: ${fps}
diff --git a/lerobot/configs/env/so100_real.yaml b/lerobot/configs/env/so100_real.yaml
new file mode 100644
index 000000000..8e65d72f4
--- /dev/null
+++ b/lerobot/configs/env/so100_real.yaml
@@ -0,0 +1,10 @@
+# @package _global_
+
+fps: 30
+
+env:
+ name: real_world
+ task: null
+ state_dim: 6
+ action_dim: 6
+ fps: ${fps}
diff --git a/lerobot/configs/policy/act_moss_real.yaml b/lerobot/configs/policy/act_moss_real.yaml
new file mode 100644
index 000000000..840a64e14
--- /dev/null
+++ b/lerobot/configs/policy/act_moss_real.yaml
@@ -0,0 +1,102 @@
+# @package _global_
+
+# Use `act_koch_real.yaml` to train on real-world datasets collected on Alexander Koch's robots.
+# Compared to `act.yaml`, it contains 2 cameras (i.e. laptop, phone) instead of 1 camera (i.e. top).
+# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps.
+# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script.
+# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy.
+#
+# Example of usage for training:
+# ```bash
+# python lerobot/scripts/train.py \
+# policy=act_koch_real \
+# env=koch_real
+# ```
+
+seed: 1000
+dataset_repo_id: lerobot/moss_pick_place_lego
+
+override_dataset_stats:
+ observation.images.laptop:
+ # stats from imagenet, since we use a pretrained vision model
+ mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1)
+ std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1)
+ observation.images.phone:
+ # stats from imagenet, since we use a pretrained vision model
+ mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1)
+ std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1)
+
+training:
+ offline_steps: 80000
+ online_steps: 0
+ eval_freq: -1
+ save_freq: 10000
+ log_freq: 100
+ save_checkpoint: true
+
+ batch_size: 8
+ lr: 1e-5
+ lr_backbone: 1e-5
+ weight_decay: 1e-4
+ grad_clip_norm: 10
+ online_steps_between_rollouts: 1
+
+ delta_timestamps:
+ action: "[i / ${fps} for i in range(${policy.chunk_size})]"
+
+eval:
+ n_episodes: 50
+ batch_size: 50
+
+# See `configuration_act.py` for more details.
+policy:
+ name: act
+
+ # Input / output structure.
+ n_obs_steps: 1
+ chunk_size: 100
+ n_action_steps: 100
+
+ input_shapes:
+ # TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env?
+ observation.images.laptop: [3, 480, 640]
+ observation.images.phone: [3, 480, 640]
+ observation.state: ["${env.state_dim}"]
+ output_shapes:
+ action: ["${env.action_dim}"]
+
+ # Normalization / Unnormalization
+ input_normalization_modes:
+ observation.images.laptop: mean_std
+ observation.images.phone: mean_std
+ observation.state: mean_std
+ output_normalization_modes:
+ action: mean_std
+
+ # Architecture.
+ # Vision backbone.
+ vision_backbone: resnet18
+ pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1
+ replace_final_stride_with_dilation: false
+ # Transformer layers.
+ pre_norm: false
+ dim_model: 512
+ n_heads: 8
+ dim_feedforward: 3200
+ feedforward_activation: relu
+ n_encoder_layers: 4
+ # Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code
+ # that means only the first layer is used. Here we match the original implementation by setting this to 1.
+ # See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521.
+ n_decoder_layers: 1
+ # VAE.
+ use_vae: true
+ latent_dim: 32
+ n_vae_encoder_layers: 4
+
+ # Inference.
+ temporal_ensemble_momentum: null
+
+ # Training and loss computation.
+ dropout: 0.1
+ kl_weight: 10.0
diff --git a/lerobot/configs/policy/act_so100_real.yaml b/lerobot/configs/policy/act_so100_real.yaml
new file mode 100644
index 000000000..3a0975b65
--- /dev/null
+++ b/lerobot/configs/policy/act_so100_real.yaml
@@ -0,0 +1,102 @@
+# @package _global_
+
+# Use `act_koch_real.yaml` to train on real-world datasets collected on Alexander Koch's robots.
+# Compared to `act.yaml`, it contains 2 cameras (i.e. laptop, phone) instead of 1 camera (i.e. top).
+# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps.
+# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script.
+# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy.
+#
+# Example of usage for training:
+# ```bash
+# python lerobot/scripts/train.py \
+# policy=act_koch_real \
+# env=koch_real
+# ```
+
+seed: 1000
+dataset_repo_id: lerobot/so100_pick_place_lego
+
+override_dataset_stats:
+ observation.images.laptop:
+ # stats from imagenet, since we use a pretrained vision model
+ mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1)
+ std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1)
+ observation.images.phone:
+ # stats from imagenet, since we use a pretrained vision model
+ mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1)
+ std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1)
+
+training:
+ offline_steps: 80000
+ online_steps: 0
+ eval_freq: -1
+ save_freq: 10000
+ log_freq: 100
+ save_checkpoint: true
+
+ batch_size: 8
+ lr: 1e-5
+ lr_backbone: 1e-5
+ weight_decay: 1e-4
+ grad_clip_norm: 10
+ online_steps_between_rollouts: 1
+
+ delta_timestamps:
+ action: "[i / ${fps} for i in range(${policy.chunk_size})]"
+
+eval:
+ n_episodes: 50
+ batch_size: 50
+
+# See `configuration_act.py` for more details.
+policy:
+ name: act
+
+ # Input / output structure.
+ n_obs_steps: 1
+ chunk_size: 100
+ n_action_steps: 100
+
+ input_shapes:
+ # TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env?
+ observation.images.laptop: [3, 480, 640]
+ observation.images.phone: [3, 480, 640]
+ observation.state: ["${env.state_dim}"]
+ output_shapes:
+ action: ["${env.action_dim}"]
+
+ # Normalization / Unnormalization
+ input_normalization_modes:
+ observation.images.laptop: mean_std
+ observation.images.phone: mean_std
+ observation.state: mean_std
+ output_normalization_modes:
+ action: mean_std
+
+ # Architecture.
+ # Vision backbone.
+ vision_backbone: resnet18
+ pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1
+ replace_final_stride_with_dilation: false
+ # Transformer layers.
+ pre_norm: false
+ dim_model: 512
+ n_heads: 8
+ dim_feedforward: 3200
+ feedforward_activation: relu
+ n_encoder_layers: 4
+ # Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code
+ # that means only the first layer is used. Here we match the original implementation by setting this to 1.
+ # See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521.
+ n_decoder_layers: 1
+ # VAE.
+ use_vae: true
+ latent_dim: 32
+ n_vae_encoder_layers: 4
+
+ # Inference.
+ temporal_ensemble_momentum: null
+
+ # Training and loss computation.
+ dropout: 0.1
+ kl_weight: 10.0
diff --git a/lerobot/configs/robot/aloha.yaml b/lerobot/configs/robot/aloha.yaml
index 51cde6a69..d8bca515f 100644
--- a/lerobot/configs/robot/aloha.yaml
+++ b/lerobot/configs/robot/aloha.yaml
@@ -1,11 +1,13 @@
-# Aloha: A Low-Cost Hardware for Bimanual Teleoperation
+# [Aloha: A Low-Cost Hardware for Bimanual Teleoperation](https://www.trossenrobotics.com/aloha-stationary)
# https://aloha-2.github.io
-# https://www.trossenrobotics.com/aloha-stationary
# Requires installing extras packages
# With pip: `pip install -e ".[dynamixel intelrealsense]"`
# With poetry: `poetry install --sync --extras "dynamixel intelrealsense"`
+# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/9_use_aloha.md)
+
+
_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot
robot_type: aloha
# Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been
diff --git a/lerobot/configs/robot/koch_bimanual.yaml b/lerobot/configs/robot/koch_bimanual.yaml
index 7f8138675..b551d15de 100644
--- a/lerobot/configs/robot/koch_bimanual.yaml
+++ b/lerobot/configs/robot/koch_bimanual.yaml
@@ -1,5 +1,5 @@
_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot
-robot_type: koch
+robot_type: koch_bimanual
calibration_dir: .cache/calibration/koch_bimanual
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
diff --git a/lerobot/configs/robot/moss.yaml b/lerobot/configs/robot/moss.yaml
new file mode 100644
index 000000000..8a9019851
--- /dev/null
+++ b/lerobot/configs/robot/moss.yaml
@@ -0,0 +1,56 @@
+# [Moss v1 robot arm](https://github.com/jess-moss/moss-robot-arms)
+
+# Requires installing extras packages
+# With pip: `pip install -e ".[feetech]"`
+# With poetry: `poetry install --sync --extras "feetech"`
+
+# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/11_use_moss.md)
+
+_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot
+robot_type: moss
+calibration_dir: .cache/calibration/moss
+
+# `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: null
+
+leader_arms:
+ main:
+ _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
+ port: /dev/tty.usbmodem58760431091
+ motors:
+ # name: (index, model)
+ shoulder_pan: [1, "sts3215"]
+ shoulder_lift: [2, "sts3215"]
+ elbow_flex: [3, "sts3215"]
+ wrist_flex: [4, "sts3215"]
+ wrist_roll: [5, "sts3215"]
+ gripper: [6, "sts3215"]
+
+follower_arms:
+ main:
+ _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
+ port: /dev/tty.usbmodem58760431191
+ motors:
+ # name: (index, model)
+ shoulder_pan: [1, "sts3215"]
+ shoulder_lift: [2, "sts3215"]
+ elbow_flex: [3, "sts3215"]
+ wrist_flex: [4, "sts3215"]
+ wrist_roll: [5, "sts3215"]
+ gripper: [6, "sts3215"]
+
+cameras:
+ laptop:
+ _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
+ camera_index: 0
+ fps: 30
+ width: 640
+ height: 480
+ phone:
+ _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
+ camera_index: 1
+ fps: 30
+ width: 640
+ height: 480
diff --git a/lerobot/configs/robot/so100.yaml b/lerobot/configs/robot/so100.yaml
new file mode 100644
index 000000000..ec6f3e3fe
--- /dev/null
+++ b/lerobot/configs/robot/so100.yaml
@@ -0,0 +1,56 @@
+# [SO-100 robot arm](https://github.com/TheRobotStudio/SO-ARM100)
+
+# Requires installing extras packages
+# With pip: `pip install -e ".[feetech]"`
+# With poetry: `poetry install --sync --extras "feetech"`
+
+# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/10_use_so100.md)
+
+_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot
+robot_type: so100
+calibration_dir: .cache/calibration/so100
+
+# `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: null
+
+leader_arms:
+ main:
+ _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
+ port: /dev/tty.usbmodem585A0077581
+ motors:
+ # name: (index, model)
+ shoulder_pan: [1, "sts3215"]
+ shoulder_lift: [2, "sts3215"]
+ elbow_flex: [3, "sts3215"]
+ wrist_flex: [4, "sts3215"]
+ wrist_roll: [5, "sts3215"]
+ gripper: [6, "sts3215"]
+
+follower_arms:
+ main:
+ _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus
+ port: /dev/tty.usbmodem585A0080971
+ motors:
+ # name: (index, model)
+ shoulder_pan: [1, "sts3215"]
+ shoulder_lift: [2, "sts3215"]
+ elbow_flex: [3, "sts3215"]
+ wrist_flex: [4, "sts3215"]
+ wrist_roll: [5, "sts3215"]
+ gripper: [6, "sts3215"]
+
+cameras:
+ laptop:
+ _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
+ camera_index: 0
+ fps: 30
+ width: 640
+ height: 480
+ phone:
+ _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera
+ camera_index: 1
+ fps: 30
+ width: 640
+ height: 480
diff --git a/lerobot/configs/robot/stretch.yaml b/lerobot/configs/robot/stretch.yaml
index 6d9f0be85..e29966b6f 100644
--- a/lerobot/configs/robot/stretch.yaml
+++ b/lerobot/configs/robot/stretch.yaml
@@ -1,3 +1,12 @@
+# [Stretch3 from Hello Robot](https://hello-robot.com/stretch-3-product)
+
+# Requires installing extras packages
+# With pip: `pip install -e ".[stretch]"`
+# With poetry: `poetry install --sync --extras "stretch"`
+
+# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/8_use_stretch.md)
+
+
_target_: lerobot.common.robot_devices.robots.stretch.StretchRobot
robot_type: stretch3
diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py
new file mode 100644
index 000000000..18707397f
--- /dev/null
+++ b/lerobot/scripts/configure_motor.py
@@ -0,0 +1,145 @@
+"""
+This script configure a single motor at a time to a given ID and baudrate.
+
+Example of usage:
+```bash
+python lerobot/scripts/configure_motor.py \
+ --port /dev/tty.usbmodem585A0080521 \
+ --brand feetech \
+ --model sts3215 \
+ --baudrate 1000000 \
+ --ID 1
+```
+"""
+
+import argparse
+import time
+
+
+def configure_motor(port, brand, model, motor_idx_des, baudrate_des):
+ if brand == "feetech":
+ from lerobot.common.robot_devices.motors.feetech import MODEL_BAUDRATE_TABLE
+ from lerobot.common.robot_devices.motors.feetech import (
+ SCS_SERIES_BAUDRATE_TABLE as SERIES_BAUDRATE_TABLE,
+ )
+ from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus as MotorsBusClass
+ elif brand == "dynamixel":
+ from lerobot.common.robot_devices.motors.dynamixel import MODEL_BAUDRATE_TABLE
+ from lerobot.common.robot_devices.motors.dynamixel import (
+ X_SERIES_BAUDRATE_TABLE as SERIES_BAUDRATE_TABLE,
+ )
+ from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus as MotorsBusClass
+ else:
+ raise ValueError(
+ f"Currently we do not support this motor brand: {brand}. We currently support feetech and dynamixel motors."
+ )
+
+ # Check if the provided model exists in the model_baud_rate_table
+ if model not in MODEL_BAUDRATE_TABLE:
+ raise ValueError(
+ f"Invalid model '{model}' for brand '{brand}'. Supported models: {list(MODEL_BAUDRATE_TABLE.keys())}"
+ )
+
+ # Setup motor names, indices, and models
+ motor_name = "motor"
+ motor_index_arbitrary = motor_idx_des # Use the motor ID passed via argument
+ motor_model = model # Use the motor model passed via argument
+
+ # Initialize the MotorBus with the correct port and motor configurations
+ motor_bus = MotorsBusClass(port=port, motors={motor_name: (motor_index_arbitrary, motor_model)})
+
+ # Try to connect to the motor bus and handle any connection-specific errors
+ try:
+ motor_bus.connect()
+ print(f"Connected on port {motor_bus.port}")
+ except OSError as e:
+ print(f"Error occurred when connecting to the motor bus: {e}")
+ return
+
+ # Motor bus is connected, proceed with the rest of the operations
+ try:
+ print("Scanning all baudrates and motor indices")
+ all_baudrates = set(SERIES_BAUDRATE_TABLE.values())
+ motor_index = -1 # Set the motor index to an out-of-range value.
+
+ for baudrate in all_baudrates:
+ motor_bus.set_bus_baudrate(baudrate)
+ present_ids = motor_bus.find_motor_indices(list(range(1, 10)))
+ if len(present_ids) > 1:
+ raise ValueError(
+ "Error: More than one motor ID detected. This script is designed to only handle one motor at a time. Please disconnect all but one motor."
+ )
+
+ if len(present_ids) == 1:
+ if motor_index != -1:
+ raise ValueError(
+ "Error: More than one motor ID detected. This script is designed to only handle one motor at a time. Please disconnect all but one motor."
+ )
+ motor_index = present_ids[0]
+
+ if motor_index == -1:
+ raise ValueError("No motors detected. Please ensure you have one motor connected.")
+
+ print(f"Motor index found at: {motor_index}")
+
+ if brand == "feetech":
+ # Allows ID and BAUDRATE to be written in memory
+ motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0)
+
+ if baudrate != baudrate_des:
+ print(f"Setting its baudrate to {baudrate_des}")
+ baudrate_idx = list(SERIES_BAUDRATE_TABLE.values()).index(baudrate_des)
+
+ # The write can fail, so we allow retries
+ motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Baud_Rate", baudrate_idx)
+ time.sleep(0.5)
+ motor_bus.set_bus_baudrate(baudrate_des)
+ present_baudrate_idx = motor_bus.read_with_motor_ids(
+ motor_bus.motor_models, motor_index, "Baud_Rate", num_retry=2
+ )
+
+ if present_baudrate_idx != baudrate_idx:
+ raise OSError("Failed to write baudrate.")
+
+ print(f"Setting its index to desired index {motor_idx_des}")
+ motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0)
+ motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "ID", motor_idx_des)
+
+ present_idx = motor_bus.read_with_motor_ids(motor_bus.motor_models, motor_idx_des, "ID", num_retry=2)
+ if present_idx != motor_idx_des:
+ raise OSError("Failed to write index.")
+
+ if brand == "feetech":
+ # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of
+ # the motors. Note: this configuration is not in the official STS3215 Memory Table
+ motor_bus.write("Lock", 0)
+ motor_bus.write("Maximum_Acceleration", 254)
+
+ motor_bus.write("Goal_Position", 2048)
+ time.sleep(4)
+ print("Present Position", motor_bus.read("Present_Position"))
+
+ motor_bus.write("Offset", 0)
+ time.sleep(4)
+ print("Offset", motor_bus.read("Offset"))
+
+ except Exception as e:
+ print(f"Error occurred during motor configuration: {e}")
+
+ finally:
+ motor_bus.disconnect()
+ print("Disconnected from motor bus.")
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser()
+ parser.add_argument("--port", type=str, required=True, help="Motors bus port (e.g. dynamixel,feetech)")
+ parser.add_argument("--brand", type=str, required=True, help="Motor brand (e.g. dynamixel,feetech)")
+ parser.add_argument("--model", type=str, required=True, help="Motor model (e.g. xl330-m077,sts3215)")
+ parser.add_argument("--ID", type=int, required=True, help="Desired ID of the current motor (e.g. 1,2,3)")
+ parser.add_argument(
+ "--baudrate", type=int, default=1000000, help="Desired baudrate for the motor (default: 1000000)"
+ )
+ args = parser.parse_args()
+
+ configure_motor(args.port, args.brand, args.model, args.ID, args.baudrate)
diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py
index 425247e65..031e608e7 100644
--- a/lerobot/scripts/control_robot.py
+++ b/lerobot/scripts/control_robot.py
@@ -144,6 +144,9 @@ def calibrate(robot: Robot, arms: list[str] | None):
robot.home()
return
+ if arms is None:
+ arms = robot.available_arms
+
unknown_arms = [arm_id for arm_id in arms if arm_id not in robot.available_arms]
available_arms_str = " ".join(robot.available_arms)
unknown_arms_str = " ".join(unknown_arms)
diff --git a/lerobot/scripts/find_motors_bus_port.py b/lerobot/scripts/find_motors_bus_port.py
new file mode 100644
index 000000000..51ef6d41c
--- /dev/null
+++ b/lerobot/scripts/find_motors_bus_port.py
@@ -0,0 +1,36 @@
+import time
+from pathlib import Path
+
+
+def find_available_ports():
+ ports = []
+ for path in Path("/dev").glob("tty*"):
+ ports.append(str(path))
+ return ports
+
+
+def find_port():
+ print("Finding all available ports for the MotorsBus.")
+ ports_before = find_available_ports()
+ print(ports_before)
+
+ print("Remove the usb cable from your MotorsBus and press Enter when done.")
+ input()
+
+ time.sleep(0.5)
+ ports_after = find_available_ports()
+ ports_diff = list(set(ports_before) - set(ports_after))
+
+ if len(ports_diff) == 1:
+ port = ports_diff[0]
+ print(f"The port of this MotorsBus is '{port}'")
+ print("Reconnect the usb cable.")
+ elif len(ports_diff) == 0:
+ raise OSError(f"Could not detect the port. No difference was found ({ports_diff}).")
+ else:
+ raise OSError(f"Could not detect the port. More than one port was found ({ports_diff}).")
+
+
+if __name__ == "__main__":
+ # Helper to find the usb port associated to all your MotorsBus.
+ find_port()
diff --git a/media/moss/follower_initial.webp b/media/moss/follower_initial.webp
new file mode 100644
index 000000000..e7ded16bd
Binary files /dev/null and b/media/moss/follower_initial.webp differ
diff --git a/media/moss/leader_rest.webp b/media/moss/leader_rest.webp
new file mode 100644
index 000000000..cd77d294d
Binary files /dev/null and b/media/moss/leader_rest.webp differ
diff --git a/media/moss/leader_rotated.webp b/media/moss/leader_rotated.webp
new file mode 100644
index 000000000..c3426650a
Binary files /dev/null and b/media/moss/leader_rotated.webp differ
diff --git a/media/moss/leader_zero.webp b/media/moss/leader_zero.webp
new file mode 100644
index 000000000..d79ed3736
Binary files /dev/null and b/media/moss/leader_zero.webp differ
diff --git a/media/so100/follower_initial.webp b/media/so100/follower_initial.webp
new file mode 100644
index 000000000..7f93a773a
Binary files /dev/null and b/media/so100/follower_initial.webp differ
diff --git a/media/so100/leader_follower.webp b/media/so100/leader_follower.webp
new file mode 100644
index 000000000..83cf4b231
Binary files /dev/null and b/media/so100/leader_follower.webp differ
diff --git a/media/so100/leader_rest.webp b/media/so100/leader_rest.webp
new file mode 100644
index 000000000..351667778
Binary files /dev/null and b/media/so100/leader_rest.webp differ
diff --git a/media/so100/leader_rotated.webp b/media/so100/leader_rotated.webp
new file mode 100644
index 000000000..1f770f6ce
Binary files /dev/null and b/media/so100/leader_rotated.webp differ
diff --git a/media/so100/leader_zero.webp b/media/so100/leader_zero.webp
new file mode 100644
index 000000000..5f8c235f9
Binary files /dev/null and b/media/so100/leader_zero.webp differ
diff --git a/poetry.lock b/poetry.lock
index fbf0431bc..bb82228de 100644
--- a/poetry.lock
+++ b/poetry.lock
@@ -1,4 +1,4 @@
-# This file is automatically @generated by Poetry 1.8.4 and should not be changed by hand.
+# This file is automatically @generated by Poetry 1.8.2 and should not be changed by hand.
[[package]]
name = "absl-py"
@@ -1292,10 +1292,6 @@ files = [
{file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:78656d3ae1282a142a5fed410ec3a6f725fdf8d9f9192ed673e336ea3b083e12"},
{file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:681e22c8ecb3b48d11cb9019f8a32d4ae1e353e20d4ce3a0f0eedd0ccbd95e5f"},
{file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4598572bab6f726ec41fabb43bf0f7e3cf8082ea0f6f8f4e57845a6c919f31b3"},
- {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:157fc1fed50946646f09df75c6d52198735a5973e53d252199bbb1c65e1594d2"},
- {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_armv7l.whl", hash = "sha256:7ae2724c181be10692c24fb8d9ce2a99a9afc57237332c3658e2ea6f4f33c091"},
- {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_i686.whl", hash = "sha256:3d324835f292edd81b962f8c0df44f7f47c0a6f8fe6f7d081951aeb1f5ba57d2"},
- {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:474c087b5e584293685a7d4837165b2ead96dc74fb435ae50d5fa0ac168a0de0"},
{file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:297350f05f5f87a0bf647a1e5b4446728e5f800788c6bb28b462bcd167f1de7f"},
{file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:b1870a8e30f0ac298d17fd546224348d13a648bcfa0cbc51dba7e5136c1af928"},
{file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:182a189212d41be0c960fd3299bf6731af2e771f8858cfb1be7ebcc17d60a254"},
@@ -1417,6 +1413,19 @@ files = [
[package.extras]
devel = ["colorama", "json-spec", "jsonschema", "pylint", "pytest", "pytest-benchmark", "pytest-cache", "validictory"]
+[[package]]
+name = "feetech-servo-sdk"
+version = "1.0.0"
+description = "This is source code from official feetech repository"
+optional = true
+python-versions = "*"
+files = [
+ {file = "feetech-servo-sdk-1.0.0.tar.gz", hash = "sha256:d4d3832e4b1b22a8222133a414db9f868224c2fb639426a1b11d96ddfe84e69c"},
+]
+
+[package.dependencies]
+pyserial = "*"
+
[[package]]
name = "filelock"
version = "3.16.1"
@@ -7420,6 +7429,7 @@ aloha = ["gym-aloha"]
dev = ["debugpy", "pre-commit"]
dora = ["gym-dora"]
dynamixel = ["dynamixel-sdk", "pynput"]
+feetech = ["feetech-servo-sdk", "pynput"]
intelrealsense = ["pyrealsense2"]
pusht = ["gym-pusht"]
stretch = ["hello-robot-stretch-body", "pynput", "pyrealsense2", "pyrender"]
@@ -7431,4 +7441,4 @@ xarm = ["gym-xarm"]
[metadata]
lock-version = "2.0"
python-versions = ">=3.10,<3.13"
-content-hash = "cd59da219818a9906018a25462e76e15c5d2c0e6419531e8ddbdc2ae998854c1"
+content-hash = "7ff63d36a5524a77cba916d212741082adcb49dfdc0dc49f8bf8ccee53c02254"
diff --git a/pyproject.toml b/pyproject.toml
index ee898db80..42cdf5813 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -65,6 +65,7 @@ pandas = {version = ">=2.2.2", optional = true}
scikit-image = {version = ">=0.23.2", optional = true}
dynamixel-sdk = {version = ">=3.7.31", optional = true}
pynput = {version = ">=1.7.7", optional = true}
+feetech-servo-sdk = {version = ">=1.0.0", optional = true}
setuptools = {version = "!=71.0.1", optional = true} # TODO(rcadene, aliberts): 71.0.1 has a bug
pyrealsense2 = {version = ">=2.55.1.6486", markers = "sys_platform != 'darwin'", optional = true} # TODO(rcadene, aliberts): Fix on Mac
pyrender = {git = "https://github.com/mmatl/pyrender.git", markers = "sys_platform == 'linux'", optional = true}
@@ -82,6 +83,7 @@ test = ["pytest", "pytest-cov", "pyserial"]
umi = ["imagecodecs"]
video_benchmark = ["scikit-image", "pandas"]
dynamixel = ["dynamixel-sdk", "pynput"]
+feetech = ["feetech-servo-sdk", "pynput"]
intelrealsense = ["pyrealsense2"]
stretch = ["hello-robot-stretch-body", "pyrender", "pyrealsense2", "pynput"]
diff --git a/tests/mock_dynamixel_sdk.py b/tests/mock_dynamixel_sdk.py
index 6d0ed20e5..a790dff05 100644
--- a/tests/mock_dynamixel_sdk.py
+++ b/tests/mock_dynamixel_sdk.py
@@ -18,6 +18,19 @@ def convert_to_bytes(value, bytes):
return value
+def get_default_motor_values(motor_index):
+ return {
+ # Key (int) are from X_SERIES_CONTROL_TABLE
+ 7: motor_index, # ID
+ 8: DEFAULT_BAUDRATE, # Baud_rate
+ 10: 0, # Drive_Mode
+ 64: 0, # Torque_Enable
+ # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144
+ # For other joints, 2560 will be autocorrected to be in calibration range
+ 132: 2560, # Present_Position
+ }
+
+
class PortHandler:
def __init__(self, port):
self.port = port
@@ -52,18 +65,9 @@ def __init__(self, port_handler, packet_handler, address, bytes):
self.packet_handler = packet_handler
def addParam(self, motor_index): # noqa: N802
+ # Initialize motor default values
if motor_index not in self.packet_handler.data:
- # Initialize motor default values
- self.packet_handler.data[motor_index] = {
- # Key (int) are from X_SERIES_CONTROL_TABLE
- 7: motor_index, # ID
- 8: DEFAULT_BAUDRATE, # Baud_rate
- 10: 0, # Drive_Mode
- 64: 0, # Torque_Enable
- # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144
- # For other joints, 2560 will be autocorrected to be in calibration range
- 132: 2560, # Present_Position
- }
+ self.packet_handler.data[motor_index] = get_default_motor_values(motor_index)
def txRxPacket(self): # noqa: N802
return COMM_SUCCESS
@@ -78,6 +82,9 @@ def __init__(self, port_handler, packet_handler, address, bytes):
self.address = address
def addParam(self, index, data): # noqa: N802
+ # Initialize motor default values
+ if index not in self.packet_handler.data:
+ self.packet_handler.data[index] = get_default_motor_values(index)
self.changeParam(index, data)
def txPacket(self): # noqa: N802
diff --git a/tests/mock_scservo_sdk.py b/tests/mock_scservo_sdk.py
new file mode 100644
index 000000000..596978c00
--- /dev/null
+++ b/tests/mock_scservo_sdk.py
@@ -0,0 +1,103 @@
+"""Mocked classes and functions from dynamixel_sdk to allow for continuous integration
+and testing code logic that requires hardware and devices (e.g. robot arms, cameras)
+
+Warning: These mocked versions are minimalist. They do not exactly mock every behaviors
+from the original classes and functions (e.g. return types might be None instead of boolean).
+"""
+
+# from dynamixel_sdk import COMM_SUCCESS
+
+DEFAULT_BAUDRATE = 1_000_000
+COMM_SUCCESS = 0 # tx or rx packet communication success
+
+
+def convert_to_bytes(value, bytes):
+ # TODO(rcadene): remove need to mock `convert_to_bytes` by implemented the inverse transform
+ # `convert_bytes_to_value`
+ del bytes # unused
+ return value
+
+
+def get_default_motor_values(motor_index):
+ return {
+ # Key (int) are from SCS_SERIES_CONTROL_TABLE
+ 5: motor_index, # ID
+ 6: DEFAULT_BAUDRATE, # Baud_rate
+ 10: 0, # Drive_Mode
+ 21: 32, # P_Coefficient
+ 22: 32, # D_Coefficient
+ 23: 0, # I_Coefficient
+ 40: 0, # Torque_Enable
+ 41: 254, # Acceleration
+ 31: -2047, # Offset
+ 33: 0, # Mode
+ 55: 1, # Lock
+ # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144
+ # For other joints, 2560 will be autocorrected to be in calibration range
+ 56: 2560, # Present_Position
+ 58: 0, # Present_Speed
+ 69: 0, # Present_Current
+ 85: 150, # Maximum_Acceleration
+ }
+
+
+class PortHandler:
+ def __init__(self, port):
+ self.port = port
+ # factory default baudrate
+ self.baudrate = DEFAULT_BAUDRATE
+
+ def openPort(self): # noqa: N802
+ return True
+
+ def closePort(self): # noqa: N802
+ pass
+
+ def setPacketTimeoutMillis(self, timeout_ms): # noqa: N802
+ del timeout_ms # unused
+
+ def getBaudRate(self): # noqa: N802
+ return self.baudrate
+
+ def setBaudRate(self, baudrate): # noqa: N802
+ self.baudrate = baudrate
+
+
+class PacketHandler:
+ def __init__(self, protocol_version):
+ del protocol_version # unused
+ # Use packet_handler.data to communicate across Read and Write
+ self.data = {}
+
+
+class GroupSyncRead:
+ def __init__(self, port_handler, packet_handler, address, bytes):
+ self.packet_handler = packet_handler
+
+ def addParam(self, motor_index): # noqa: N802
+ # Initialize motor default values
+ if motor_index not in self.packet_handler.data:
+ self.packet_handler.data[motor_index] = get_default_motor_values(motor_index)
+
+ def txRxPacket(self): # noqa: N802
+ return COMM_SUCCESS
+
+ def getData(self, index, address, bytes): # noqa: N802
+ return self.packet_handler.data[index][address]
+
+
+class GroupSyncWrite:
+ def __init__(self, port_handler, packet_handler, address, bytes):
+ self.packet_handler = packet_handler
+ self.address = address
+
+ def addParam(self, index, data): # noqa: N802
+ if index not in self.packet_handler.data:
+ self.packet_handler.data[index] = get_default_motor_values(index)
+ self.changeParam(index, data)
+
+ def txPacket(self): # noqa: N802
+ return COMM_SUCCESS
+
+ def changeParam(self, index, data): # noqa: N802
+ self.packet_handler.data[index][self.address] = data
diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py
index 2c0bca9b6..97ce28a64 100644
--- a/tests/test_control_robot.py
+++ b/tests/test_control_robot.py
@@ -36,7 +36,7 @@
from lerobot.scripts.control_robot import calibrate, record, replay, teleoperate
from lerobot.scripts.train import make_optimizer_and_scheduler
from tests.test_robots import make_robot
-from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, require_robot
+from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, mock_calibration_dir, require_robot
@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES)
@@ -49,6 +49,7 @@ def test_teleoperate(tmpdir, request, robot_type, mock):
# and avoid writing calibration files in user .cache/calibration folder
tmpdir = Path(tmpdir)
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False
@@ -89,6 +90,7 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock):
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = Path(tmpdir) / robot_type
+ mock_calibration_dir(calibration_dir)
overrides.append(f"calibration_dir={calibration_dir}")
root = Path(tmpdir) / "data"
@@ -121,6 +123,7 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock):
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False or for aloha
@@ -162,6 +165,12 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock):
elif robot_type in ["koch", "koch_bimanual"]:
env_name = "koch_real"
policy_name = "act_koch_real"
+ elif robot_type == "so100":
+ env_name = "so100_real"
+ policy_name = "act_so100_real"
+ elif robot_type == "moss":
+ env_name = "moss_real"
+ policy_name = "act_moss_real"
else:
raise NotImplementedError(robot_type)
@@ -248,6 +257,7 @@ def test_resume_record(tmpdir, request, robot_type, mock):
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False or for aloha
@@ -311,6 +321,7 @@ def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock):
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False or for aloha
@@ -360,6 +371,7 @@ def test_record_with_event_exit_early(tmpdir, request, robot_type, mock):
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False or for aloha
@@ -410,6 +422,7 @@ def test_record_with_event_stop_recording(tmpdir, request, robot_type, mock, num
# Create an empty calibration directory to trigger manual calibration
# and avoid writing calibration files in user .cache/calibration folder
calibration_dir = tmpdir / robot_type
+ mock_calibration_dir(calibration_dir)
overrides = [f"calibration_dir={calibration_dir}"]
else:
# Use the default .cache/calibration folder when mock=False or for aloha
diff --git a/tests/test_motors.py b/tests/test_motors.py
index 672234071..2f668926c 100644
--- a/tests/test_motors.py
+++ b/tests/test_motors.py
@@ -30,8 +30,8 @@
import numpy as np
import pytest
-from lerobot.common.robot_devices.motors.dynamixel import find_port
from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
+from lerobot.scripts.find_motors_bus_port import find_port
from tests.utils import TEST_MOTOR_TYPES, make_motors_bus, require_motor
@@ -52,12 +52,24 @@ def test_configure_motors_all_ids_1(request, motor_type, mock):
if mock:
request.getfixturevalue("patch_builtins_input")
+ if motor_type == "dynamixel":
+ # see X_SERIES_BAUDRATE_TABLE
+ smaller_baudrate = 9_600
+ smaller_baudrate_value = 0
+ elif motor_type == "feetech":
+ # see SCS_SERIES_BAUDRATE_TABLE
+ smaller_baudrate = 19_200
+ smaller_baudrate_value = 7
+ else:
+ raise ValueError(motor_type)
+
input("Are you sure you want to re-configure the motors? Press enter to continue...")
# This test expect the configuration was already correct.
motors_bus = make_motors_bus(motor_type, mock=mock)
motors_bus.connect()
- motors_bus.write("Baud_Rate", [0] * len(motors_bus.motors))
- motors_bus.set_bus_baudrate(9_600)
+ motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus.motors))
+
+ motors_bus.set_bus_baudrate(smaller_baudrate)
motors_bus.write("ID", [1] * len(motors_bus.motors))
del motors_bus
diff --git a/tests/test_robots.py b/tests/test_robots.py
index 13ad8c450..05966ff15 100644
--- a/tests/test_robots.py
+++ b/tests/test_robots.py
@@ -30,7 +30,7 @@
from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot
from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError
-from tests.utils import TEST_ROBOT_TYPES, make_robot, require_robot
+from tests.utils import TEST_ROBOT_TYPES, make_robot, mock_calibration_dir, require_robot
@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES)
@@ -39,7 +39,6 @@ def test_robot(tmpdir, request, robot_type, mock):
# TODO(rcadene): measure fps in nightly?
# TODO(rcadene): test logs
# TODO(rcadene): add compatibility with other robots
-
robot_kwargs = {"robot_type": robot_type}
if robot_type == "aloha" and mock:
@@ -54,6 +53,7 @@ def test_robot(tmpdir, request, robot_type, mock):
tmpdir = Path(tmpdir)
calibration_dir = tmpdir / robot_type
overrides_calibration_dir = [f"calibration_dir={calibration_dir}"]
+ mock_calibration_dir(calibration_dir)
robot_kwargs["calibration_dir"] = calibration_dir
# Test connecting without devices raises an error
diff --git a/tests/utils.py b/tests/utils.py
index 0c4b94d89..f24b3551c 100644
--- a/tests/utils.py
+++ b/tests/utils.py
@@ -13,10 +13,12 @@
# 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 json
import os
import platform
from copy import copy
from functools import wraps
+from pathlib import Path
import pytest
import torch
@@ -52,7 +54,7 @@
OPENCV_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_OPENCV_CAMERA_INDEX", 0))
INTELREALSENSE_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_INTELREALSENSE_CAMERA_INDEX", 128422271614))
-DYNAMIXEL_PORT = "/dev/tty.usbmodem575E0032081"
+DYNAMIXEL_PORT = os.environ.get("LEROBOT_TEST_DYNAMIXEL_PORT", "/dev/tty.usbmodem575E0032081")
DYNAMIXEL_MOTORS = {
"shoulder_pan": [1, "xl430-w250"],
"shoulder_lift": [2, "xl430-w250"],
@@ -62,6 +64,16 @@
"gripper": [6, "xl330-m288"],
}
+FEETECH_PORT = os.environ.get("LEROBOT_TEST_FEETECH_PORT", "/dev/tty.usbmodem585A0080971")
+FEETECH_MOTORS = {
+ "shoulder_pan": [1, "sts3215"],
+ "shoulder_lift": [2, "sts3215"],
+ "elbow_flex": [3, "sts3215"],
+ "wrist_flex": [4, "sts3215"],
+ "wrist_roll": [5, "sts3215"],
+ "gripper": [6, "sts3215"],
+}
+
def require_x86_64_kernel(func):
"""
@@ -271,13 +283,39 @@ def wrapper(*args, **kwargs):
return wrapper
+def mock_calibration_dir(calibration_dir):
+ # TODO(rcadene): remove this hack
+ # calibration file produced with Moss v1, but works with Koch, Koch bimanual and SO-100
+ example_calib = {
+ "homing_offset": [-1416, -845, 2130, 2872, 1950, -2211],
+ "drive_mode": [0, 0, 1, 1, 1, 0],
+ "start_pos": [1442, 843, 2166, 2849, 1988, 1835],
+ "end_pos": [2440, 1869, -1106, -1848, -926, 3235],
+ "calib_mode": ["DEGREE", "DEGREE", "DEGREE", "DEGREE", "DEGREE", "LINEAR"],
+ "motor_names": ["shoulder_pan", "shoulder_lift", "elbow_flex", "wrist_flex", "wrist_roll", "gripper"],
+ }
+ Path(str(calibration_dir)).mkdir(parents=True, exist_ok=True)
+ with open(calibration_dir / "main_follower.json", "w") as f:
+ json.dump(example_calib, f)
+ with open(calibration_dir / "main_leader.json", "w") as f:
+ json.dump(example_calib, f)
+ with open(calibration_dir / "left_follower.json", "w") as f:
+ json.dump(example_calib, f)
+ with open(calibration_dir / "left_leader.json", "w") as f:
+ json.dump(example_calib, f)
+ with open(calibration_dir / "right_follower.json", "w") as f:
+ json.dump(example_calib, f)
+ with open(calibration_dir / "right_leader.json", "w") as f:
+ json.dump(example_calib, f)
+
+
def make_robot(robot_type: str, overrides: list[str] | None = None, mock=False) -> Robot:
if mock:
overrides = [] if overrides is None else copy(overrides)
# Explicitely add mock argument to the cameras and set it to true
# TODO(rcadene, aliberts): redesign when we drop hydra
- if robot_type == "koch":
+ if robot_type in ["koch", "so100", "moss"]:
overrides.append("+leader_arms.main.mock=true")
overrides.append("+follower_arms.main.mock=true")
if "~cameras" not in overrides:
@@ -338,5 +376,12 @@ def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus:
motors = kwargs.pop("motors", DYNAMIXEL_MOTORS)
return DynamixelMotorsBus(port, motors, **kwargs)
+ elif motor_type == "feetech":
+ from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus
+
+ port = kwargs.pop("port", FEETECH_PORT)
+ motors = kwargs.pop("motors", FEETECH_MOTORS)
+ return FeetechMotorsBus(port, motors, **kwargs)
+
else:
raise ValueError(f"The motor type '{motor_type}' is not valid.")