|
# Imitation Learning on Real-World Robots
|
|
|
|
This tutorial will explain how to train a neural network to control a real robot autonomously.
|
|
|
|
**You'll learn:**
|
|
1. How to record and visualize your dataset.
|
|
2. How to train a policy using your data and prepare it for evaluation.
|
|
3. How to evaluate your policy and visualize the results.
|
|
|
|
By following these steps, you'll be able to replicate tasks, such as picking up a Lego block and placing it in a bin with a high success rate, as shown in the video below.
|
|
|
|
<details>
|
|
<summary><strong>Video: pickup lego block task</strong></summary>
|
|
|
|
<div class="video-container">
|
|
<video controls width="600">
|
|
<source src="https://huggingface.co/datasets/huggingface/documentation-images/resolve/main/lerobot/lerobot_task.mp4" type="video/mp4" />
|
|
</video>
|
|
</div>
|
|
|
|
</details>
|
|
|
|
This tutorial isn’t tied to a specific robot: we walk you through the commands and API snippets you can adapt for any supported platform.
|
|
|
|
During data collection, you’ll use a “teloperation” device, such as a leader arm or keyboard to teleoperate the robot and record its motion trajectories.
|
|
|
|
Once you’ve gathered enough trajectories, you’ll train a neural network to imitate these trajectories and deploy the trained model so your robot can perform the task autonomously.
|
|
|
|
If you run into any issues at any point, jump into our [Discord community](https://discord.com/invite/s3KuuzsPFb) for support.
|
|
|
|
## Set up and Calibrate
|
|
|
|
If you haven't yet set up and calibrated your robot and teleop device, please do so by following the robot-specific tutorial.
|
|
|
|
## Teleoperate
|
|
|
|
In this example, we’ll demonstrate how to teleoperate the SO101 robot. For each command, we also provide a corresponding API example.
|
|
|
|
Note that the `id` associated with a robot is used to store the calibration file. It's important to use the same `id` when teleoperating, recording, and evaluating when using the same setup.
|
|
|
|
<hfoptions id="teleoperate_so101">
|
|
<hfoption id="Command">
|
|
```bash
|
|
python -m lerobot.teleoperate \
|
|
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
</hfoption>
|
|
<hfoption id="API example">
|
|
```python
|
|
from lerobot.common.teleoperators.so101_leader import SO101LeaderConfig, SO101Leader
|
|
from lerobot.common.robots.so101_follower import SO101FollowerConfig, SO101Follower
|
|
|
|
robot_config = SO101FollowerConfig(
|
|
port="/dev/tty.usbmodem58760431541",
|
|
id="my_red_robot_arm",
|
|
)
|
|
|
|
teleop_config = SO101LeaderConfig(
|
|
port="/dev/tty.usbmodem58760431551",
|
|
id="my_blue_leader_arm",
|
|
)
|
|
|
|
robot = SO101Follower(robot_config)
|
|
teleop_device = SO101Leader(teleop_config)
|
|
robot.connect()
|
|
teleop_device.connect()
|
|
|
|
while True:
|
|
action = teleop_device.get_action()
|
|
robot.send_action(action)
|
|
```
|
|
</hfoption>
|
|
</hfoptions>
|
|
|
|
The teleoperate command will automatically:
|
|
1. Identify any missing calibrations and initiate the calibration procedure.
|
|
2. Connect the robot and teleop device and start teleoperation.
|
|
|
|
## Cameras
|
|
|
|
To add cameras to your setup, follow this [Guide](./cameras#setup-cameras).
|
|
|
|
## Teleoperate with cameras
|
|
|
|
With `rerun`, you can teleoperate again while simultaneously visualizing the camera feeds and joint positions. In this example, we’re using the Koch arm.
|
|
|
|
<hfoptions id="teleoperate_koch_camera">
|
|
<hfoption id="Command">
|
|
```bash
|
|
python -m lerobot.teleoperate \
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
</hfoption>
|
|
<hfoption id="API example">
|
|
```python
|
|
from lerobot.common.cameras.opencv.configuration_opencv import OpenCVCameraConfig
|
|
from lerobot.common.teleoperators.koch_leader import KochLeaderConfig, KochLeader
|
|
from lerobot.common.robots.koch_follower import KochFollowerConfig, KochFollower
|
|
|
|
camera_config = {
|
|
"front": OpenCVCameraConfig(index_or_path=0, width=1920, height=1080, fps=30)
|
|
}
|
|
|
|
robot_config = KochFollowerConfig(
|
|
port="/dev/tty.usbmodem585A0076841",
|
|
id="my_red_robot_arm",
|
|
cameras=camera_config
|
|
)
|
|
|
|
teleop_config = KochLeaderConfig(
|
|
port="/dev/tty.usbmodem58760431551",
|
|
id="my_blue_leader_arm",
|
|
)
|
|
|
|
robot = KochFollower(robot_config)
|
|
teleop_device = KochLeader(teleop_config)
|
|
robot.connect()
|
|
teleop_device.connect()
|
|
|
|
while True:
|
|
observation = robot.get_observation()
|
|
action = teleop_device.get_action()
|
|
robot.send_action(action)
|
|
```
|
|
</hfoption>
|
|
</hfoptions>
|
|
|
|
## Record a dataset
|
|
|
|
Once you're familiar with teleoperation, you can record your first dataset.
|
|
|
|
We use the Hugging Face hub features for uploading your dataset. If you haven't previously used the Hub, make sure you can login via the cli using a write-access token, this token can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens).
|
|
|
|
Add your token to the CLI by running this command:
|
|
```bash
|
|
huggingface-cli login
|
|
```
|
|
|
|
Then store your Hugging Face repository name in a variable:
|
|
```bash
|
|
HF_USER=$(huggingface-cli whoami | head -n 1)
|
|
echo $HF_USER
|
|
```
|
|
|
|
Now you can record a dataset. To record 2 episodes and upload your dataset to the hub, execute this command tailored to the SO101.
|
|
```bash
|
|
python -m lerobot.record \
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
|
|
#### Dataset upload
|
|
Locally, your dataset is stored in this folder: `~/.cache/huggingface/lerobot/{repo-id}`. At the end of data recording, your dataset will be uploaded on your Hugging Face page (e.g. https://huggingface.co/datasets/cadene/so101_test) that you can obtain by running:
|
|
```bash
|
|
echo https://huggingface.co/datasets/${HF_USER}/so101_test
|
|
```
|
|
Your dataset will be automatically tagged with `LeRobot` for the community to find it easily, and you can also add custom tags (in this case `tutorial` for example).
|
|
|
|
You can look for other LeRobot datasets on the hub by searching for `LeRobot` [tags](https://huggingface.co/datasets?other=LeRobot).
|
|
|
|
#### Record function
|
|
|
|
The `record` function provides a suite of tools for capturing and managing data during robot operation:
|
|
|
|
##### 1. Data Storage
|
|
- Data is stored using the `LeRobotDataset` format and is stored on disk during recording.
|
|
- By default, the dataset is pushed to your Hugging Face page after recording.
|
|
- To disable uploading, use `
|
|
|
|
##### 2. Checkpointing and Resuming
|
|
- Checkpoints are automatically created during recording.
|
|
- If an issue occurs, you can resume by re-running the same command with `
|
|
- To start recording from scratch, **manually delete** the dataset directory.
|
|
|
|
##### 3. Recording Parameters
|
|
Set the flow of data recording using command-line arguments:
|
|
- `
|
|
Duration of each data recording episode (default: **60 seconds**).
|
|
- `
|
|
Duration for resetting the environment after each episode (default: **60 seconds**).
|
|
- `
|
|
Total number of episodes to record (default: **50**).
|
|
|
|
##### 4. Keyboard Controls During Recording
|
|
Control the data recording flow using keyboard shortcuts:
|
|
- Press **Right Arrow (`→`)**: Early stop the current episode or reset time and move to the next.
|
|
- Press **Left Arrow (`←`)**: Cancel the current episode and re-record it.
|
|
- Press **Escape (`ESC`)**: Immediately stop the session, encode videos, and upload the dataset.
|
|
|
|
#### Tips for gathering data
|
|
|
|
Once you're comfortable with data recording, you can create a larger dataset for training. A good starting task is grasping an object at different locations and placing it in a bin. We suggest recording at least 50 episodes, with 10 episodes per location. Keep the cameras fixed and maintain consistent grasping behavior throughout the recordings. Also make sure the object you are manipulating is visible on the camera's. A good rule of thumb is you should be able to do the task yourself by only looking at the camera images.
|
|
|
|
In the following sections, you’ll train your neural network. After achieving reliable grasping performance, you can start introducing more variations during data collection, such as additional grasp locations, different grasping techniques, and altering camera positions.
|
|
|
|
Avoid adding too much variation too quickly, as it may hinder your results.
|
|
|
|
If you want to dive deeper into this important topic, you can check out the [blog post](https://huggingface.co/blog/lerobot-datasets#what-makes-a-good-dataset) we wrote on what makes a good dataset.
|
|
|
|
|
|
#### Troubleshooting:
|
|
- On Linux, if the left and right arrow keys and escape key don't have any effect during data recording, make sure you've set the `$DISPLAY` environment variable. See [pynput limitations](https://pynput.readthedocs.io/en/latest/limitations.html#linux).
|
|
|
|
## Visualize a dataset
|
|
|
|
If you uploaded your dataset to the hub with `
|
|
```bash
|
|
echo ${HF_USER}/so101_test
|
|
```
|
|
|
|
## Replay an episode
|
|
|
|
A useful feature is the `replay` function, which allows you to replay any episode that you've recorded or episodes from any dataset out there. This function helps you test the repeatability of your robot's actions and assess transferability across robots of the same model.
|
|
|
|
You can replay the first episode on your robot with:
|
|
```bash
|
|
python -m lerobot.replay \
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
|
|
Your robot should replicate movements similar to those you recorded. For example, check out [this video](https://x.com/RemiCadene/status/1793654950905680090) where we use `replay` on a Aloha robot from [Trossen Robotics](https://www.trossenrobotics.com).
|
|
|
|
## 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
|
|
python lerobot/scripts/train.py \
|
|
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
|
|
Let's explain the command:
|
|
1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/so101_test`.
|
|
2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor states, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset.
|
|
4. We provided `policy.device=cuda` since we are training on a Nvidia GPU, but you could use `policy.device=mps` to train on Apple silicon.
|
|
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`.
|
|
|
|
Training should take several hours. You will find checkpoints in `outputs/train/act_so101_test/checkpoints`.
|
|
|
|
To resume training from a checkpoint, below is an example command to resume from `last` checkpoint of the `act_so101_test` policy:
|
|
```bash
|
|
python lerobot/scripts/train.py \
|
|
--config_path=outputs/train/act_so101_test/checkpoints/last/pretrained_model/train_config.json \
|
|
--resume=true
|
|
```
|
|
|
|
#### Train using Collab
|
|
If your local computer doesn't have a powerful GPU you could utilize Google Collab to train your model by following the [ACT training notebook](./notebooks#training-act).
|
|
|
|
#### Upload policy checkpoints
|
|
|
|
Once training is done, upload the latest checkpoint with:
|
|
```bash
|
|
huggingface-cli upload ${HF_USER}/act_so101_test \
|
|
outputs/train/act_so101_test/checkpoints/last/pretrained_model
|
|
```
|
|
|
|
You can also upload intermediate checkpoints with:
|
|
```bash
|
|
CKPT=010000
|
|
huggingface-cli upload ${HF_USER}/act_so101_test${CKPT} \
|
|
outputs/train/act_so101_test/checkpoints/${CKPT}/pretrained_model
|
|
```
|
|
|
|
## Evaluate your policy
|
|
|
|
You can use the `record` script from [`lerobot/record.py`](https://github.com/huggingface/lerobot/blob/main/lerobot/record.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes:
|
|
```bash
|
|
python -m lerobot.record \
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
```
|
|
|
|
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 `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_so101_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `${HF_USER}/act_so101_test`).
|
|
2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_so101_test`).
|
|
|