HIL-SERL Real Robot Training Workflow Guide

In this tutorial you will go through the full Human-in-the-Loop Sample-Efficient Reinforcement Learning (HIL-SERL) workflow using LeRobot. You will master training a policy with RL on a real robot in just a few hours.

HIL-SERL is a sample-efficient reinforcement learning algorithm that combines human demonstrations with online learning and human interventions. The approach starts from a small set of human demonstrations, uses them to train a reward classifier, and then employs an actor-learner architecture where humans can intervene during policy execution to guide exploration and correct unsafe behaviors. In this tutorial, you’ll use a gamepad to provide interventions and control the robot during the learning process.

It combines three key ingredients:

  1. Offline demonstrations & reward classifier: a handful of human-teleop episodes plus a vision-based success detector give the policy a shaped starting point.
  2. On-robot actor / learner loop with human interventions: a distributed Soft Actor Critic (SAC) learner updates the policy while an actor explores on the physical robot; the human can jump in at any time to correct dangerous or unproductive behaviour.
  3. Safety & efficiency tools: joint/end-effector (EE) bounds, crop region of interest (ROI) preprocessing and WandB monitoring keep the data useful and the hardware safe.

Together these elements let HIL-SERL reach near-perfect task success and faster cycle times than imitation-only baselines.

HIL-SERL workflow

HIL-SERL workflow, Luo et al. 2024

This guide provides step-by-step instructions for training a robot policy using LeRobot’s HilSerl implementation to train on a real robot.

What do I need?

What kind of tasks can I train?

One can use HIL-SERL to train on a variety of manipulation tasks. Some recommendations:

Install LeRobot with HIL-SERL

To install LeRobot with HIL-SERL, you need to install the hilserl extra.

pip install -e ".[hilserl]"

Real Robot Training Workflow

Understanding Configuration

The training process begins with proper configuration for the HILSerl environment. The configuration class of interest is HILSerlRobotEnvConfig in lerobot/common/envs/configs.py. Which is defined as:

class HILSerlRobotEnvConfig(EnvConfig):
    robot: RobotConfig | None = None    # Main robot agent (defined in `lerobot/common/robots`)
    teleop: TeleoperatorConfig | None = None    # Teleoperator agent, e.g., gamepad or leader arm, (defined in `lerobot/common/teleoperators`)
    wrapper: EnvTransformConfig | None = None    # Environment wrapper settings; check `lerobot/scripts/server/gym_manipulator.py`
    fps: int = 10    # Control frequency
    name: str = "real_robot"    # Environment name
    mode: str = None    # "record", "replay", or None (for training)
    repo_id: str | None = None    # LeRobot dataset repository ID
    dataset_root: str | None = None    # Local dataset root (optional)
    task: str = ""    # Task identifier
    num_episodes: int = 10    # Number of episodes for recording
    episode: int = 0    # episode index for replay
    device: str = "cuda"    # Compute device
    push_to_hub: bool = True    # Whether to push the recorded datasets to Hub
    pretrained_policy_name_or_path: str | None = None    # For policy loading
    reward_classifier_pretrained_path: str | None = None    # For reward model
    number_of_steps_after_success: int = 0    # For reward classifier, collect more positive examples after a success to train a classifier

Finding Robot Workspace Bounds

Before collecting demonstrations, you need to determine the appropriate operational bounds for your robot.

This helps simplify the problem of learning on the real robot in two ways: 1) by limiting the robot’s operational space to a specific region that solves the task and avoids unnecessary or unsafe exploration, and 2) by allowing training in end-effector space rather than joint space. Empirically, learning in joint space for reinforcement learning in manipulation is often a harder problem - some tasks are nearly impossible to learn in joint space but become learnable when the action space is transformed to end-effector coordinates.

Using find_joint_limits.py

This script helps you find the safe operational bounds for your robot’s end-effector. Given that you have a follower and leader arm, you can use the script to find the bounds for the follower arm that will be applied during training. Bounding the action space will reduce the redundant exploration of the agent and guarantees safety.

python -m lerobot.scripts.find_joint_limits \
    --robot.type=so100_follower \
    --robot.port=/dev/tty.usbmodem58760431541 \
    --robot.id=black \
    --teleop.type=so100_leader \
    --teleop.port=/dev/tty.usbmodem58760431551 \
    --teleop.id=blue

Workflow

  1. Run the script and move the robot through the space that solves the task
  2. The script will record the minimum and maximum end-effector positions and the joint angles and prints them to the console, for example:
    Max ee position [0.2417 0.2012 0.1027]
    Min ee position [0.1663 -0.0823 0.0336]
    Max joint positions [-20.0, -20.0, -20.0, -20.0, -20.0, -20.0]
    Min joint positions [50.0, 50.0, 50.0, 50.0, 50.0, 50.0]
  3. Use these values in the configuration of your teleoperation device (TeleoperatorConfig) under the end_effector_bounds field

Example Configuration

"end_effector_bounds": {
    "max": [0.24, 0.20, 0.10],
    "min": [0.16, -0.08, 0.03]
}

Collecting Demonstrations

With the bounds defined, you can safely collect demonstrations for training. Training RL with off-policy algorithm allows us to use offline datasets collected in order to improve the efficiency of the learning process.

Setting Up Record Mode

Create a configuration file for recording demonstrations (or edit an existing one like env_config_so100.json):

  1. Set mode to "record"
  2. Specify a unique repo_id for your dataset (e.g., “username/task_name”)
  3. Set num_episodes to the number of demonstrations you want to collect
  4. Set crop_params_dict to null initially (we’ll determine crops later)
  5. Configure robot, cameras, and other hardware settings

Example configuration section:

"mode": "record",
"repo_id": "username/pick_lift_cube",
"dataset_root": null,
"task": "pick_and_lift",
"num_episodes": 15,
"episode": 0,
"push_to_hub": true

Using a Teleoperation Device

Along with your robot, you will need a teleoperation device to control it in order to collect datasets of your task and perform interventions during the online training. We support using a gamepad or a keyboard or the leader arm of the robot.

HIL-Serl learns actions in the end-effector space of the robot. Therefore, the teleoperation will control the end-effector’s x,y,z displacements.

For that we need to define a version of the robot that takes actions in the end-effector space. Check the robot class SO100FollowerEndEffector and its configuration SO100FollowerEndEffectorConfig for the default parameters related to the end-effector space.

class SO100FollowerEndEffectorConfig(SO100FollowerConfig):
    """Configuration for the SO100FollowerEndEffector robot."""

    # Default bounds for the end-effector position (in meters)
    end_effector_bounds: dict[str, list[float]] = field( # bounds for the end-effector in x,y,z direction
        default_factory=lambda: {
            "min": [-1.0, -1.0, -1.0],  # min x, y, z
            "max": [1.0, 1.0, 1.0],  # max x, y, z
        }
    )

    max_gripper_pos: float = 50 # maximum gripper position that the gripper will be open at

    end_effector_step_sizes: dict[str, float] = field( # maximum step size for the end-effector in x,y,z direction
        default_factory=lambda: {
            "x": 0.02,
            "y": 0.02,
            "z": 0.02,
        }
    )

The Teleoperator defines the teleoperation device. You can check the list of available teleoperators in lerobot/common/teleoperators.

Setting up the Gamepad

The gamepad provides a very convenient way to control the robot and the episode state.

To setup the gamepad, you need to set the control_mode to "gamepad" and define the teleop section in the configuration file.

    "teleop": {
        "type": "gamepad",
        "use_gripper": true
    },

Figure shows the control mappings on a Logitech gamepad.

Gamepad button mapping for robot control and episode management

Setting up the SO101 leader

The SO101 leader arm has reduced gears that allows it to move and track the follower arm during exploration. Therefore, taking over is much smoother than the gearless SO100.

To setup the SO101 leader, you need to set the control_mode to "leader" and define the teleop section in the configuration file.

    "teleop": {
        "type": "so101_leader",
        "port": "/dev/tty.usbmodem585A0077921", # check your port number
        "use_degrees": true
    },

In order to annotate the success/failure of the episode, you will need to use a keyboard to press s for success, esc for failure. During the online training, press space to take over the policy and space again to give the control back to the policy.

Video: SO101 leader teleoperation

SO101 leader teleoperation example, the leader tracks the follower, press `space` to intervene

Recording Demonstrations

Start the recording process, an example of the config file can be found here:

python lerobot/scripts/rl/gym_manipulator.py --config_path lerobot/configs/env_config_so100.json

During recording:

  1. The robot will reset to the initial position defined in the configuration file fixed_reset_joint_positions
  2. Complete the task successfully
  3. The episode ends with a reward of 1 when you press the “success” button
  4. If the time limit is reached, or the fail button is pressed, the episode ends with a reward of 0
  5. You can rerecord an episode by pressing the “rerecord” button
  6. The process automatically continues to the next episode
  7. After recording all episodes, the dataset is pushed to the Hugging Face Hub (optional) and saved locally

Processing the Dataset

After collecting demonstrations, process them to determine optimal camera crops. Reinforcement learning is sensitive to background distractions, so it is important to crop the images to the relevant workspace area.

Visual RL algorithms learn directly from pixel inputs, making them vulnerable to irrelevant visual information. Background elements like changing lighting, shadows, people moving, or objects outside the workspace can confuse the learning process. Good ROI selection should:

Note: If you already know the crop parameters, you can skip this step and just set the crop_params_dict in the configuration file during recording.

Determining Crop Parameters

Use the crop_dataset_roi.py script to interactively select regions of interest in your camera images:

python lerobot/scripts/rl/crop_dataset_roi.py --repo-id username/pick_lift_cube
  1. For each camera view, the script will display the first frame
  2. Draw a rectangle around the relevant workspace area
  3. Press ‘c’ to confirm the selection
  4. Repeat for all camera views
  5. The script outputs cropping parameters and creates a new cropped dataset

Example output:

Selected Rectangular Regions of Interest (top, left, height, width):
observation.images.side: [180, 207, 180, 200]
observation.images.front: [180, 250, 120, 150]

Interactive cropping tool for selecting regions of interest

Updating Configuration

Add these crop parameters to your training configuration:

"crop_params_dict": {
    "observation.images.side": [180, 207, 180, 200],
    "observation.images.front": [180, 250, 120, 150]
},
"resize_size": [128, 128]

Recommended image resolution

Most vision-based policies have been validated on square inputs of either 128×128 (default) or 64×64 pixels. We therefore advise setting the resize_size parameter to [128, 128] – or [64, 64] if you need to save GPU memory and bandwidth. Other resolutions are possible but have not been extensively tested.

Training a Reward Classifier

The reward classifier plays an important role in the HIL-SERL workflow by automating reward assignment and automatically detecting episode success. Instead of manually defining reward functions or relying on human feedback for every timestep, the reward classifier learns to predict success/failure from visual observations. This enables the RL algorithm to learn efficiently by providing consistent and automated reward signals based on the robot’s camera inputs.

This guide explains how to train a reward classifier for human-in-the-loop reinforcement learning implementation of LeRobot. Reward classifiers learn to predict the reward value given a state which can be used in an RL setup to train a policy.

Note: Training a reward classifier is optional. You can start the first round of RL experiments by annotating the success manually with your gamepad or keyboard device.

The reward classifier implementation in modeling_classifier.py uses a pretrained vision model to process the images. It can output either a single value for binary rewards to predict success/fail cases or multiple values for multi-class settings.

Collecting a Dataset for the reward classifier

Before training, you need to collect a dataset with labeled examples. The record_dataset function in gym_manipulator.py enables the process of collecting a dataset of observations, actions, and rewards.

To collect a dataset, you need to modify some parameters in the environment configuration based on HILSerlRobotEnvConfig.

python lerobot/scripts/rl/gym_manipulator.py --config_path lerobot/configs/reward_classifier_train_config.json

Key Parameters for Data Collection

The number_of_steps_after_success parameter is crucial as it allows you to collect more positive examples. When a success is detected, the system will continue recording for the specified number of steps while maintaining the reward=1 label. Otherwise, there won’t be enough states in the dataset labeled to 1 to train a good classifier.

Example configuration section for data collection:

{
    "mode": "record",
    "repo_id": "hf_username/dataset_name",
    "dataset_root": "data/your_dataset",
    "num_episodes": 20,
    "push_to_hub": true,
    "fps": 10,
    "number_of_steps_after_success": 15
}

Reward Classifier Configuration

The reward classifier is configured using configuration_classifier.py. Here are the key parameters:

Example configuration for training the reward classifier:

{
  "policy": {
    "type": "reward_classifier",
    "model_name": "helper2424/resnet10",
    "model_type": "cnn",
    "num_cameras": 2,
    "num_classes": 2,
    "hidden_dim": 256,
    "dropout_rate": 0.1,
    "learning_rate": 1e-4,
    "device": "cuda",
    "use_amp": true,
    "input_features": {
      "observation.images.front": {
        "type": "VISUAL",
        "shape": [3, 128, 128]
      },
      "observation.images.side": {
        "type": "VISUAL",
        "shape": [3, 128, 128]
      }
    }
  }
}

Training the Classifier

To train the classifier, use the train.py script with your configuration:

python lerobot/scripts/train.py --config_path path/to/reward_classifier_train_config.json

Deploying and Testing the Model

To use your trained reward classifier, configure the HILSerlRobotEnvConfig to use your model:

env_config = HILSerlRobotEnvConfig(
    reward_classifier_pretrained_path="path_to_your_pretrained_trained_model",
    # Other environment parameters
)

or set the argument in the json config file.

{
    "reward_classifier_pretrained_path": "path_to_your_pretrained_model"
}

Run gym_manipulator.py to test the model.

python lerobot/scripts/rl/gym_manipulator.py --config_path path/to/env_config.json

The reward classifier will automatically provide rewards based on the visual input from the robot’s cameras.

Example Workflow for training the reward classifier

  1. Create the configuration files: Create the necessary json configuration files for the reward classifier and the environment. Check the examples here.

  2. Collect a dataset:

    python lerobot/scripts/rl/gym_manipulator.py --config_path lerobot/configs/env_config.json
  3. Train the classifier:

    python lerobot/scripts/train.py --config_path lerobot/configs/reward_classifier_train_config.json
  4. Test the classifier:

    python lerobot/scripts/rl/gym_manipulator.py --config_path lerobot/configs/env_config.json

Training with Actor-Learner

The LeRobot system uses a distributed actor-learner architecture for training. This architecture decouples robot interactions from the learning process, allowing them to run concurrently without blocking each other. The actor server handles robot observations and actions, sending interaction data to the learner server. The learner server performs gradient descent and periodically updates the actor’s policy weights. You will need to start two processes: a learner and an actor.

Configuration Setup

Create a training configuration file (example available here). The training config is based on the main TrainRLServerPipelineConfig class in lerobot/configs/train.py.

  1. Configure the policy settings (type="sac", device, etc.)
  2. Set dataset to your cropped dataset
  3. Configure environment settings with crop parameters
  4. Check the other parameters related to SAC in configuration_sac.py.
  5. Verify that the policy config is correct with the right input_features and output_features for your task.

Starting the Learner

First, start the learner server process:

python lerobot/scripts/rl/learner.py --config_path lerobot/configs/train_config_hilserl_so100.json

The learner:

Starting the Actor

In a separate terminal, start the actor process with the same configuration:

python lerobot/scripts/rl/actor.py --config_path lerobot/configs/train_config_hilserl_so100.json

The actor:

Training Flow

The training proceeds automatically:

  1. The actor executes the policy in the environment
  2. Transitions are collected and sent to the learner
  3. The learner updates the policy based on these transitions
  4. Updated policy parameters are sent back to the actor
  5. The process continues until the specified step limit is reached

Human in the Loop

Figure shows the control mappings on a Logitech gamepad.

Example showing how human interventions help guide policy learning over time

Monitoring and Debugging

If you have wandb.enable set to true in your configuration, you can monitor training progress in real-time through the Weights & Biases dashboard.

Guide to Human Interventions

The learning process is very sensitive to the intervention strategy. It will takes a few runs to understand how to intervene effectively. Some tips and hints:

The ideal behaviour is that your intervention rate should drop gradually during training as shown in the figure below.

Intervention rate

Plot of the intervention rate during a training run on a pick and lift cube task

Key hyperparameters to tune

Some configuration values have a disproportionate impact on training stability and speed:

Congrats 🎉, you have finished this tutorial!

If you have any questions or need help, please reach out on Discord.

Paper citation:

@article{luo2024precise,
  title={Precise and Dexterous Robotic Manipulation via Human-in-the-Loop Reinforcement Learning},
  author={Luo, Jianlan and Xu, Charles and Wu, Jeffrey and Levine, Sergey},
  journal={arXiv preprint arXiv:2410.21845},
  year={2024}
}
< > Update on GitHub