From 9bda2e746fb33bb05b1153d3e2387d3fae1278c7 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Sat, 25 Jan 2025 19:25:34 +0100 Subject: [PATCH 1/7] Fix examples --- examples/10_use_so100.md | 165 ++++++---- examples/11_use_moss.md | 155 ++++++--- examples/7_get_started_with_real_robot.md | 310 ++++++++---------- examples/8_use_stretch.md | 42 +-- examples/9_use_aloha.md | 110 ++++--- .../robot_devices/cameras/intelrealsense.py | 53 ++- .../common/robot_devices/cameras/opencv.py | 23 +- .../common/robot_devices/control_configs.py | 2 +- .../common/robot_devices/motors/dynamixel.py | 17 +- .../common/robot_devices/motors/feetech.py | 16 +- .../common/robot_devices/robots/configs.py | 2 +- .../robot_devices/robots/manipulator.py | 6 +- lerobot/scripts/control_robot.py | 23 +- 13 files changed, 480 insertions(+), 444 deletions(-) diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index 155bbe5198..151c3f2d35 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -16,9 +16,9 @@ On your computer: mkdir -p ~/miniconda3 # Linux: wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh -# Mac M-series: +# Mac M-series: # curl https://repo.anaconda.com/miniconda/Miniconda3-latest-MacOSX-arm64.sh -o ~/miniconda3/miniconda.sh -# Mac Intel: +# Mac Intel: # curl https://repo.anaconda.com/miniconda/Miniconda3-latest-MacOSX-x86_64.sh -o ~/miniconda3/miniconda.sh bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3 rm ~/miniconda3/miniconda.sh @@ -96,9 +96,53 @@ sudo chmod 666 /dev/ttyACM0 sudo chmod 666 /dev/ttyACM1 ``` -#### d. Update YAML file - -Now that you have the ports, modify the *port* sections in `so100.yaml` +#### d. Update config file + +IMPORTANTLY: Now that you have your ports, update the **port** default values of [`SO100RobotConfig`](../lerobot/common/robot_devices/robots/configs.py). You will find something like: +```python +@RobotConfig.register_subclass("so100") +@dataclass +class So100RobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem58760431091", <-- UPDATE HERE + 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: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", <-- UPDATE HERE + 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"], + }, + ), + } + ) +``` ### 2. Configure the motors @@ -155,9 +199,11 @@ You will need to move the follower arm to these positions sequentially: Make sure both arms are connected and 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_follower +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --robot.cameras='{}' \ + --control.type=calibrate \ + --control.arms='["main_follower"]' ``` #### b. Manual calibration of leader arm @@ -169,9 +215,11 @@ Follow step 6 of the [assembly video](https://youtu.be/FioA2oeFZ5I?t=724) which 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 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --robot.cameras='{}' \ + --control.type=calibrate \ + --control.arms='["main_leader"]' ``` ## F. Teleoperate @@ -179,18 +227,20 @@ python lerobot/scripts/control_robot.py calibrate \ **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 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --robot.cameras='{}' \ + --control.type=teleoperate \ + --control.display_cameras=false ``` #### a. 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 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --control.type=teleoperate ``` ## G. Record a dataset @@ -210,26 +260,27 @@ 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 \ - --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 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/so100_test \ + --control.tags='["so100","tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=2 \ + --control.push_to_hub=true ``` ## H. 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: +If you uploaded your dataset to the hub with `--control.push_to_hub=true`, 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: +If you didn't upload with `--control.push_to_hub=false`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ --repo-id ${HF_USER}/so100_test @@ -239,11 +290,12 @@ python lerobot/scripts/visualize_dataset_html.py \ Now try to replay the first episode on your robot: ```bash -python lerobot/scripts/control_robot.py replay \ - --robot-path lerobot/configs/robot/so100.yaml \ - --fps 30 \ - --repo-id ${HF_USER}/so100_test \ - --episode 0 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --control.type=replay \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/so100_test \ + --control.episode=0 ``` ## J. Train a policy @@ -251,20 +303,18 @@ python lerobot/scripts/control_robot.py replay \ 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 \ - 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 + --dataset.repo_id=${HF_USER}/so100_test \ + --policy.type=act \ + --output_dir=outputs/train/act_so100_test \ + --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. +1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/so100_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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. +4. We provided `device=cuda` since we are training on a Nvidia GPU, but you could use `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_so100_test/checkpoints`. @@ -273,21 +323,22 @@ Training should take several hours. You will find checkpoints in `outputs/train/ 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 \ - --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 +python lerobot/scripts/control_robot.py \ + --robot.type=so100 \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/eval_act_so100_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=10 \ + --control.policy.path=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`). +1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_so100_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_so100_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_so100_test`). ## L. More Information diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index 55d6fcaf94..c8261b930d 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -83,6 +83,54 @@ sudo chmod 666 /dev/ttyACM0 sudo chmod 666 /dev/ttyACM1 ``` +#### Update config file + +IMPORTANTLY: Now that you have your ports, update the **port** default values of [`MossRobotConfig`](../lerobot/common/robot_devices/robots/configs.py). You will find something like: +```python +@RobotConfig.register_subclass("moss") +@dataclass +class MossRobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem58760431091", <-- UPDATE HERE + 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: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", <-- UPDATE HERE + 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"], + }, + ), + } + ) +``` + **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 @@ -134,9 +182,11 @@ You will need to move the follower arm to these positions sequentially: Make sure both arms are connected and 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_follower +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --robot.cameras='{}' \ + --control.type=calibrate \ + --control.arms='["main_follower"]' ``` **Manual calibration of leader arm** @@ -148,9 +198,11 @@ Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMi 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 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --robot.cameras='{}' \ + --control.type=calibrate \ + --control.arms='["main_leader"]' ``` ## Teleoperate @@ -158,18 +210,20 @@ python lerobot/scripts/control_robot.py calibrate \ **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 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --robot.cameras='{}' \ + --control.type=teleoperate \ + --control.display_cameras=false ``` **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 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --control.type=teleoperate ``` ## Record a dataset @@ -189,16 +243,17 @@ 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 \ - --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 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/moss_test \ + --control.tags='["moss","tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=2 \ + --control.push_to_hub=true ``` ## Visualize a dataset @@ -218,11 +273,12 @@ python lerobot/scripts/visualize_dataset_html.py \ Now try to replay the first episode on your robot: ```bash -python lerobot/scripts/control_robot.py replay \ - --robot-path lerobot/configs/robot/moss.yaml \ - --fps 30 \ - --repo-id ${HF_USER}/moss_test \ - --episode 0 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --control.type=replay \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/moss_test \ + --control.episode=0 ``` ## Train a policy @@ -230,20 +286,18 @@ python lerobot/scripts/control_robot.py replay \ 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 \ - 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 + --dataset.repo_id=${HF_USER}/moss_test \ + --policy.type=act \ + --output_dir=outputs/train/act_moss_test \ + --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. +1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/moss_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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. +4. We provided `device=cuda` since we are training on a Nvidia GPU, but you could use `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_moss_test/checkpoints`. @@ -252,21 +306,22 @@ Training should take several hours. You will find checkpoints in `outputs/train/ 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 \ - --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 +python lerobot/scripts/control_robot.py \ + --robot.type=moss \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/eval_act_moss_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=10 \ + --control.policy.path=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`). +1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_moss_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_moss_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_moss_test`). ## More diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index c86508e7c7..9f0c1fcbf1 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -58,9 +58,9 @@ Finally, connect both arms to your computer via USB. Note that the USB doesn't p In the upcoming sections, you'll learn about our classes and functions by running some python code, in an interactive session, or by copy-pasting it in a python file. If this is your first time using the tutorial., we highly recommend going through these steps to get deeper intuition about how things work. Once you're more familiar, you can streamline the process by directly running the teleoperate script (which is detailed further in the tutorial): ```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/koch.yaml \ - --robot-overrides '~cameras' # do not instantiate the cameras +python lerobot/scripts/control_robot.py \ + --robot.type=koch \ + --robot.cameras='{}' # do not instantiate the cameras ``` It will automatically: @@ -117,13 +117,11 @@ Next, you'll need to list the motors for each arm, including their name, index, To assign indices to the motors, run this code in an interactive Python session. Replace the `port` values with the ones you identified earlier: ```python +from lerobot.common.robot_devices.motors.configs import DynamixelMotorsBusConfig from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus -leader_port = "/dev/tty.usbmodem575E0031751" -follower_port = "/dev/tty.usbmodem575E0032081" - -leader_arm = DynamixelMotorsBus( - port=leader_port, +leader_config = DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem575E0031751", motors={ # name: (index, model) "shoulder_pan": (1, "xl330-m077"), @@ -135,8 +133,8 @@ leader_arm = DynamixelMotorsBus( }, ) -follower_arm = DynamixelMotorsBus( - port=follower_port, +follower_config = DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem575E0032081", motors={ # name: (index, model) "shoulder_pan": (1, "xl430-w250"), @@ -147,44 +145,56 @@ follower_arm = DynamixelMotorsBus( "gripper": (6, "xl330-m288"), }, ) -``` -*Updating the YAML Configuration File* - -Next, update the port values in the YAML configuration file for the Koch robot at [`lerobot/configs/robot/koch.yaml`](../lerobot/configs/robot/koch.yaml) with the ports you've identified: -```yaml -[...] -robot_type: koch -leader_arms: - main: - _target_: lerobot.common.robot_devices.motors.dynamixel.DynamixelMotorsBus - port: /dev/tty.usbmodem575E0031751 # <- Update - motors: - # name: (index, model) - shoulder_pan: [1, "xl330-m077"] - shoulder_lift: [2, "xl330-m077"] - elbow_flex: [3, "xl330-m077"] - wrist_flex: [4, "xl330-m077"] - wrist_roll: [5, "xl330-m077"] - gripper: [6, "xl330-m077"] -follower_arms: - main: - _target_: lerobot.common.robot_devices.motors.dynamixel.DynamixelMotorsBus - port: /dev/tty.usbmodem575E0032081 # <- Update - motors: - # name: (index, model) - shoulder_pan: [1, "xl430-w250"] - shoulder_lift: [2, "xl430-w250"] - elbow_flex: [3, "xl330-m288"] - wrist_flex: [4, "xl330-m288"] - wrist_roll: [5, "xl330-m288"] - gripper: [6, "xl330-m288"] -[...] +leader_arm = DynamixelMotorsBus(leader_config) +follower_arm = DynamixelMotorsBus(follower_config) ``` -Don't forget to set `robot_type: aloha` if you follow this tutorial with [Aloha bimanual robot](aloha-2.github.io) instead of Koch v1.1 - -This configuration file is used to instantiate your robot across all scripts. We'll cover how this works later on. +IMPORTANTLY: Now that you have your ports, update [`KochRobotConfig`](../lerobot/common/robot_devices/robots/configs.py). You will find something like: +```python +@RobotConfig.register_subclass("koch") +@dataclass +class KochRobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".cache/calibration/koch" + # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes. + # Set this to a positive scalar to have the same value for all motors, or a list that is the same length as + # the number of motors in your follower arms. + max_relative_target: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0085511", <-- UPDATE HERE + motors={ + # name: (index, model) + "shoulder_pan": [1, "xl330-m077"], + "shoulder_lift": [2, "xl330-m077"], + "elbow_flex": [3, "xl330-m077"], + "wrist_flex": [4, "xl330-m077"], + "wrist_roll": [5, "xl330-m077"], + "gripper": [6, "xl330-m077"], + }, + ), + } + ) + + follower_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", <-- UPDATE HERE + motors={ + # name: (index, model) + "shoulder_pan": [1, "xl430-w250"], + "shoulder_lift": [2, "xl430-w250"], + "elbow_flex": [3, "xl330-m288"], + "wrist_flex": [4, "xl330-m288"], + "wrist_roll": [5, "xl330-m288"], + "gripper": [6, "xl330-m288"], + }, + ), + } + ) +``` **Connect and Configure your Motors** @@ -312,27 +322,27 @@ Alternatively, you can unplug the power cord, which will automatically disable t **Instantiate the ManipulatorRobot** -Before you can teleoperate your robot, you need to instantiate the [`ManipulatorRobot`](../lerobot/common/robot_devices/robots/manipulator.py) using the previously defined `leader_arm` and `follower_arm`. +Before you can teleoperate your robot, you need to instantiate the [`ManipulatorRobot`](../lerobot/common/robot_devices/robots/manipulator.py) using the previously defined `leader_config` and `follower_config`. -For the Koch v1.1 robot, we only have one leader, so we refer to it as `"main"` and define it as `leader_arms={"main": leader_arm}`. We do the same for the follower arm. For other robots (like the Aloha), which may have two pairs of leader and follower arms, you would define them like this: `leader_arms={"left": left_leader_arm, "right": right_leader_arm},`. Same thing for the follower arms. +For the Koch v1.1 robot, we only have one leader, so we refer to it as `"main"` and define it as `leader_arms={"main": leader_config}`. We do the same for the follower arm. For other robots (like the Aloha), which may have two pairs of leader and follower arms, you would define them like this: `leader_arms={"left": left_leader_config, "right": right_leader_config},`. Same thing for the follower arms. -You also need to provide a path to a calibration directory, such as `calibration_dir=".cache/calibration/koch"`. More on this in the next section. Run the following code to instantiate your manipulator robot: ```python +from lerobot.common.robot_devices.robots.configs import KochRobotConfig from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot -robot = ManipulatorRobot( - robot_type="koch", - leader_arms={"main": leader_arm}, - follower_arms={"main": follower_arm}, - calibration_dir=".cache/calibration/koch", +robot_config = KochRobotConfig( + leader_arms={"main": leader_config}, + follower_arms={"main": follower_config}, + cameras={}, # We don't use any camera for now ) +robot = ManipulatorRobot(robot_config) ``` -The `robot_type="koch"` is used to set the associated settings and calibration process. For instance, we activate the torque of the gripper of the leader Koch v1.1 arm and position it at a 40 degree angle to use it as a trigger. +The `KochRobotConfig` is used to set the associated settings and calibration process. For instance, we activate the torque of the gripper of the leader Koch v1.1 arm and position it at a 40 degree angle to use it as a trigger. -For the [Aloha bimanual robot](https://aloha-2.github.io), we would use `robot_type="aloha"` to set different settings such as a secondary ID for shadow joints (shoulder, elbow). Specific to Aloha, LeRobot comes with default calibration files stored in in `.cache/calibration/aloha_default`. Assuming the motors have been properly assembled, no manual calibration step is expected. If you need to run manual calibration, simply update `calibration_dir` to `.cache/calibration/aloha`. +For the [Aloha bimanual robot](https://aloha-2.github.io), we would use `AlohaRobotConfig` to set different settings such as a secondary ID for shadow joints (shoulder, elbow). Specific to Aloha, LeRobot comes with default calibration files stored in in `.cache/calibration/aloha_default`. Assuming the motors have been properly assembled, no manual calibration step is expected for Aloha. **Calibrate and Connect the ManipulatorRobot** @@ -579,9 +589,11 @@ Note: Some cameras may take a few seconds to warm up, and the first frame might Finally, run this code to instantiate and connectyour camera: ```python +from lerobot.common.robot_devices.cameras.configs import OpenCVCameraConfig from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera -camera = OpenCVCamera(camera_index=0) +camera_config = OpenCVCameraConfig(camera_index=0) +camera = OpenCVCamera(config) camera.connect() color_image = camera.read() @@ -603,7 +615,7 @@ uint8 With certain camera, you can also specify additional parameters like frame rate, resolution, and color mode during instantiation. For instance: ```python -camera = OpenCVCamera(camera_index=0, fps=30, width=640, height=480) +config = OpenCVCameraConfig(camera_index=0, fps=30, width=640, height=480) ``` If the provided arguments are not compatible with the camera, an exception will be raised. @@ -626,8 +638,8 @@ robot = ManipulatorRobot( follower_arms={"main": follower_arm}, calibration_dir=".cache/calibration/koch", cameras={ - "laptop": OpenCVCamera(0, fps=30, width=640, height=480), - "phone": OpenCVCamera(1, fps=30, width=640, height=480), + "laptop": OpenCVCameraConfig(0, fps=30, width=640, height=480), + "phone": OpenCVCameraConfig(1, fps=30, width=640, height=480), }, ) robot.connect() @@ -652,34 +664,15 @@ torch.Size([3, 480, 640]) 255 ``` -Also, update the following lines of the yaml file for Koch robot [`lerobot/configs/robot/koch.yaml`](../lerobot/configs/robot/koch.yaml) with the names and configurations of your cameras: -```yaml -[...] -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 -``` - -This file is used to instantiate your robot in all our scripts. We will explain how this works in the next section. - -### d. Use `koch.yaml` and our `teleoperate` function +### d. Use `control_robot.py` and our `teleoperate` function -Instead of manually running the python code in a terminal window, you can use [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) to instantiate your robot by providing the path to the robot yaml file (e.g. [`lerobot/configs/robot/koch.yaml`](../lerobot/configs/robot/koch.yaml)) and control your robot with various modes as explained next. +Instead of manually running the python code in a terminal window, you can use [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) to instantiate your robot by providing the robot configurations via command line and control your robot with various modes as explained next. Try running this code to teleoperate your robot (if you dont have a camera, keep reading): ```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/koch.yaml +python lerobot/scripts/control_robot.py \ + --robot.type=koch \ + --control.type=teleoperate ``` You will see a lot of lines appearing like this one: @@ -694,21 +687,12 @@ It contains - `dtRlead: 4.93 (203.0hz)` which is the number of milliseconds it took to read the position of the leader arm using `leader_arm.read("Present_Position")`. - `dtWfoll: 0.22 (4446.9hz)` which is the number of milliseconds it took to set a new goal position for the follower arm using `follower_arm.write("Goal_position", leader_pos)` ; note that writing is done asynchronously so it takes less time than reading. -Note: you can override any entry in the yaml file using `--robot-overrides` and the [hydra.cc](https://hydra.cc/docs/advanced/override_grammar/basic) syntax. If needed, you can override the ports like this: +Importantly: If you don't have any camera, you can remove them dynamically with this [draccus](https://github.com/dlwh/draccus) syntax `--robot.cameras='{}'`: ```bash python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/koch.yaml \ - --robot-overrides \ - leader_arms.main.port=/dev/tty.usbmodem575E0031751 \ - follower_arms.main.port=/dev/tty.usbmodem575E0032081 -``` - -Importantly: If you don't have any camera, you can remove them dynamically with this [hydra.cc](https://hydra.cc/docs/advanced/override_grammar/basic) syntax `'~cameras'`: -```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/koch.yaml \ - --robot-overrides \ - '~cameras' + --robot.type=koch \ + --robot.cameras='{}' \ + --control.type=teleoperate ``` We advise to create a new yaml file when the command becomes too long. @@ -744,23 +728,23 @@ for _ in range(record_time_s * fps): Importantly, many utilities are still missing. For instance, if you have cameras, you will need to save the images on disk to not go out of RAM, and to do so in threads to not slow down communication with your robot. Also, you will need to store your data in a format optimized for training and web sharing like [`LeRobotDataset`](../lerobot/common/datasets/lerobot_dataset.py). More on this in the next section. -### a. Use `koch.yaml` and the `record` function +### a. Use the `record` function You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) to achieve efficient data recording. It encompasses many recording utilities: -1. Frames from cameras are saved on disk in threads, and encoded into videos at the end of recording. +1. Frames from cameras are saved on disk in threads, and encoded into videos at the end of each episode recording. 2. Video streams from cameras are displayed in window so that you can verify them. -3. Data is stored with [`LeRobotDataset`](../lerobot/common/datasets/lerobot_dataset.py) format which is pushed to your Hugging Face page (unless `--push-to-hub 0` is provided). -4. Checkpoints are done during recording, so if any issue occurs, you can resume recording by re-running the same command again. You can also use `--force-override 1` to start recording from scratch. +3. Data is stored with [`LeRobotDataset`](../lerobot/common/datasets/lerobot_dataset.py) format which is pushed to your Hugging Face page (unless `--control.push_to_hub=false` is provided). +4. Checkpoints are done during recording, so if any issue occurs, you can resume recording by re-running the same command again with `--control.resume=true`. You might need to add `--control.local_files_only=true` if your dataset was not uploaded to hugging face hub. Also you will need to manually delete the dataset directory to start recording from scratch. 5. Set the flow of data recording using command line arguments: - - `--warmup-time-s` defines the number of seconds before starting data collection. It allows the robot devices to warmup and synchronize (10 seconds by default). - - `--episode-time-s` defines the number of seconds for data recording for each episode (60 seconds by default). - - `--reset-time-s` defines the number of seconds for resetting the environment after each episode (60 seconds by default). - - `--num-episodes` defines the number of episodes to record (50 by default). + - `--control.warmup_time_s=10` defines the number of seconds before starting data collection. It allows the robot devices to warmup and synchronize (10 seconds by default). + - `--control.episode_time_s=60` defines the number of seconds for data recording for each episode (60 seconds by default). + - `--control.reset_time_s=60` defines the number of seconds for resetting the environment after each episode (60 seconds by default). + - `--control.num_episodes=50` defines the number of episodes to record (50 by default). 6. Control the flow during data recording using keyboard keys: - Press right arrow `->` at any time during episode recording to early stop and go to resetting. Same during resetting, to early stop and to go to the next episode recording. - Press left arrow `<-` at any time during episode recording or resetting to early stop, cancel the current episode, and re-record it. - Press escape `ESC` at any time during episode recording to end the session early and go straight to video encoding and dataset uploading. -7. Similarly to `teleoperate`, you can also use `--robot-path` and `--robot-overrides` to specify your robots. +7. Similarly to `teleoperate`, you can also use the command line to override anything. Before trying `record`, if you want to push your dataset to the hub, 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 @@ -771,27 +755,27 @@ Also, store your Hugging Face repository name in a variable (e.g. `cadene` or `l HF_USER=$(huggingface-cli whoami | head -n 1) echo $HF_USER ``` -If you don't want to push to hub, use `--push-to-hub 0`. +If you don't want to push to hub, use `--control.push_to_hub=false`. Now run this to record 2 episodes: ```bash -python lerobot/scripts/control_robot.py record \ - --robot-path lerobot/configs/robot/koch.yaml \ - --fps 30 \ - --repo-id ${HF_USER}/koch_test \ - --tags tutorial \ - --warmup-time-s 5 \ - --episode-time-s 30 \ - --reset-time-s 30 \ - --num-episodes 2 +python lerobot/scripts/control_robot.py \ + --robot.type=koch \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/koch_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=2 \ + --control.push_to_hub=true ``` This will write your dataset locally to `~/.cache/huggingface/lerobot/{repo-id}` (e.g. `data/cadene/koch_test`) and push it on the hub at `https://huggingface.co/datasets/{HF_USER}/{repo-id}`. 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 -Remember to add `--robot-overrides '~cameras'` if you don't have any cameras and you still use the default `koch.yaml` configuration. - You will see a lot of lines appearing like this one: ``` INFO 2024-08-10 15:02:58 ol_robot.py:219 dt:33.34 (30.0hz) dtRlead: 5.06 (197.5hz) dtWfoll: 0.25 (3963.7hz) dtRfoll: 6.22 (160.7hz) dtRlaptop: 32.57 (30.7hz) dtRphone: 33.84 (29.5hz) @@ -853,13 +837,16 @@ A useful feature of [`lerobot/scripts/control_robot.py`](../lerobot/scripts/cont To replay the first episode of the dataset you just recorded, run the following command: ```bash -python lerobot/scripts/control_robot.py replay \ - --robot-path lerobot/configs/robot/koch.yaml \ - --fps 30 \ - --repo-id ${HF_USER}/koch_test \ - --episode 0 +python lerobot/scripts/control_robot.py \ + --robot.type=koch \ + --control.type=replay \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/koch_test \ + --control.episode=0 ``` +Note: You might need to add `--control.local_files_only=true` if your dataset was not uploaded to hugging face hub. + 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). ## 4. Train a policy on your data @@ -869,50 +856,17 @@ Your robot should replicate movements similar to those you recorded. For example 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 \ - dataset_repo_id=${HF_USER}/koch_test \ - policy=act_koch_real \ - env=koch_real \ - hydra.run.dir=outputs/train/act_koch_test \ - hydra.job.name=act_koch_test \ - device=cuda \ - wandb.enable=true + --dataset.repo_id=${HF_USER}/koch_test \ + --policy.type=act \ + --output_dir=outputs/train/act_koch_test \ + --job_name=act_koch_test \ + --device=cuda \ + --wandb.enable=true ``` Let's explain it: -1. We provided the dataset as argument with `dataset_repo_id=${HF_USER}/koch_test`. -2. We provided the policy with `policy=act_koch_real`. This loads configurations from [`lerobot/configs/policy/act_koch_real.yaml`](../lerobot/configs/policy/act_koch_real.yaml). Importantly, this policy uses 2 cameras as input `laptop` and `phone`. If your dataset has different cameras, update the yaml file to account for it in the following parts: -```yaml -... -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) -... - input_shapes: - observation.images.laptop: [3, 480, 640] - observation.images.phone: [3, 480, 640] -... - input_normalization_modes: - observation.images.laptop: mean_std - observation.images.phone: mean_std -... -``` -3. We provided an environment as argument with `env=koch_real`. This loads configurations from [`lerobot/configs/env/koch_real.yaml`](../lerobot/configs/env/koch_real.yaml). It looks like -```yaml -fps: 30 -env: - name: real_world - task: null - state_dim: 6 - action_dim: 6 - fps: ${fps} -``` -It should match your dataset (e.g. `fps: 30`) and your robot (e.g. `state_dim: 6` and `action_dim: 6`). We are still working on simplifying this in future versions of `lerobot`. +1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/koch_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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. 4. We provided `device=cuda` since we are training on a Nvidia GPU, but you could use `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`. @@ -946,7 +900,6 @@ fps = 30 device = "cuda" # TODO: On Mac, use "mps" or "cpu" ckpt_path = "outputs/train/act_koch_test/checkpoints/last/pretrained_model" -# TODO(alibert, rcadene): fix this file policy = ACTPolicy.from_pretrained(ckpt_path) policy.to(device) @@ -979,34 +932,35 @@ for _ in range(inference_time_s * fps): busy_wait(1 / fps - dt_s) ``` -### a. Use `koch.yaml` and our `record` function +### a. Use our `record` function Ideally, when controlling your robot with your neural network, you would want to record evaluation episodes and to be able to visualize them later on, or even train on them like in Reinforcement Learning. This pretty much corresponds to recording a new dataset but with a neural network providing the actions instead of teleoperation. To this end, 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/koch.yaml \ - --fps 30 \ - --repo-id ${HF_USER}/eval_koch_test \ - --tags tutorial eval \ - --warmup-time-s 5 \ - --episode-time-s 30 \ - --reset-time-s 30 \ - --num-episodes 10 \ - -p outputs/train/act_koch_test/checkpoints/last/pretrained_model +python lerobot/scripts/control_robot.py \ + --robot.type=koch \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/eval_act_koch_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=10 \ + --control.policy.path=outputs/train/act_koch_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_koch_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_koch_test`). -2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_koch_test`). +1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_koch_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_koch_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_koch_test`). ### b. Visualize evaluation afterwards You can then visualize your evaluation dataset by running the same command as before but with the new inference dataset as argument: ```bash python lerobot/scripts/visualize_dataset.py \ - --repo-id ${HF_USER}/eval_koch_test + --repo-id ${HF_USER}/eval_act_koch_test ``` ## 6. Next step diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md index c2c306f071..29dc0a1674 100644 --- a/examples/8_use_stretch.md +++ b/examples/8_use_stretch.md @@ -92,8 +92,9 @@ Serial Number = stretch-se3-3054 **Calibrate (Optional)** Before operating Stretch, you need to [home](https://docs.hello-robot.com/0.3/getting_started/stretch_hardware_overview/#homing) it first. Be mindful about giving Stretch some space as this procedure will move the robot's arm and gripper. Now run this command: ```bash -python lerobot/scripts/control_robot.py calibrate \ - --robot-path lerobot/configs/robot/stretch.yaml +python lerobot/scripts/control_robot.py \ + --robot.type=stretch \ + --control.type=calibrate ``` This is equivalent to running `stretch_robot_home.py` @@ -104,8 +105,9 @@ Before trying teleoperation, you need activate the gamepad controller by pressin Now try out teleoperation (see above documentation to learn about the gamepad controls): ```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/stretch.yaml +python lerobot/scripts/control_robot.py \ + --robot.type=stretch \ + --control.type=teleoperate ``` This is essentially the same as running `stretch_gamepad_teleop.py` @@ -125,16 +127,17 @@ echo $HF_USER Record one episode: ```bash -python lerobot/scripts/control_robot.py record \ - --robot-path lerobot/configs/robot/stretch.yaml \ - --fps 20 \ - --repo-id ${HF_USER}/stretch_test \ - --tags stretch tutorial \ - --warmup-time-s 3 \ - --episode-time-s 40 \ - --reset-time-s 10 \ - --num-episodes 1 \ - --push-to-hub 0 +python lerobot/scripts/control_robot.py \ + --robot.type=stretch \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/stretch_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=2 \ + --control.push_to_hub=true ``` > **Note:** If you're using ssh to connect to Stretch and run this script, you won't be able to visualize its cameras feed (though they will still be recording). To see the cameras stream, use [tethered](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#tethered-setup) or [untethered setup](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#untethered-setup). @@ -142,11 +145,12 @@ python lerobot/scripts/control_robot.py record \ **Replay an episode** Now try to replay this episode (make sure the robot's initial position is the same): ```bash -python lerobot/scripts/control_robot.py replay \ - --robot-path lerobot/configs/robot/stretch.yaml \ - --fps 20 \ - --repo-id ${HF_USER}/stretch_test \ - --episode 0 +python lerobot/scripts/control_robot.py \ + --robot.type=stretch \ + --control.type=replay \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/stretch_test \ + --control.episode=0 ``` Follow [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) to train a policy on your data and run inference on your robot. You will need to adapt the code for Stretch. diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index f531a2c1d5..e073b70592 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -51,16 +51,18 @@ Teleoperation consists in manually operating the leader arms to move the followe By running the following code, you can start your first **SAFE** teleoperation: ```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/aloha.yaml \ - --robot-overrides max_relative_target=5 +python lerobot/scripts/control_robot.py \ + --robot.type=aloha \ + --robot.max_relative_target=5 \ + --control.type=teleoperate ``` -By adding `--robot-overrides max_relative_target=5`, we override the default value for `max_relative_target` defined in `lerobot/configs/robot/aloha.yaml`. It is expected to be `5` to limit the magnitude of the movement for more safety, but the teleoperation won't be smooth. When you feel confident, you can disable this limit by adding `--robot-overrides max_relative_target=null` to the command line: +By adding `--robot.max_relative_target=5`, we override the default value for `max_relative_target` defined in [`AlohaRobotConfig`](lerobot/common/robot_devices/robots/configs.py). It is expected to be `5` to limit the magnitude of the movement for more safety, but the teleoperation won't be smooth. When you feel confident, you can disable this limit by adding `--robot.max_relative_target=null` to the command line: ```bash -python lerobot/scripts/control_robot.py teleoperate \ - --robot-path lerobot/configs/robot/aloha.yaml \ - --robot-overrides max_relative_target=null +python lerobot/scripts/control_robot.py \ + --robot.type=aloha \ + --robot.max_relative_target=null \ + --control.type=teleoperate ``` ## Record a dataset @@ -80,27 +82,28 @@ 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/aloha.yaml \ - --robot-overrides max_relative_target=null \ - --fps 30 \ - --repo-id ${HF_USER}/aloha_test \ - --tags aloha tutorial \ - --warmup-time-s 5 \ - --episode-time-s 40 \ - --reset-time-s 10 \ - --num-episodes 2 \ - --push-to-hub 1 +python lerobot/scripts/control_robot.py \ + --robot.type=aloha \ + --robot.max_relative_target=null \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/aloha_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=2 \ + --control.push_to_hub=true ``` ## 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: +If you uploaded your dataset to the hub with `--control.push_to_hub=true`, 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}/aloha_test ``` -If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: +If you didn't upload with `--control.push_to_hub=false`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ --repo-id ${HF_USER}/aloha_test @@ -109,16 +112,17 @@ python lerobot/scripts/visualize_dataset_html.py \ ## Replay an episode **/!\ FOR SAFETY, READ THIS /!\** -Replay consists in automatically replaying the sequence of actions (i.e. goal positions for your motors) recorded in a given dataset episode. Make sure the current initial position of your robot is similar to the one in your episode, so that your follower arms don't move too fast to go to the first goal positions. For safety, you might want to add `--robot-overrides max_relative_target=5` to your command line as explained above. +Replay consists in automatically replaying the sequence of actions (i.e. goal positions for your motors) recorded in a given dataset episode. Make sure the current initial position of your robot is similar to the one in your episode, so that your follower arms don't move too fast to go to the first goal positions. For safety, you might want to add `--robot.max_relative_target=5` to your command line as explained above. Now try to replay the first episode on your robot: ```bash -python lerobot/scripts/control_robot.py replay \ - --robot-path lerobot/configs/robot/aloha.yaml \ - --robot-overrides max_relative_target=null \ - --fps 30 \ - --repo-id ${HF_USER}/aloha_test \ - --episode 0 +python lerobot/scripts/control_robot.py \ + --robot.type=aloha \ + --robot.max_relative_target=null \ + --control.type=replay \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/aloha_test \ + --control.episode=0 ``` ## Train a policy @@ -126,46 +130,46 @@ python lerobot/scripts/control_robot.py replay \ 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 \ - dataset_repo_id=${HF_USER}/aloha_test \ - policy=act_aloha_real \ - env=aloha_real \ - hydra.run.dir=outputs/train/act_aloha_test \ - hydra.job.name=act_aloha_test \ - device=cuda \ - wandb.enable=true + --dataset.repo_id=${HF_USER}/aloha_test \ + --policy.type=act \ + --output_dir=outputs/train/act_aloha_test \ + --job_name=act_aloha_test \ + --device=cuda \ + --wandb.enable=true ``` Let's explain it: -1. We provided the dataset as argument with `dataset_repo_id=${HF_USER}/aloha_test`. -2. We provided the policy with `policy=act_aloha_real`. This loads configurations from [`lerobot/configs/policy/act_aloha_real.yaml`](../lerobot/configs/policy/act_aloha_real.yaml). Importantly, this policy uses 4 cameras as input `cam_right_wrist`, `cam_left_wrist`, `cam_high`, and `cam_low`. -3. We provided an environment as argument with `env=aloha_real`. This loads configurations from [`lerobot/configs/env/aloha_real.yaml`](../lerobot/configs/env/aloha_real.yaml). Note: this yaml defines 18 dimensions for the `state_dim` and `action_dim`, corresponding to 18 motors, not 14 motors as used in previous Aloha work. This is because, we include the `shoulder_shadow` and `elbow_shadow` motors for simplicity. -4. We provided `device=cuda` since we are training on a Nvidia GPU. +1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/aloha_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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. +4. We provided `device=cuda` since we are training on a Nvidia GPU, but you could use `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`. +For more information on the `train` script see the previous tutorial: [`examples/4_train_policy_with_script.md`](../examples/4_train_policy_with_script.md) + Training should take several hours. You will find checkpoints in `outputs/train/act_aloha_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/aloha.yaml \ - --robot-overrides max_relative_target=null \ - --fps 30 \ - --repo-id ${HF_USER}/eval_act_aloha_test \ - --tags aloha tutorial eval \ - --warmup-time-s 5 \ - --episode-time-s 40 \ - --reset-time-s 10 \ - --num-episodes 10 \ - --num-image-writer-processes 1 \ - -p outputs/train/act_aloha_test/checkpoints/last/pretrained_model +python lerobot/scripts/control_robot.py \ + --robot.type=aloha \ + --control.type=record \ + --control.fps=30 \ + --control.repo_id=${HF_USER}/eval_act_aloha_test \ + --control.tags='["tutorial"]' \ + --control.warmup_time_s=5 \ + --control.episode_time_s=30 \ + --control.reset_time_s=30 \ + --control.num_episodes=10 \ + --control.policy.path=outputs/train/act_aloha_test/checkpoints/last/pretrained_model \ + --control.num_image_writer_processes=1 ``` 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_aloha_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_aloha_test`). -2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_aloha_test`). -3. We use `--num-image-writer-processes 1` instead of the default value (`0`). On our computer, using a dedicated process to write images from the 4 cameras on disk allows to reach constent 30 fps during inference. Feel free to explore different values for `--num-image-writer-processes`. +1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_aloha_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_aloha_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_aloha_test`). +3. We use `--control.num_image_writer_processes=1` instead of the default value (`0`). On our computer, using a dedicated process to write images from the 4 cameras on disk allows to reach constent 30 fps during inference. Feel free to explore different values for `--control.num_image_writer_processes`. ## More diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index affb5e6249..dff2e9d907 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -11,7 +11,6 @@ import time import traceback from collections import Counter -from dataclasses import replace from pathlib import Path from threading import Thread @@ -165,33 +164,35 @@ class IntelRealSenseCamera: When an IntelRealSenseCamera is instantiated, if no specific config is provided, the default fps, width, height and color_mode of the given camera will be used. - Example of usage: + Example of instantiating with a serial number: ```python - # Instantiate with its serial number - camera = IntelRealSenseCamera(serial_number=128422271347) - # Or by its name if it's unique - camera = IntelRealSenseCamera.init_from_name("Intel RealSense D405") + from lerobot.common.robot_devices.cameras.configs import IntelRealSenseCameraConfig + + config = IntelRealSenseCameraConfig(serial_number=128422271347) + camera = IntelRealSenseCamera(config) camera.connect() color_image = camera.read() # when done using the camera, consider disconnecting camera.disconnect() ``` + Example of instantiating with a name if it's unique: + ``` + config = IntelRealSenseCameraConfig(name="Intel RealSense D405") + ``` + Example of changing default fps, width, height and color_mode: ```python - camera = IntelRealSenseCamera(serial_number=128422271347, fps=30, width=1280, height=720) - camera = connect() # applies the settings, might error out if these settings are not compatible with the camera - - camera = IntelRealSenseCamera(serial_number=128422271347, fps=90, width=640, height=480) - camera = connect() - - camera = IntelRealSenseCamera(serial_number=128422271347, fps=90, width=640, height=480, color_mode="bgr") - camera = connect() + config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=30, width=1280, height=720) + config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480) + config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480, color_mode="bgr") + # Note: might error out upon `camera.connect()` if these settings are not compatible with the camera ``` Example of returning depth: ```python - camera = IntelRealSenseCamera(serial_number=128422271347, use_depth=True) + config = IntelRealSenseCameraConfig(serial_number=128422271347, use_depth=True) + camera = IntelRealSenseCamera(config) camera.connect() color_image, depth_map = camera.read() ``` @@ -199,12 +200,13 @@ class IntelRealSenseCamera: def __init__( self, - config: IntelRealSenseCameraConfig | None = None, - **kwargs, + config: IntelRealSenseCameraConfig, ): - config = IntelRealSenseCameraConfig(**kwargs) if config is None else replace(config, **kwargs) - - self.serial_number = config.serial_number + self.config = config + if config.name is not None: + self.serial_number = self.find_serial_number_from_name(config.name) + else: + self.serial_number = config.serial_number self.fps = config.fps self.width = config.width self.height = config.height @@ -236,8 +238,7 @@ def __init__( elif config.rotation == 180: self.rotation = cv2.ROTATE_180 - @classmethod - def init_from_name(cls, name: str, config: IntelRealSenseCameraConfig | None = None, **kwargs): + def find_serial_number_from_name(self, name): camera_infos = find_cameras() camera_names = [cam["name"] for cam in camera_infos] this_name_count = Counter(camera_names)[name] @@ -250,13 +251,7 @@ def init_from_name(cls, name: str, config: IntelRealSenseCameraConfig | None = N name_to_serial_dict = {cam["name"]: cam["serial_number"] for cam in camera_infos} cam_sn = name_to_serial_dict[name] - if config is None: - config = IntelRealSenseCameraConfig() - - # Overwrite the config arguments using kwargs - config = replace(config, **kwargs) - - return cls(serial_number=cam_sn, config=config, **kwargs) + return cam_sn def connect(self): if self.is_connected: diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 99f1ec7821..4843e9b22b 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -9,7 +9,6 @@ import shutil import threading import time -from dataclasses import replace from pathlib import Path from threading import Thread @@ -195,7 +194,10 @@ class OpenCVCamera: Example of usage: ```python - camera = OpenCVCamera(camera_index=0) + from lerobot.common.robot_devices.cameras.configs import OpenCVCameraConfig + + config = OpenCVCameraConfig(camera_index=0) + camera = OpenCVCamera(config) camera.connect() color_image = camera.read() # when done using the camera, consider disconnecting @@ -204,20 +206,15 @@ class OpenCVCamera: Example of changing default fps, width, height and color_mode: ```python - camera = OpenCVCamera(camera_index=0, fps=30, width=1280, height=720) - camera = connect() # applies the settings, might error out if these settings are not compatible with the camera - - camera = OpenCVCamera(camera_index=0, fps=90, width=640, height=480) - camera = connect() - - camera = OpenCVCamera(camera_index=0, fps=90, width=640, height=480, color_mode="bgr") - camera = connect() + config = OpenCVCameraConfig(camera_index=0, fps=30, width=1280, height=720) + config = OpenCVCameraConfig(camera_index=0, fps=90, width=640, height=480) + config = OpenCVCameraConfig(camera_index=0, fps=90, width=640, height=480, color_mode="bgr") + # Note: might error out open `camera.connect()` if these settings are not compatible with the camera ``` """ - def __init__(self, config: OpenCVCameraConfig | None = None, **kwargs): - config = OpenCVCameraConfig(**kwargs) if config is None else replace(config, **kwargs) - + def __init__(self, config: OpenCVCameraConfig): + self.config = config self.camera_index = config.camera_index self.port = None diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index 24d4546161..f646e260c8 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -16,7 +16,7 @@ class ControlConfig(draccus.ChoiceRegistry): @ControlConfig.register_subclass("calibrate") @dataclass class CalibrateControlConfig(ControlConfig): - # List of arms to calibrate (e.g. `--arms left_follower right_follower left_leader`) + # List of arms to calibrate (e.g. `--arms='["left_follower","right_follower"]' left_leader`) arms: list[str] | None = None diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index bbadf2ba70..54836d8ecb 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 dataclasses import replace import numpy as np import tqdm @@ -254,7 +253,6 @@ def __init__(self, message="Joint is out of range"): class DynamixelMotorsBus: - # TODO(rcadene): Add a script to find the motor indices without DynamixelWizzard2 """ The DynamixelMotorsBus class allows to efficiently read and write to the attached motors. It relies on the python dynamixel sdk to communicate with the motors. For more info, see the [Dynamixel SDK Documentation](https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20). @@ -276,10 +274,11 @@ class DynamixelMotorsBus: motor_index = 6 motor_model = "xl330-m288" - motors_bus = DynamixelMotorsBus( + config = DynamixelMotorsBusConfig( port="/dev/tty.usbmodem575E0031751", motors={motor_name: (motor_index, motor_model)}, ) + motors_bus = DynamixelMotorsBus(config) motors_bus.connect() position = motors_bus.read("Present_Position") @@ -295,24 +294,14 @@ class DynamixelMotorsBus: def __init__( self, - config: DynamixelMotorsBusConfig | None = None, - extra_model_control_table: dict[str, list[tuple]] | None = None, - extra_model_resolution: dict[str, int] | None = None, - **kwargs, + config: DynamixelMotorsBusConfig, ): - config = DynamixelMotorsBusConfig(**kwargs) if config is None else replace(config, **kwargs) - self.port = config.port self.motors = config.motors self.mock = config.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 diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/robot_devices/motors/feetech.py index b915f47e26..fd5e877bf6 100644 --- a/lerobot/common/robot_devices/motors/feetech.py +++ b/lerobot/common/robot_devices/motors/feetech.py @@ -4,7 +4,6 @@ import time import traceback from copy import deepcopy -from dataclasses import replace import numpy as np import tqdm @@ -254,10 +253,11 @@ class FeetechMotorsBus: motor_index = 6 motor_model = "sts3215" - motors_bus = FeetechMotorsBus( + config = FeetechMotorsBusConfig( port="/dev/tty.usbmodem575E0031751", motors={motor_name: (motor_index, motor_model)}, ) + motors_bus = FeetechMotorsBus(config) motors_bus.connect() position = motors_bus.read("Present_Position") @@ -273,24 +273,14 @@ class FeetechMotorsBus: def __init__( self, - config: FeetechMotorsBusConfig | None = None, - extra_model_control_table: dict[str, list[tuple]] | None = None, - extra_model_resolution: dict[str, int] | None = None, - **kwargs, + config: FeetechMotorsBusConfig, ): - config = FeetechMotorsBusConfig(**kwargs) if config is None else replace(config, **kwargs) - self.port = config.port self.motors = config.motors self.mock = config.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 diff --git a/lerobot/common/robot_devices/robots/configs.py b/lerobot/common/robot_devices/robots/configs.py index 6d615b2879..a976f601c2 100644 --- a/lerobot/common/robot_devices/robots/configs.py +++ b/lerobot/common/robot_devices/robots/configs.py @@ -85,7 +85,7 @@ class AlohaRobotConfig(ManipulatorRobotConfig): # Also, everything is expected to work safely out-of-the-box, but we highly advise to # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully - max_relative_target: int = 5 + max_relative_target: int | None = 5 leader_arms: dict[str, MotorsBusConfig] = field( default_factory=lambda: { diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index a46d7dc058..ceeaa9a88e 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -8,7 +8,6 @@ import logging import time import warnings -from dataclasses import replace from pathlib import Path import numpy as np @@ -144,11 +143,8 @@ class ManipulatorRobot: def __init__( self, config: ManipulatorRobotConfig, - **kwargs, ): - # Overwrite config arguments using kwargs - self.config = replace(config, **kwargs) - + self.config = config self.robot_type = self.config.type self.calibration_dir = Path(self.config.calibration_dir) self.leader_arms = make_motors_buses_from_configs(self.config.leader_arms) diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index c7401ba8e6..a7195c0b38 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -57,9 +57,9 @@ python lerobot/scripts/control_robot.py replay \ --robot.type=so100 \ --control.type=replay \ - --control.fps 30 \ - --control.repo-id $USER/koch_test \ - --control.episode 0 + --control.fps=30 \ + --control.repo_id=$USER/koch_test \ + --control.episode=0 ``` - Record a full dataset in order to train a policy, with 2 seconds of warmup, @@ -88,12 +88,13 @@ - Train on this dataset with the ACT policy: ```bash -# TODO(rcadene): fix python lerobot/scripts/train.py \ - policy=act_koch_real \ - env=koch_real \ - dataset_repo_id=$USER/koch_pick_place_lego \ - hydra.run.dir=outputs/train/act_koch_real + --dataset.repo_id=${HF_USER}/koch_pick_place_lego \ + --policy.type=act \ + --output_dir=outputs/train/act_koch_pick_place_lego \ + --job_name=act_koch_pick_place_lego \ + --device=cuda \ + --wandb.enable=true ``` - Run the pretrained policy on the robot: @@ -102,12 +103,12 @@ --robot.type=so100 \ --control.type=record \ --control.fps=30 \ - --control.repo_id=$USER/eval_act_koch_real \ + --control.repo_id=$USER/eval_act_koch_pick_place_lego \ --control.num_episodes=10 \ --control.warmup_time_s=2 \ --control.episode_time_s=30 \ - --control.reset_time_s=10 - --control.pretrained_policy_path=outputs/train/act_koch_real/checkpoints/080000/pretrained_model + --control.reset_time_s=10 \ + --control.policy.path=outputs/train/act_koch_pick_place_lego/checkpoints/080000/pretrained_model ``` """ From e58b481b553f8708084546138bbabf55a9920edd Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Sun, 26 Jan 2025 15:49:15 +0100 Subject: [PATCH 2/7] fix unit tests --- .../common/robot_devices/cameras/intelrealsense.py | 5 ++++- lerobot/common/robot_devices/cameras/opencv.py | 3 ++- lerobot/common/robot_devices/cameras/utils.py | 12 +++++++++--- lerobot/common/robot_devices/motors/utils.py | 12 +++++++++--- 4 files changed, 24 insertions(+), 8 deletions(-) diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index dff2e9d907..7e65dba9d0 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -94,7 +94,10 @@ def save_images_from_cameras( cameras = [] for cam_sn in serial_numbers: print(f"{cam_sn=}") - camera = IntelRealSenseCamera(serial_number=cam_sn, fps=fps, width=width, height=height, mock=mock) + config = IntelRealSenseCameraConfig( + serial_number=cam_sn, fps=fps, width=width, height=height, mock=mock + ) + camera = IntelRealSenseCamera(config) camera.connect() print( f"IntelRealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 4843e9b22b..93c791fa28 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -126,7 +126,8 @@ def save_images_from_cameras( print("Connecting cameras") cameras = [] for cam_idx in camera_ids: - camera = OpenCVCamera(camera_index=cam_idx, fps=fps, width=width, height=height, mock=mock) + config = OpenCVCameraConfig(camera_index=cam_idx, fps=fps, width=width, height=height, mock=mock) + camera = OpenCVCamera(config) camera.connect() print( f"OpenCVCamera({camera.camera_index}, fps={camera.fps}, width={camera.width}, " diff --git a/lerobot/common/robot_devices/cameras/utils.py b/lerobot/common/robot_devices/cameras/utils.py index 73675fc250..88288ea3f3 100644 --- a/lerobot/common/robot_devices/cameras/utils.py +++ b/lerobot/common/robot_devices/cameras/utils.py @@ -2,7 +2,11 @@ import numpy as np -from lerobot.common.robot_devices.cameras.configs import CameraConfig +from lerobot.common.robot_devices.cameras.configs import ( + CameraConfig, + IntelRealSenseCameraConfig, + OpenCVCameraConfig, +) # Defines a camera type @@ -36,12 +40,14 @@ def make_camera(camera_type, **kwargs) -> Camera: if camera_type == "opencv": from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera - return OpenCVCamera(**kwargs) + config = OpenCVCameraConfig(**kwargs) + return OpenCVCamera(config) elif camera_type == "intelrealsense": from lerobot.common.robot_devices.cameras.intelrealsense import IntelRealSenseCamera - return IntelRealSenseCamera(**kwargs) + config = IntelRealSenseCameraConfig(**kwargs) + return IntelRealSenseCamera(config) else: raise ValueError(f"The camera type '{camera_type}' is not valid.") diff --git a/lerobot/common/robot_devices/motors/utils.py b/lerobot/common/robot_devices/motors/utils.py index fb625339fd..fc64f050f0 100644 --- a/lerobot/common/robot_devices/motors/utils.py +++ b/lerobot/common/robot_devices/motors/utils.py @@ -1,6 +1,10 @@ from typing import Protocol -from lerobot.common.robot_devices.motors.configs import MotorsBusConfig +from lerobot.common.robot_devices.motors.configs import ( + DynamixelMotorsBusConfig, + FeetechMotorsBusConfig, + MotorsBusConfig, +) class MotorsBus(Protocol): @@ -36,12 +40,14 @@ def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: if motor_type == "dynamixel": from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus - return DynamixelMotorsBus(**kwargs) + config = DynamixelMotorsBusConfig(**kwargs) + return DynamixelMotorsBus(config) elif motor_type == "feetech": from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus - return FeetechMotorsBus(**kwargs) + config = FeetechMotorsBusConfig(**kwargs) + return FeetechMotorsBus(config) else: raise ValueError(f"The motor type '{motor_type}' is not valid.") From cfcd25134c76125e5bab698f28a2017c98c52d9f Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Sun, 26 Jan 2025 18:04:54 +0100 Subject: [PATCH 3/7] nit --- examples/7_get_started_with_real_robot.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 9f0c1fcbf1..4f7fdd15dc 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -105,10 +105,10 @@ 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: +Troubleshooting: On Linux, you might need to give access to the USB ports by running this command with your ports: ```bash -sudo chmod 666 /dev/ttyACM0 -sudo chmod 666 /dev/ttyACM1 +sudo chmod 666 /dev/tty.usbmodem575E0032081 +sudo chmod 666 /dev/tty.usbmodem575E0031751 ``` *Listing and Configuring Motors* From 2cafb02aaad11ead738286734186b0c7e6b47ab6 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Sun, 26 Jan 2025 19:35:08 +0100 Subject: [PATCH 4/7] Update documentation --- examples/10_use_so100.md | 15 ++++++++++++--- examples/11_use_moss.md | 19 ++++++++++++++----- examples/7_get_started_with_real_robot.md | 15 +++++++++++---- examples/8_use_stretch.md | 1 + examples/9_use_aloha.md | 3 +++ .../common/robot_devices/control_configs.py | 2 +- lerobot/scripts/control_robot.py | 13 ++++++++----- lerobot/scripts/train.py | 3 ++- 8 files changed, 52 insertions(+), 19 deletions(-) diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index 151c3f2d35..293212f24c 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -230,8 +230,7 @@ Then you are ready to teleoperate your robot! Run this simple script (it won't c python lerobot/scripts/control_robot.py \ --robot.type=so100 \ --robot.cameras='{}' \ - --control.type=teleoperate \ - --control.display_cameras=false + --control.type=teleoperate ``` @@ -264,6 +263,7 @@ python lerobot/scripts/control_robot.py \ --robot.type=so100 \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/so100_test \ --control.tags='["so100","tutorial"]' \ --control.warmup_time_s=5 \ @@ -273,6 +273,8 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` +Note: You can resume recording by adding `--control.resume=true`. Also if you didn't push your dataset yet, add `--control.local_files_only=true`. + ## H. Visualize a dataset If you uploaded your dataset to the hub with `--control.push_to_hub=true`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by: @@ -283,7 +285,8 @@ echo ${HF_USER}/so100_test If you didn't upload with `--control.push_to_hub=false`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --repo-id ${HF_USER}/so100_test + --repo-id ${HF_USER}/so100_test \ + --local-files-only 1 ``` ## I. Replay an episode @@ -298,6 +301,8 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` +Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. + ## J. 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: @@ -311,6 +316,8 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` +Note: If you didn't push your dataset yet, add `--control.local_files_only=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.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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. @@ -327,12 +334,14 @@ python lerobot/scripts/control_robot.py \ --robot.type=so100 \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/eval_act_so100_test \ --control.tags='["tutorial"]' \ --control.warmup_time_s=5 \ --control.episode_time_s=30 \ --control.reset_time_s=30 \ --control.num_episodes=10 \ + --control.push_to_hub=true \ --control.policy.path=outputs/train/act_so100_test/checkpoints/last/pretrained_model ``` diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index c8261b930d..e35ba9b278 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -213,8 +213,7 @@ Then you are ready to teleoperate your robot! Run this simple script (it won't c python lerobot/scripts/control_robot.py \ --robot.type=moss \ --robot.cameras='{}' \ - --control.type=teleoperate \ - --control.display_cameras=false + --control.type=teleoperate ``` @@ -247,6 +246,7 @@ python lerobot/scripts/control_robot.py \ --robot.type=moss \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/moss_test \ --control.tags='["moss","tutorial"]' \ --control.warmup_time_s=5 \ @@ -256,17 +256,20 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` +Note: You can resume recording by adding `--control.resume=true`. Also if you didn't push your dataset yet, add `--control.local_files_only=true`. + ## 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: +If you uploaded your dataset to the hub with `--control.push_to_hub=true`, 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: +If you didn't upload with `--control.push_to_hub=false`, you can also visualize it locally with: ```bash python lerobot/scripts/visualize_dataset_html.py \ - --repo-id ${HF_USER}/moss_test + --repo-id ${HF_USER}/moss_test \ + --local-files-only 1 ``` ## Replay an episode @@ -281,6 +284,8 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` +Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. + ## 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: @@ -294,6 +299,8 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` +Note: If you didn't push your dataset yet, add `--control.local_files_only=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.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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. @@ -310,12 +317,14 @@ python lerobot/scripts/control_robot.py \ --robot.type=moss \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/eval_act_moss_test \ --control.tags='["tutorial"]' \ --control.warmup_time_s=5 \ --control.episode_time_s=30 \ --control.reset_time_s=30 \ --control.num_episodes=10 \ + --control.push_to_hub=true \ --control.policy.path=outputs/train/act_moss_test/checkpoints/last/pretrained_model ``` diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 4f7fdd15dc..3d863f5699 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -60,7 +60,7 @@ In the upcoming sections, you'll learn about our classes and functions by runnin ```bash python lerobot/scripts/control_robot.py \ --robot.type=koch \ - --robot.cameras='{}' # do not instantiate the cameras + --control.type=teleoperate ``` It will automatically: @@ -671,8 +671,8 @@ Instead of manually running the python code in a terminal window, you can use [` Try running this code to teleoperate your robot (if you dont have a camera, keep reading): ```bash python lerobot/scripts/control_robot.py \ - --robot.type=koch \ - --control.type=teleoperate + --robot.type=koch \ + --control.type=teleoperate ``` You will see a lot of lines appearing like this one: @@ -689,7 +689,7 @@ It contains Importantly: If you don't have any camera, you can remove them dynamically with this [draccus](https://github.com/dlwh/draccus) syntax `--robot.cameras='{}'`: ```bash -python lerobot/scripts/control_robot.py teleoperate \ +python lerobot/scripts/control_robot.py \ --robot.type=koch \ --robot.cameras='{}' \ --control.type=teleoperate @@ -762,6 +762,7 @@ Now run this to record 2 episodes: python lerobot/scripts/control_robot.py \ --robot.type=koch \ --control.type=record \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.fps=30 \ --control.repo_id=${HF_USER}/koch_test \ --control.tags='["tutorial"]' \ @@ -772,6 +773,7 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` + This will write your dataset locally to `~/.cache/huggingface/lerobot/{repo-id}` (e.g. `data/cadene/koch_test`) and push it on the hub at `https://huggingface.co/datasets/{HF_USER}/{repo-id}`. 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 @@ -826,6 +828,8 @@ python lerobot/scripts/visualize_dataset_html.py \ --repo-id ${HF_USER}/koch_test ``` +Note: You might need to add `--local-files-only 1` if your dataset was not uploaded to hugging face hub. + This will launch a local web server that looks like this:
Koch v1.1 leader and follower arms @@ -864,6 +868,8 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` +Note: You might need to add `--dataset.local_files_only=true` if your dataset was not uploaded to hugging face hub. + Let's explain it: 1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/koch_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 sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. @@ -948,6 +954,7 @@ python lerobot/scripts/control_robot.py \ --control.episode_time_s=30 \ --control.reset_time_s=30 \ --control.num_episodes=10 \ + --control.push_to_hub=true \ --control.policy.path=outputs/train/act_koch_test/checkpoints/last/pretrained_model ``` diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md index 29dc0a1674..2f8c0ffbb7 100644 --- a/examples/8_use_stretch.md +++ b/examples/8_use_stretch.md @@ -131,6 +131,7 @@ python lerobot/scripts/control_robot.py \ --robot.type=stretch \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/stretch_test \ --control.tags='["tutorial"]' \ --control.warmup_time_s=5 \ diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index e073b70592..d74c8b7aca 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -87,6 +87,7 @@ python lerobot/scripts/control_robot.py \ --robot.max_relative_target=null \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/aloha_test \ --control.tags='["tutorial"]' \ --control.warmup_time_s=5 \ @@ -156,12 +157,14 @@ python lerobot/scripts/control_robot.py \ --robot.type=aloha \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=${HF_USER}/eval_act_aloha_test \ --control.tags='["tutorial"]' \ --control.warmup_time_s=5 \ --control.episode_time_s=30 \ --control.reset_time_s=30 \ --control.num_episodes=10 \ + --control.push_to_hub=true \ --control.policy.path=outputs/train/act_aloha_test/checkpoints/last/pretrained_model \ --control.num_image_writer_processes=1 ``` diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index f646e260c8..4e76578864 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -27,7 +27,7 @@ class TeleoperateControlConfig(ControlConfig): fps: int | None = None teleop_time_s: float | None = None # Display all cameras on screen - display_cameras: bool = False + display_cameras: bool = True @ControlConfig.register_subclass("record") diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index a7195c0b38..12325c133b 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -17,12 +17,12 @@ ```bash python lerobot/scripts/control_robot.py \ --robot.type=so100 \ + --robot.cameras='{}' \ --control.type=teleoperate -# Remove the cameras from the robot definition. They are not used in 'teleoperate' anyway. +# Add the cameras from the robot definition to visualize them: python lerobot/scripts/control_robot.py \ --robot.type=so100 \ - --robot.cameras='{}' \ --control.type=teleoperate ``` @@ -40,9 +40,10 @@ --robot.type=so100 \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=$USER/koch_test \ --control.num_episodes=1 \ - --control.run_compute_stats=False + --control.push_to_hub=True ``` - Visualize dataset: @@ -83,8 +84,8 @@ - Tap escape key 'esc' to stop the data recording. This might require a sudo permission to allow your terminal to monitor keyboard events. -**NOTE**: You can resume/continue data recording by running the same data recording command and adding `--resume 1`. -If the dataset you want to extend is not on the hub, you also need to add `--local-files-only 1`. +**NOTE**: You can resume/continue data recording by running the same data recording command and adding `--control.resume=true`. +If the dataset you want to extend is not on the hub, you also need to add `--control.local_files_only=true`. - Train on this dataset with the ACT policy: ```bash @@ -103,11 +104,13 @@ --robot.type=so100 \ --control.type=record \ --control.fps=30 \ + --control.single_task="Grasp a lego block and put it in the bin." \ --control.repo_id=$USER/eval_act_koch_pick_place_lego \ --control.num_episodes=10 \ --control.warmup_time_s=2 \ --control.episode_time_s=30 \ --control.reset_time_s=10 \ + --control.push_to_hub=true \ --control.policy.path=outputs/train/act_koch_pick_place_lego/checkpoints/080000/pretrained_model ``` """ diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index 78facdeea6..5fc51a5291 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -227,7 +227,8 @@ def train(cfg: TrainPipelineConfig): num_total_params = sum(p.numel() for p in policy.parameters()) log_output_dir(cfg.output_dir) - logging.info(f"{cfg.env.task=}") + if cfg.env is not None: + logging.info(f"{cfg.env.task=}") logging.info(f"{cfg.offline.steps=} ({format_big_number(cfg.offline.steps)})") logging.info(f"{cfg.online.steps=}") logging.info(f"{offline_dataset.num_frames=} ({format_big_number(offline_dataset.num_frames)})") From 614fcd4c79c21ca320464e2754ecb2beea962fb4 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Sun, 26 Jan 2025 19:40:05 +0100 Subject: [PATCH 5/7] Use parser.wrap, logs, fix start_image_writer with no cameras --- lerobot/scripts/control_robot.py | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 12325c133b..3fdb0acc38 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -117,8 +117,8 @@ import logging import time - -import draccus +from dataclasses import asdict +from pprint import pformat # from safetensors.torch import load_file, save_file from lerobot.common.datasets.lerobot_dataset import LeRobotDataset @@ -144,6 +144,7 @@ from lerobot.common.robot_devices.robots.utils import Robot, make_robot_from_config from lerobot.common.robot_devices.utils import busy_wait, safe_disconnect from lerobot.common.utils.utils import has_method, init_logging, log_say +from lerobot.configs import parser ######################################################################################## # Control modes @@ -217,10 +218,11 @@ def record( root=cfg.root, local_files_only=cfg.local_files_only, ) - dataset.start_image_writer( - num_processes=cfg.num_image_writer_processes, - num_threads=cfg.num_image_writer_threads_per_camera * len(robot.cameras), - ) + if len(robot.cameras) > 0: + dataset.start_image_writer( + num_processes=cfg.num_image_writer_processes, + num_threads=cfg.num_image_writer_threads_per_camera * len(robot.cameras), + ) sanity_check_dataset_robot_compatibility(dataset, robot, cfg.fps, cfg.video) else: # Create empty dataset or load existing saved episodes @@ -340,9 +342,10 @@ def replay( log_control_info(robot, dt_s, fps=cfg.fps) -@draccus.wrap() +@parser.wrap() def control_robot(cfg: ControlPipelineConfig): init_logging() + logging.info(pformat(asdict(cfg))) robot = make_robot_from_config(cfg.robot) From 481490f8fb291e0e97d2b124e0d50386cd172103 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Mon, 27 Jan 2025 17:56:09 +0100 Subject: [PATCH 6/7] prepare __post_init__ control_configs --- .../common/robot_devices/control_configs.py | 23 ++++++++++++++----- 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index 4e76578864..b90e93cc85 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -1,3 +1,4 @@ +import logging from dataclasses import dataclass from pathlib import Path @@ -6,6 +7,7 @@ from lerobot.common.robot_devices.robots.configs import RobotConfig from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig +from lerobot.configs.train import TrainPipelineConfig @dataclass @@ -91,12 +93,21 @@ def __post_init__(self): cli_overrides = parser.get_cli_overrides("policy") self.policy = PreTrainedConfig.from_pretrained(policy_path, cli_overrides=cli_overrides) self.policy.pretrained_path = policy_path - - if self.policy is not None: - if self.device is None: - raise ValueError("Set one of the following device: cuda, cpu or mps") - elif self.device == "cuda" and self.use_amp is None: - raise ValueError("Set 'use_amp' to True or False.") + train_cfg = TrainPipelineConfig.from_pretrained(policy_path) + if self.use_amp != train_cfg.use_amp: + raise ValueError( + f"The policy you are trying to load has been trained with use_amp={train_cfg.use_amp} " + f"but you're trying to evaluate it with use_amp={self.use_amp}" + ) + if self.device == "mps" and train_cfg.device == "cuda": + logging.warning( + "You are loading a policy that has been trained with a Cuda kernel on a Metal backend." + "This is lilely to produced unexpected results due to differences between these two kernels." + ) + else: + logging.warning( + "No pretrained path was provided, evaluated policy will be built from scratch (random weights)." + ) @ControlConfig.register_subclass("replay") From e53dfe39e97d68f0b44e20072d7f1769ab441403 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Mon, 27 Jan 2025 18:29:12 +0100 Subject: [PATCH 7/7] Add auto device and amp for control_config and eval_config --- .../common/robot_devices/control_configs.py | 33 +++++++++++-------- lerobot/common/utils/utils.py | 20 +++++++++++ lerobot/configs/eval.py | 31 +++++++++++------ 3 files changed, 61 insertions(+), 23 deletions(-) diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index b90e93cc85..418265d94a 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -5,6 +5,7 @@ import draccus from lerobot.common.robot_devices.robots.configs import RobotConfig +from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig from lerobot.configs.train import TrainPipelineConfig @@ -93,21 +94,27 @@ def __post_init__(self): cli_overrides = parser.get_cli_overrides("policy") self.policy = PreTrainedConfig.from_pretrained(policy_path, cli_overrides=cli_overrides) self.policy.pretrained_path = policy_path - train_cfg = TrainPipelineConfig.from_pretrained(policy_path) - if self.use_amp != train_cfg.use_amp: - raise ValueError( - f"The policy you are trying to load has been trained with use_amp={train_cfg.use_amp} " - f"but you're trying to evaluate it with use_amp={self.use_amp}" - ) - if self.device == "mps" and train_cfg.device == "cuda": + + # When no device or use_amp are given, use the one from training config. + if self.device is None or self.use_amp is None: + train_cfg = TrainPipelineConfig.from_pretrained(policy_path) + if self.device is None: + self.device = train_cfg.device + if self.use_amp is None: + self.use_amp = train_cfg.use_amp + + # Automatically switch to available device if necessary + if not is_torch_device_available(self.device): + auto_device = auto_select_torch_device() + logging.warning(f"Device '{self.device}' is not available. Switching to '{auto_device}'.") + self.device = auto_device + + # Automatically deactivate AMP if necessary + if self.use_amp and not is_amp_available(self.device): logging.warning( - "You are loading a policy that has been trained with a Cuda kernel on a Metal backend." - "This is lilely to produced unexpected results due to differences between these two kernels." + f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." ) - else: - logging.warning( - "No pretrained path was provided, evaluated policy will be built from scratch (random weights)." - ) + self.use_amp = False @ControlConfig.register_subclass("replay") diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py index 329b8b8a21..d766089b5c 100644 --- a/lerobot/common/utils/utils.py +++ b/lerobot/common/utils/utils.py @@ -74,6 +74,26 @@ def get_safe_torch_device(try_device: str, log: bool = False) -> torch.device: return device +def is_torch_device_available(try_device: str) -> bool: + if try_device == "cuda": + return torch.cuda.is_available() + elif try_device == "mps": + return torch.backends.mps.is_available() + elif try_device == "cpu": + return True + else: + raise ValueError(f"Unknown device '{try_device}.") + + +def is_amp_available(device: str): + if device in ["cuda", "cpu"]: + return True + elif device == "mps": + return False + else: + raise ValueError(f"Unknown device '{device}.") + + def get_global_random_state() -> dict[str, Any]: """Get the random state for `random`, `numpy`, and `torch`.""" random_state_dict = { diff --git a/lerobot/configs/eval.py b/lerobot/configs/eval.py index c95929e136..10467fda2c 100644 --- a/lerobot/configs/eval.py +++ b/lerobot/configs/eval.py @@ -4,7 +4,7 @@ from pathlib import Path from lerobot.common import envs, policies # noqa: F401 -from lerobot.common.utils.utils import auto_select_torch_device +from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.default import EvalConfig from lerobot.configs.policies import PreTrainedConfig @@ -46,17 +46,28 @@ def __post_init__(self): cli_overrides = parser.get_cli_overrides("policy") self.policy = PreTrainedConfig.from_pretrained(policy_path, cli_overrides=cli_overrides) self.policy.pretrained_path = policy_path - train_cfg = TrainPipelineConfig.from_pretrained(policy_path) - if self.use_amp != train_cfg.use_amp: - raise ValueError( - f"The policy you are trying to load has been trained with use_amp={train_cfg.use_amp} " - f"but you're trying to evaluate it with use_amp={self.use_amp}" - ) - if self.device == "mps" and train_cfg.device == "cuda": + + # When no device or use_amp are given, use the one from training config. + if self.device is None or self.use_amp is None: + train_cfg = TrainPipelineConfig.from_pretrained(policy_path) + if self.device is None: + self.device = train_cfg.device + if self.use_amp is None: + self.use_amp = train_cfg.use_amp + + # Automatically switch to available device if necessary + if not is_torch_device_available(self.device): + auto_device = auto_select_torch_device() + logging.warning(f"Device '{self.device}' is not available. Switching to '{auto_device}'.") + self.device = auto_device + + # Automatically deactivate AMP if necessary + if self.use_amp and not is_amp_available(self.device): logging.warning( - "You are loading a policy that has been trained with a Cuda kernel on a Metal backend." - "This is lilely to produced unexpected results due to differences between these two kernels." + f"Automatic Mixed Precision (amp) is not available on device '{self.device}'. Deactivating AMP." ) + self.use_amp = False + else: logging.warning( "No pretrained path was provided, evaluated policy will be built from scratch (random weights)."