🤗 This repository is a fork of lerobot
by XenseRobotics, used for Xense's multimodal tactile data acquisition system.
This branch tracks upstream lerobot v5.1, with Xense-specific robots
(BiARX5, BiFlexiv Rizon4 RT, Xense Flare), teleoperators (Pico4, dual
SpaceMouse) and tactile cameras layered on top. For generic lerobot
usage (datasets, policies, training scripts) refer to the
upstream README.
Tested on Ubuntu 22.04, NVIDIA driver ≥ 570.144. Use
Mamba
(strongly recommended over plain conda — it's much faster on the
robostack-staging channel that ships ROS Humble + SOEM). v5.1 pins
Python 3.12 and PyTorch ≥ 2.2 with CUDA 12.8.
curl -L -O "https://github.com/conda-forge/miniforge/releases/latest/download/Miniforge3-$(uname)-$(uname -m).sh"
bash Miniforge3-$(uname)-$(uname -m).shStep 1: 📂 Clone the repository with all submodules:
git clone \
--recurse-submodules \
https://github.com/Vertax42/lerobot-xense.git
cd lerobot-xenseIf you already cloned without submodules, initialize them manually:
git submodule update --init --recursive --progress
This repository uses third_party/ git submodules to manage hardware SDK dependencies:
| Submodule | Installed package |
|---|---|
third_party/ARX5_SDK |
pyarx |
third_party/libpyflexiv |
flexiv_rt |
third_party/XenseVR-PC-Service |
xensevr_pc_service_sdk |
third_party/XGripper |
xensegripper |
third_party/xense_franka |
xense_franka |
third_party/elite-robots-cs-sdk |
Elite CS C++ SDK (builds elite_cs_sdk) |
third_party/elite-robots-cs-sdk-python |
elite_cs_sdk (Elite CS Python bindings) |
xensesdkis not a submodule — it is installed from the vendored wheeldist/xensesdk-2.0.0-cp312-cp312-linux_x86_64.whl(which bundles the patchedlibxense_c.soflash reader). The Elite Python SDK is built against the localthird_party/elite-robots-cs-sdkC++ submodule (no network fetch of the C++ source).
Step 2: 🐍 Create and activate the mamba environment:
bash ./setup_env.sh --mamba lerobot-xense
mamba activate lerobot-xenseThe default env name baked into
conda_environment.yamlislerobot-xense-py312. You can pass a different name to--mamba, but the rest of this README and the openpi project assumelerobot-xense-py312.
Step 3: 📦 Install LeRobot-Xense and all hardware SDK bindings:
bash ./setup_env.sh --installThis step will:
- Update the conda environment from
conda_environment.yaml - Install the main package from
pyproject.toml - Install
xensesdkfrom the vendored wheel (dist/xensesdk-2.0.0-cp312-cp312-linux_x86_64.whl) - Build and install all
third_partySDK packages:pyarx,flexiv_rt,xensevr_pc_service_sdk,xensegripper,xense_franka, andelite_cs_sdk(Elite CS — built from the C++ + Python submodules) - Configure SpaceMouse udev rules and HID permissions automatically
You will be prompted for
sudopassword during installation (for ARX5 real-time capability and udev rules).
Step 4: ✅ Verify the installation:
python -c 'import pyarx; print("pyarx OK ->", pyarx.__file__)'
python -c 'import flexiv_rt; print("flexiv_rt OK ->", flexiv_rt.__file__)'
python -c 'import xensevr_pc_service_sdk; print("xensevr_pc_service_sdk OK ->", xensevr_pc_service_sdk.__file__)'
python -c 'import xensesdk; print("xensesdk OK ->", xensesdk.__file__)'
python -c 'import xensegripper; print("xensegripper OK ->", xensegripper.__file__)'
python -c 'import elite_cs_sdk; print("elite_cs_sdk OK ->", elite_cs_sdk.__file__)'Step 5: 📌 Note on FFmpeg / video: v5.1 no longer pins ffmpeg
through conda (the robostack ICU pin conflicted with newer ffmpeg
builds). Video encoding/decoding is handled by torchcodec + av
wheels installed via setup_env.sh --install. If you need a system
ffmpeg with libsvtav1, install it separately (apt or upstream
static build):
# Optional: verify torchcodec wheel is loadable
python -c 'import torchcodec; print("torchcodec OK ->", torchcodec.__version__)'The ARX5 SDK requires CAP_SYS_NICE on the Python interpreter for real-time CAN thread scheduling. This is handled by setup_env.sh --install, but can be set manually:
PY_EXE=$(python -c 'import sys, os; p = sys.executable; print(os.path.realpath(p))')
sudo setcap cap_sys_nice+ep "$PY_EXE"
getcap "$PY_EXE" # should show: cap_sys_nice+epThis project includes advanced SpaceMouse support with both single and dual-device modes for precise robotic control.
System Requirements:
- Ubuntu 22.04 (tested) or other Linux distributions
- Python 3.12+
- libhidapi (installed via apt)
Python Packages:
pyspacemouse- Modern cross-platform SpaceMouse libraryhidapi- Python wrapper for HID APIeasyhid- Easy-to-use HID library (dependency of pyspacemouse)
All Python dependencies are automatically installed by setup_env.sh --install.
SpaceMouse requires proper udev rules to allow non-root access. See Step 2 in the Installation section above for complete setup instructions.
After installation and permissions setup, test your SpaceMouse:
# Basic functionality test (prints real-time 6-DoF values)
python test_pyspacemouse_basic.py
# Test with lerobot integration
python test_spacemouse.pyThe test script will display real-time position (x, y, z) and orientation (roll, pitch, yaw) values as you move the SpaceMouse.
📝 Note: If you're using a 3Dconnexion Universal Receiver (wireless), you may see multiple devices listed (e.g., 14 "UniversalReceiver" entries). This is normal - the receiver exposes multiple HID interfaces for different functions. PySpaceMouse will automatically select the correct interface for 6-DoF input.
- ✅ Modern PySpaceMouse Integration: Uses PySpaceMouse library for cross-platform SpaceMouse support
- ✅ No System Services Required: Direct HID communication, no need for spacenavd daemon
- ✅ Single Device Mode: Traditional 6-DoF control with one SpaceMouse
- ✅ Dual Device Mode: Advanced left/right hand coordination for complex manipulation
- ✅ Flexible Axis Assignment: Configure which device controls position vs orientation
- ✅ Independent Sensitivity: Per-device sensitivity settings for optimal control
from lerobot.teleoperators.spacemouse import SpacemouseConfig, SpacemouseTeleop
# Standard single SpaceMouse setup (default)
config = SpacemouseConfig(
pos_sensitivity=0.8, # Position control sensitivity
ori_sensitivity=1.5, # Orientation control sensitivity
deadzone=0.1, # Deadzone threshold
frequency=200, # Polling frequency (Hz)
)
teleop = SpacemouseTeleop(config)Perfect for complex robotic tasks requiring precise position and orientation control:
from lerobot.teleoperators.spacemouse import SpacemouseConfig, DeviceConfig
# Left hand controls position, right hand controls orientation
config = SpacemouseConfig(
multi_device_mode=True,
left_device=DeviceConfig(
device_index=0,
enabled_axes=(True, True, True, False, False, False), # X, Y, Z position only
pos_sensitivity=0.8,
ori_sensitivity=0.0, # Disabled
),
right_device=DeviceConfig(
device_index=1,
enabled_axes=(False, False, False, True, True, True), # Roll, pitch, yaw only
pos_sensitivity=0.0, # Disabled
ori_sensitivity=1.5,
)
)
teleop = SpacemouseTeleop(config)See examples/spacemouse_dual_config_example.py for complete configuration examples including:
- Position/Orientation split control
- Dual-arm robot control
- Fine/Coarse movement control
- 🤖 Dual-Arm Robots: Independent control of two robotic arms
- 🎯 Precision Manipulation: Decouple position and orientation control for fine tasks
- 🔄 Complex Assembly: Left hand positions, right hand orients components
- 🏭 Industrial Applications: Enhanced ergonomics and control precision
- Single Mode: Any 3Dconnexion SpaceMouse device
- Dual Mode: Two identical SpaceMouse devices (e.g., two SpaceNavigators)
All 3Dconnexion devices supported by PySpaceMouse:
- SpaceNavigator
- SpaceMouse Pro
- SpaceMouse Wireless
- SpaceMouse Compact
- And more...
Lerobot record XenseFlare dataset can be directly used for FlexivRizon4 policy training. 🎉
For lerobot-record with --robot.type=bi_flexiv_rizon4_rt --teleop.type=bi_pico4, the controller buttons are mapped as follows:
| Controller button | Keyboard equivalent | Action |
|---|---|---|
Right A |
go_start |
Reset both arms to start pose (RT non-blocking, recording continues) |
Left X |
rerecord_episode |
Discard current episode and re-record |
Left Y |
exit_early |
Finish current episode early |
Right B |
stop_recording |
Stop the recording session |
Button state is refreshed via BiPico4.poll_buttons() at the top of each loop iteration, before event checks. Keyboard events and controller buttons are unified into the same events[] checks — both are equal-priority input sources.
During RT reset, the record loop keeps running: observations are still sampled, teleop actions are still read, and the teleop pose is re-synced to the robot once the reset trajectory finishes.
This section documents the dataset construction logic in flexiv_rizon4_rt_record_loop, which handles both normal teleoperation recording and the RT reset trajectory recording for bi_flexiv_rizon4_rt + bi_pico4.
while timestamp < control_time_s:
poll_buttons() # lightweight button refresh (no pose computation)
# Unified event checks — keyboard OR controller button, symmetric
stop_recording / B → break
rerecord / X → break
exit_early / Y → break
go_start / A → reset_to_initial_position(), recording continues
get_observation()
check robot_is_moving + sync teleop if reset just finished
get_action()
send_action / dataset write
| Variable | Role |
|---|---|
reset_triggered |
Per-frame flag. Set True the frame reset is triggered. Skips send_action and dataset write for that frame only. Resets to False at the start of every iteration. |
prev_rt_moving |
Edge-detection flag. Set True while robot.rt_moving is True. Cleared to False when movement stops, triggering one call to _sync_rt_teleop_to_robot_pose(). |
prev_observation_frame |
Holds the previous frame's observation. Used by shifted-frame logic to pair obs[t-1] with the robot's actual position at obs[t] as the action. |
robot.send_action(teleop_action) → sent_action
dataset: { obs[t], action = sent_action[t] } # direct frame
prev_observation_frame = obs[t]
robot.reset_to_initial_position() # C++ RT thread takes over arm control
send_action → skipped
dataset → skipped
prev_observation_frame = obs[T] # saved as anchor for next iteration
obs[T] is intentionally not written to the dataset. It is used as prev_observation_frame for the first shifted frame on the next iteration, so it appears exactly once — without this skip it would appear twice (once as a direct frame, once as the prev of the first shifted frame).
send_action → skipped (C++ RT thread drives the arm autonomously)
current_as_action = { key: obs[t][key] for key in robot.action_features }
# robot.action_features = left/right TCP pose (9D each) + gripper (1D each) = 20D total
# Iterates action_features keys only — image keys in obs[t] are excluded automatically.
dataset: { obs[t-1], action = current_as_action } # shifted frame
prev_observation_frame = obs[t]
The action is extracted from the current observation using the same keys as robot.action_features. This records where the robot actually moved to, not what the teleop commanded — the same shifted-frame convention used by bi_arx5_record_loop.
| Frame | reset_triggered |
robot_is_moving |
send_action |
Dataset write | prev_obs updated to |
|---|---|---|---|---|---|
| T-1 (normal teleop) | False | False | ✓ | {obs[T-1], action[T-1]} direct |
obs[T-1] |
| T (reset triggered) | True | False | skipped | skipped | obs[T] |
| T+1 (RT moving) | False | True | skipped | {obs[T], state_20d[T+1]} shifted |
obs[T+1] |
| T+2 (RT moving) | False | True | skipped | {obs[T+1], state_20d[T+2]} shifted |
obs[T+2] |
| … | False | True | skipped | shifted | … |
| N+1 (reset done, teleop synced) | False | False | ✓ | {obs[N+1], action[N+1]} direct |
obs[N+1] |
state_20d[t] = {k: obs[t][k] for k in robot.action_features} — left/right TCP pose (9D each) + gripper (1D each), image keys excluded.
frame T-2 normal teleop → dataset: { obs[T-2], action[T-2] }
frame T-1 normal teleop → dataset: { obs[T-1], action[T-1] }, prev=obs[T-1]
frame T reset trigger → dataset: skipped, prev=obs[T]
frame T+1 rt_moving → dataset: { obs[T], state_20d[T+1] }, prev=obs[T+1]
frame T+2 rt_moving → dataset: { obs[T+1], state_20d[T+2] }, prev=obs[T+2]
...
frame N rt_moving → dataset: { obs[N-1], state_20d[N] }, prev=obs[N]
frame N+1 reset done → _sync_rt_teleop_to_robot_pose()
normal teleop → dataset: { obs[N+1], action[N+1] }
When prev_rt_moving transitions True → False (frame N+1), _sync_rt_teleop_to_robot_pose() is called once. This reads the robot's current TCP pose (now at start position) and calls teleop.reset_to_pose(), updating the Pico4's internal _start_pos reference. Without this sync the teleop would compute position deltas from the pre-reset pose, causing the arm to jump on the first grip after reset.
A dataset in LeRobotDataset format is very simple to use. It can be loaded from a repository on the Hugging Face hub or a local folder simply with e.g. dataset = LeRobotDataset("lerobot/aloha_static_coffee") and can be indexed into like any Hugging Face and PyTorch dataset. For instance dataset[0] will retrieve a single temporal frame from the dataset containing observation(s) and an action as PyTorch tensors ready to be fed to a model.
A specificity of LeRobotDataset is that, rather than retrieving a single frame by its index, we can retrieve several frames based on their temporal relationship with the indexed frame, by setting delta_timestamps to a list of relative times with respect to the indexed frame. For example, with delta_timestamps = {"observation.image": [-1, -0.5, -0.2, 0]} one can retrieve, for a given index, 4 frames: 3 "previous" frames 1 second, 0.5 seconds, and 0.2 seconds before the indexed frame, and the indexed frame itself (corresponding to the 0 entry). See example 1_load_lerobot_dataset.py for more details on delta_timestamps.
Under the hood, the LeRobotDataset format makes use of several ways to serialize data which can be useful to understand if you plan to work more closely with this format. We tried to make a flexible yet simple dataset format that would cover most type of features and specificities present in reinforcement learning and robotics, in simulation and in real-world, with a focus on cameras and robot states but easily extended to other types of sensory inputs as long as they can be represented by a tensor.
Here are the important details and internal structure organization of a typical LeRobotDataset instantiated with dataset = LeRobotDataset("lerobot/aloha_static_coffee"). The exact features will change from dataset to dataset but not the main aspects:
dataset attributes:
├ hf_dataset: a Hugging Face dataset (backed by Arrow/parquet). Typical features example:
│ ├ observation.images.cam_high (VideoFrame):
│ │ VideoFrame = {'path': path to a mp4 video, 'timestamp' (float32): timestamp in the video}
│ ├ observation.state (list of float32): position of an arm joints (for instance)
│ ... (more observations)
│ ├ action (list of float32): goal position of an arm joints (for instance)
│ ├ episode_index (int64): index of the episode for this sample
│ ├ frame_index (int64): index of the frame for this sample in the episode ; starts at 0 for each episode
│ ├ timestamp (float32): timestamp in the episode
│ ├ next.done (bool): indicates the end of an episode ; True for the last frame in each episode
│ └ index (int64): general index in the whole dataset
├ meta: a LeRobotDatasetMetadata object containing:
│ ├ info: a dictionary of metadata on the dataset
│ │ ├ codebase_version (str): this is to keep track of the codebase version the dataset was created with
│ │ ├ fps (int): frame per second the dataset is recorded/synchronized to
│ │ ├ features (dict): all features contained in the dataset with their shapes and types
│ │ ├ total_episodes (int): total number of episodes in the dataset
│ │ ├ total_frames (int): total number of frames in the dataset
│ │ ├ robot_type (str): robot type used for recording
│ │ ├ data_path (str): formattable string for the parquet files
│ │ └ video_path (str): formattable string for the video files (if using videos)
│ ├ episodes: a DataFrame containing episode metadata with columns:
│ │ ├ episode_index (int): index of the episode
│ │ ├ tasks (list): list of tasks for this episode
│ │ ├ length (int): number of frames in this episode
│ │ ├ dataset_from_index (int): start index of this episode in the dataset
│ │ └ dataset_to_index (int): end index of this episode in the dataset
│ ├ stats: a dictionary of statistics (max, mean, min, std) for each feature in the dataset, for instance
│ │ ├ observation.images.front_cam: {'max': tensor with same number of dimensions (e.g. `(c, 1, 1)` for images, `(c,)` for states), etc.}
│ │ └ ...
│ └ tasks: a DataFrame containing task information with task names as index and task_index as values
├ root (Path): local directory where the dataset is stored
├ image_transforms (Callable): optional image transformations to apply to visual modalities
└ delta_timestamps (dict): optional delta timestamps for temporal queries
A LeRobotDataset is serialised using several widespread file formats for each of its parts, namely:
- hf_dataset stored using Hugging Face datasets library serialization to parquet
- videos are stored in mp4 format to save space
- metadata are stored in plain json/jsonl files
Dataset can be uploaded/downloaded from the HuggingFace hub seamlessly. To work on a local dataset, you can specify its location with the root argument if it's not in the default ~/.cache/huggingface/lerobot location.
🎉 Major SpaceMouse System Overhaul:
- Modern Library Migration: Migrated from legacy
spnavto modernPySpaceMouselibrary - Cross-Platform Support: Now supports Linux, macOS, and Windows
- No System Dependencies: Removed requirement for
spacenavdsystem service - Dual-Device Support: Revolutionary dual SpaceMouse mode for advanced manipulation
- Flexible Configuration: Per-device sensitivity and axis assignment
- Hardware Independence: Direct HID communication for better reliability
Breaking Changes:
spacenavdservice is no longer required- Configuration options have been expanded with new dual-device parameters
- Old single-device configurations remain fully compatible
Migration Benefits:
- ✅ Easier setup (no system services to configure)
- ✅ Better cross-platform compatibility
- ✅ More responsive input handling
- ✅ Advanced dual-hand control capabilities
- ✅ Future-proof with active library maintenance
If you use this codebase, please cite the original LeRobot project:
@misc{cadene2024lerobot,
author = {Cadene, Remi and Alibert, Simon and Soare, Alexander and Gallouedec, Quentin and Zouitine, Adil and Palma, Steven and Kooijmans, Pepijn and Aractingi, Michel and Shukor, Mustafa and Aubakirova, Dana and Russi, Martino and Capuano, Francesco and Pascal, Caroline and Choghari, Jade and Moss, Jess and Wolf, Thomas},
title = {LeRobot: State-of-the-art Machine Learning for Real-World Robotics in Pytorch},
howpublished = "\url{https://github.com/huggingface/lerobot}",
year = {2024}
}