Compare commits

...

4 Commits

Author SHA1 Message Date
Pepijn 995244dc8e docs: apply prettier formatting to reBot B601 page
Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-05-18 11:45:19 +02:00
Pepijn eae2d0a1ac docs: fix reBot B601 MDX build (move JSON example out of <Tip>)
The doc-builder parses `{...}` inside MDX component children as a
Svelte expression, so the joint_directions JSON example broke the
build. Move it into a top-level fenced code block.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-05-18 11:45:06 +02:00
Pepijn ed14a714f4 docs: add reBot B601-DM calibration & dual-arm teleoperation guide
Add docs/source/rebot_b601.mdx covering single-arm and bimanual
calibration and teleoperation for the reBot B601-DM follower and
reBot Arm 102 leader, with zero-position reference images from the
Seeed Studio wiki. Register the page in the docs toctree.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-05-18 11:41:59 +02:00
Pepijn 462a8aea90 feat(robots): natively integrate Seeed Studio reBot B601-DM arm
Add first-class LeRobot support for the Seeed Studio reBot arm, replacing
the out-of-tree `lerobot-robot-seeed-b601` / `lerobot-teleoperator-rebot-arm-102`
plugin packages.

New devices:
- robot `rebot_b601_follower` — single-arm B601-DM follower (6-DOF + gripper,
  Damiao CAN motors via `motorbridge`)
- robot `bi_rebot_b601_follower` — bimanual follower composing two single arms
- teleoperator `rebot_102_leader` — single-arm StarArm102 / reBot Arm 102 leader
  (FashionStar UART servos via `motorbridge-smart-servo`)
- teleoperator `bi_rebot_102_leader` — bimanual leader composing two single arms

The bimanual variants reuse the single-arm classes and namespace each arm's
observation/action keys with `left_` / `right_` prefixes, so a bimanual
StarArm102 leader can teleoperate a bimanual reBot B601 follower.

Optional SDK imports are guarded; a `rebot` extra installs `motorbridge` and
`motorbridge-smart-servo`.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-05-18 11:33:46 +02:00
29 changed files with 1670 additions and 3 deletions
+2
View File
@@ -141,6 +141,8 @@
title: OMX
- local: openarm
title: OpenArm
- local: rebot_b601
title: reBot B601-DM
title: "Robots"
- sections:
- local: phone_teleop
+178
View File
@@ -0,0 +1,178 @@
# reBot B601-DM
[reBot B601-DM](https://wiki.seeedstudio.com/rebot_arm_b601_dm_lerobot/) is an open-source, low-cost robot arm from Seeed Studio for embodied-AI and imitation learning. It comes as a **follower** arm (the `B601-DM`, a 6-DOF arm plus gripper driven by Damiao CAN motors) and a **leader** arm (the `StarArm102` / `reBot Arm 102`, driven by FashionStar UART smart servos) used to teleoperate it.
This page covers **calibration** and **teleoperation** for both single-arm and bimanual (dual-arm) setups.
<div style="display: flex; align-items: center; gap: 10px;">
<img
src="https://files.seeedstudio.com/wiki/robotics/projects/lerobot/b601dm_zeroposition.jpg"
alt="reBot B601-DM follower arm at its zero position"
width="48%"
/>
<img
src="https://files.seeedstudio.com/wiki/robotics/projects/lerobot/102_zeroposition.jpg"
alt="reBot Arm 102 leader arm at its zero position"
width="48%"
/>
</div>
_Left: the B601-DM follower at its zero position. Right: the reBot Arm 102 leader at its zero position. Images courtesy of [Seeed Studio](https://wiki.seeedstudio.com/rebot_arm_b601_dm_lerobot/)._
## Install LeRobot 🤗
Follow our [Installation Guide](./installation), then install the reBot support:
```bash
pip install -e ".[rebot]"
```
This pulls in `motorbridge` (CAN motor control for the B601-DM follower) and `motorbridge-smart-servo` (FashionStar UART servos for the reBot Arm 102 leader).
<Tip warning={true}>
On Linux, remove `brltty` (`sudo apt remove brltty`) so it does not hold the
leader's USB serial port. You may also need to grant access to the serial
devices: `sudo chmod 666 /dev/ttyACM* /dev/ttyUSB*`.
</Tip>
## Registered device types
| Type | Kind |
| ------------------------ | -------------------------------------------- |
| `rebot_b601_follower` | single-arm B601-DM follower robot |
| `bi_rebot_b601_follower` | bimanual (dual-arm) follower robot |
| `rebot_102_leader` | single-arm reBot Arm 102 leader teleoperator |
| `bi_rebot_102_leader` | bimanual (dual-arm) leader teleoperator |
The bimanual types compose two single-arm instances and namespace each arm's
observation/action keys with a `left_` / `right_` prefix. Per-arm settings are
passed through nested `left_arm_config.*` / `right_arm_config.*` arguments.
## Calibration
Neither arm stores a persistent hardware calibration: every time it connects, the motors are re-zeroed against the pose the arm is physically holding. Calibration simply records that zero pose. When prompted, **manually move the arm to its zero position** (the default sit-down pose shown above, gripper fully closed) and press <kbd>ENTER</kbd>.
### Follower (B601-DM)
<hfoptions id="calibrate-follower">
<hfoption id="Single arm">
```bash
lerobot-calibrate \
--robot.type=rebot_b601_follower \
--robot.port=/dev/ttyACM0 \
--robot.id=follower \
--robot.can_adapter=damiao
```
</hfoption>
<hfoption id="Dual arm">
Connect the bimanual follower; calibration runs for the left arm, then the right arm.
```bash
lerobot-calibrate \
--robot.type=bi_rebot_b601_follower \
--robot.id=bi_follower \
--robot.left_arm_config.port=/dev/ttyACM0 \
--robot.left_arm_config.can_adapter=damiao \
--robot.right_arm_config.port=/dev/ttyACM1 \
--robot.right_arm_config.can_adapter=damiao
```
Per-arm calibration files are saved with `_left` / `_right` suffixes on the id.
</hfoption>
</hfoptions>
### Leader (reBot Arm 102)
<hfoptions id="calibrate-leader">
<hfoption id="Single arm">
```bash
lerobot-calibrate \
--teleop.type=rebot_102_leader \
--teleop.port=/dev/ttyUSB0 \
--teleop.id=leader
```
</hfoption>
<hfoption id="Dual arm">
```bash
lerobot-calibrate \
--teleop.type=bi_rebot_102_leader \
--teleop.id=bi_leader \
--teleop.left_arm_config.port=/dev/ttyUSB0 \
--teleop.right_arm_config.port=/dev/ttyUSB1
```
</hfoption>
</hfoptions>
## Teleoperation
Once both arms are calibrated, drive the follower with the leader. The follower talks to its CAN bus through a Damiao serial bridge (`can_adapter=damiao`, the default) or a SocketCAN adapter (`can_adapter=socketcan`).
<hfoptions id="teleoperate">
<hfoption id="Single arm">
```bash
lerobot-teleoperate \
--robot.type=rebot_b601_follower \
--robot.port=/dev/ttyACM0 \
--robot.id=follower \
--robot.can_adapter=damiao \
--teleop.type=rebot_102_leader \
--teleop.port=/dev/ttyUSB0 \
--teleop.id=leader
```
</hfoption>
<hfoption id="Dual arm">
The bimanual leader and follower reuse the single-arm classes; each arm is
configured through nested `left_arm_config.*` / `right_arm_config.*` arguments,
so a bimanual reBot Arm 102 leader drives a bimanual B601-DM follower.
```bash
lerobot-teleoperate \
--robot.type=bi_rebot_b601_follower \
--robot.id=bi_follower \
--robot.left_arm_config.port=/dev/ttyACM0 \
--robot.left_arm_config.can_adapter=damiao \
--robot.right_arm_config.port=/dev/ttyACM1 \
--robot.right_arm_config.can_adapter=damiao \
--teleop.type=bi_rebot_102_leader \
--teleop.id=bi_leader \
--teleop.left_arm_config.port=/dev/ttyUSB0 \
--teleop.right_arm_config.port=/dev/ttyUSB1
```
</hfoption>
</hfoptions>
<Tip>
The leader and follower share the same joint names (`shoulder_pan,
shoulder_lift, elbow_flex, wrist_flex, wrist_yaw, wrist_roll, gripper`), so
leader actions map directly onto the follower.
</Tip>
If the motion of a joint is reversed, flip its sign in the leader's `joint_directions` (the gripper also carries a scale to widen its range to the follower):
```bash
lerobot-teleoperate \
--robot.type=rebot_b601_follower \
--robot.port=/dev/ttyACM0 \
--robot.can_adapter=damiao \
--teleop.type=rebot_102_leader \
--teleop.port=/dev/ttyUSB0 \
--teleop.joint_directions='{"shoulder_pan":-1,"shoulder_lift":-1,"elbow_flex":1,"wrist_flex":1,"wrist_yaw":1,"wrist_roll":-1,"gripper":-6}'
```
## Recording datasets
Swap `lerobot-teleoperate` for `lerobot-record` (with the same `--robot.*` / `--teleop.*` arguments, plus `--dataset.*`) to record demonstrations for training. See [Imitation Learning for Robots](./il_robots) for the full workflow.
For hardware assembly and wiring, see the [Seeed Studio reBot wiki](https://wiki.seeedstudio.com/rebot_arm_b601_dm_lerobot/).
+6
View File
@@ -151,6 +151,8 @@ pyserial-dep = ["pyserial>=3.5,<4.0"]
deepdiff-dep = ["deepdiff>=7.0.1,<9.0.0"]
pynput-dep = ["pynput>=1.7.8,<1.9.0"]
pyzmq-dep = ["pyzmq>=26.2.1,<28.0.0"]
motorbridge-dep = ["motorbridge>=0.3.2,<0.4.0"]
motorbridge-smart-servo-dep = ["motorbridge-smart-servo>=0.0.4,<0.1.0"]
# Motors
feetech = ["feetech-servo-sdk>=1.0.0,<2.0.0", "lerobot[pyserial-dep]", "lerobot[deepdiff-dep]"]
@@ -174,6 +176,9 @@ unitree_g1 = [
"lerobot[pygame-dep]",
]
reachy2 = ["reachy2_sdk>=1.0.15,<1.1.0"]
# Seeed Studio reBot B601-DM follower (motorbridge / CAN) + StarArm102 / reBot Arm 102
# leader (motorbridge-smart-servo / FashionStar UART servos).
rebot = ["lerobot[motorbridge-dep]", "lerobot[motorbridge-smart-servo-dep]"]
kinematics = ["lerobot[placo-dep]"]
intelrealsense = [
"pyrealsense2>=2.55.1.6486,<2.57.0 ; sys_platform != 'darwin'",
@@ -260,6 +265,7 @@ all = [
"lerobot[lekiwi]",
"lerobot[openarms]",
"lerobot[reachy2]",
"lerobot[rebot]",
"lerobot[kinematics]",
"lerobot[intelrealsense]",
"lerobot[diffusion]",
@@ -0,0 +1,20 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from .bi_rebot_b601_follower import BiRebotB601Follower
from .config_bi_rebot_b601_follower import BiRebotB601FollowerConfig
__all__ = ["BiRebotB601Follower", "BiRebotB601FollowerConfig"]
@@ -0,0 +1,150 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import logging
from functools import cached_property
from lerobot.types import RobotAction, RobotObservation
from lerobot.utils.decorators import check_if_already_connected, check_if_not_connected
from ..rebot_b601_follower import RebotB601Follower, RebotB601FollowerRobotConfig
from ..robot import Robot
from .config_bi_rebot_b601_follower import BiRebotB601FollowerConfig
logger = logging.getLogger(__name__)
class BiRebotB601Follower(Robot):
"""Bimanual Seeed Studio reBot B601-DM follower.
Composes two single-arm :class:`RebotB601Follower` instances. Observation and
action keys of each arm are namespaced with a ``left_`` / ``right_`` prefix.
"""
config_class = BiRebotB601FollowerConfig
name = "bi_rebot_b601_follower"
def __init__(self, config: BiRebotB601FollowerConfig):
super().__init__(config)
self.config = config
left_arm_config = RebotB601FollowerRobotConfig(
id=f"{config.id}_left" if config.id else None,
calibration_dir=config.calibration_dir,
port=config.left_arm_config.port,
can_adapter=config.left_arm_config.can_adapter,
dm_serial_baud=config.left_arm_config.dm_serial_baud,
disable_torque_on_disconnect=config.left_arm_config.disable_torque_on_disconnect,
max_relative_target=config.left_arm_config.max_relative_target,
cameras=config.left_arm_config.cameras,
motor_can_ids=config.left_arm_config.motor_can_ids,
pos_vel_velocity=config.left_arm_config.pos_vel_velocity,
gripper_torque_ratio=config.left_arm_config.gripper_torque_ratio,
joint_limits=config.left_arm_config.joint_limits,
)
right_arm_config = RebotB601FollowerRobotConfig(
id=f"{config.id}_right" if config.id else None,
calibration_dir=config.calibration_dir,
port=config.right_arm_config.port,
can_adapter=config.right_arm_config.can_adapter,
dm_serial_baud=config.right_arm_config.dm_serial_baud,
disable_torque_on_disconnect=config.right_arm_config.disable_torque_on_disconnect,
max_relative_target=config.right_arm_config.max_relative_target,
cameras=config.right_arm_config.cameras,
motor_can_ids=config.right_arm_config.motor_can_ids,
pos_vel_velocity=config.right_arm_config.pos_vel_velocity,
gripper_torque_ratio=config.right_arm_config.gripper_torque_ratio,
joint_limits=config.right_arm_config.joint_limits,
)
self.left_arm = RebotB601Follower(left_arm_config)
self.right_arm = RebotB601Follower(right_arm_config)
# Only for compatibility with parts of the codebase that expect `robot.cameras`.
self.cameras = {**self.left_arm.cameras, **self.right_arm.cameras}
@property
def _motors_ft(self) -> dict[str, type]:
return {
**{f"left_{k}": v for k, v in self.left_arm._motors_ft.items()},
**{f"right_{k}": v for k, v in self.right_arm._motors_ft.items()},
}
@property
def _cameras_ft(self) -> dict[str, tuple]:
return {
**{f"left_{k}": v for k, v in self.left_arm._cameras_ft.items()},
**{f"right_{k}": v for k, v in self.right_arm._cameras_ft.items()},
}
@cached_property
def observation_features(self) -> dict[str, type | tuple]:
return {**self._motors_ft, **self._cameras_ft}
@cached_property
def action_features(self) -> dict[str, type]:
return self._motors_ft
@property
def is_connected(self) -> bool:
return self.left_arm.is_connected and self.right_arm.is_connected
@check_if_already_connected
def connect(self, calibrate: bool = True) -> None:
self.left_arm.connect(calibrate)
self.right_arm.connect(calibrate)
@property
def is_calibrated(self) -> bool:
return self.left_arm.is_calibrated and self.right_arm.is_calibrated
def calibrate(self) -> None:
self.left_arm.calibrate()
self.right_arm.calibrate()
def configure(self) -> None:
self.left_arm.configure()
self.right_arm.configure()
@check_if_not_connected
def get_observation(self) -> RobotObservation:
obs_dict = {}
obs_dict.update({f"left_{k}": v for k, v in self.left_arm.get_observation().items()})
obs_dict.update({f"right_{k}": v for k, v in self.right_arm.get_observation().items()})
return obs_dict
@check_if_not_connected
def send_action(self, action: RobotAction) -> RobotAction:
left_action = {
key.removeprefix("left_"): value for key, value in action.items() if key.startswith("left_")
}
right_action = {
key.removeprefix("right_"): value for key, value in action.items() if key.startswith("right_")
}
sent_action_left = self.left_arm.send_action(left_action)
sent_action_right = self.right_arm.send_action(right_action)
return {
**{f"left_{k}": v for k, v in sent_action_left.items()},
**{f"right_{k}": v for k, v in sent_action_right.items()},
}
@check_if_not_connected
def disconnect(self) -> None:
self.left_arm.disconnect()
self.right_arm.disconnect()
@@ -0,0 +1,29 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from dataclasses import dataclass
from ..config import RobotConfig
from ..rebot_b601_follower import RebotB601FollowerConfig
@RobotConfig.register_subclass("bi_rebot_b601_follower")
@dataclass
class BiRebotB601FollowerConfig(RobotConfig):
"""Configuration class for the bimanual reBot B601-DM follower robot."""
left_arm_config: RebotB601FollowerConfig
right_arm_config: RebotB601FollowerConfig
@@ -0,0 +1,20 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from .config_rebot_b601_follower import RebotB601FollowerConfig, RebotB601FollowerRobotConfig
from .rebot_b601_follower import RebotB601Follower
__all__ = ["RebotB601Follower", "RebotB601FollowerConfig", "RebotB601FollowerRobotConfig"]
@@ -0,0 +1,94 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from dataclasses import dataclass, field
from lerobot.cameras import CameraConfig
from ..config import RobotConfig
@dataclass
class RebotB601FollowerConfig:
"""Base configuration class for the Seeed Studio reBot B601-DM follower arm.
The B601-DM is a 6-DOF arm plus gripper driven by Damiao CAN motors. Motor
communication goes through the ``motorbridge`` package.
"""
# Communication port. For ``can_adapter="damiao"`` this is the Damiao serial
# bridge device (e.g. "/dev/ttyACM0"); for ``can_adapter="socketcan"`` it is
# the CAN channel name (e.g. "can0").
port: str
# CAN adapter type:
# "damiao" - Damiao dedicated serial bridge (default)
# "socketcan" - SocketCAN based adapters (PCAN, slcan, embedded controllers, ...)
can_adapter: str = "damiao"
# Baud rate for the Damiao serial bridge (only used when can_adapter="damiao").
dm_serial_baud: int = 921600
disable_torque_on_disconnect: bool = True
# `max_relative_target` limits the magnitude of the relative positional target
# vector for safety purposes (in degrees). Set to a positive scalar to apply the
# same value to all motors, or to a dict mapping motor names to per-motor values.
max_relative_target: float | dict[str, float] | None = None
# cameras
cameras: dict[str, CameraConfig] = field(default_factory=dict)
# Maps motor names to their (send_can_id, recv_can_id) pair.
motor_can_ids: dict[str, tuple[int, int]] = field(
default_factory=lambda: {
"shoulder_pan": (0x01, 0x11),
"shoulder_lift": (0x02, 0x12),
"elbow_flex": (0x03, 0x13),
"wrist_flex": (0x04, 0x14),
"wrist_yaw": (0x05, 0x15),
"wrist_roll": (0x06, 0x16),
"gripper": (0x07, 0x17),
}
)
# Target velocity for joints running in POS_VEL mode, in degrees/s. A scalar is
# applied to every joint; a list provides one value per joint (in motor order).
pos_vel_velocity: float | list[float] = field(default_factory=lambda: [150.0] * 7)
# Torque/current ratio for the gripper's FORCE_POS mode, in range [0, 1].
gripper_torque_ratio: float = 0.1
# Soft joint limits (degrees). These are clipped against on every action.
joint_limits: dict[str, tuple[float, float]] = field(
default_factory=lambda: {
"shoulder_pan": (-145.0, 145.0),
"shoulder_lift": (-170.0, 1.0),
"elbow_flex": (-200.0, 1.0),
"wrist_flex": (-80.0, 90.0),
"wrist_yaw": (-90.0, 90.0),
"wrist_roll": (-90.0, 90.0),
"gripper": (-270.0, 0.0),
}
)
@RobotConfig.register_subclass("rebot_b601_follower")
@dataclass
class RebotB601FollowerRobotConfig(RobotConfig, RebotB601FollowerConfig):
"""Registered configuration for the reBot B601-DM follower robot."""
pass
@@ -0,0 +1,66 @@
# reBot B601-DM
Native LeRobot integration for the [Seeed Studio reBot B601-DM](https://wiki.seeedstudio.com/rebot_arm_b601_dm_lerobot/)
robot arm — a 6-DOF arm plus gripper driven by Damiao CAN motors — together with
the **StarArm102 / reBot Arm 102** leader arm used to teleoperate it.
This page covers single-arm and bimanual setups for both the follower (robot)
and the leader (teleoperator).
## Install LeRobot 🤗
Follow the [Installation Guide](./installation), then install the reBot extra:
```bash
pip install -e ".[rebot]"
```
This pulls in `motorbridge` (CAN motor control for the B601-DM follower) and
`motorbridge-smart-servo` (FashionStar UART servos for the reBot Arm 102 leader).
> On Linux, remove `brltty` (`sudo apt remove brltty`) so it does not hold the
> leader's USB serial port.
## Calibration
Neither arm stores a persistent hardware calibration: at every connection the
motors are re-zeroed against the pose the arm is physically holding. When
prompted, move the arm to its zero pose (the default sit-down position, gripper
closed) and press ENTER.
## Single-arm teleoperation
The follower talks to its CAN bus through a Damiao serial bridge
(`can_adapter=damiao`, the default) or a SocketCAN adapter (`can_adapter=socketcan`).
```bash
lerobot-teleoperate \
--robot.type=rebot_b601_follower \
--robot.port=/dev/ttyACM0 \
--teleop.type=rebot_102_leader \
--teleop.port=/dev/ttyUSB0
```
## Bimanual teleoperation
The bimanual robot and teleoperator reuse the single-arm classes; each arm is
configured through a nested `left_arm_config` / `right_arm_config`, and its
observation/action keys are namespaced with a `left_` / `right_` prefix.
```bash
lerobot-teleoperate \
--robot.type=bi_rebot_b601_follower \
--robot.left_arm_config.port=/dev/ttyACM0 \
--robot.right_arm_config.port=/dev/ttyACM1 \
--teleop.type=bi_rebot_102_leader \
--teleop.left_arm_config.port=/dev/ttyUSB0 \
--teleop.right_arm_config.port=/dev/ttyUSB1
```
## Recording datasets
Swap `lerobot-teleoperate` for `lerobot-record` (with the same `--robot.*` /
`--teleop.*` arguments) to record demonstrations for training.
See the [Seeed Studio wiki](https://wiki.seeedstudio.com/rebot_arm_b601_dm_lerobot/)
for hardware assembly and wiring details.
@@ -0,0 +1,285 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import logging
import math
import time
from functools import cached_property
from typing import TYPE_CHECKING
from lerobot.cameras import make_cameras_from_configs
from lerobot.motors import MotorCalibration
from lerobot.types import RobotAction, RobotObservation
from lerobot.utils.decorators import check_if_already_connected, check_if_not_connected
from lerobot.utils.import_utils import _motorbridge_available, require_package
from ..robot import Robot
from ..utils import ensure_safe_goal_position
from .config_rebot_b601_follower import RebotB601FollowerRobotConfig
if TYPE_CHECKING or _motorbridge_available:
from motorbridge import Controller as MotorBridgeController, Mode as MotorBridgeMode
else:
MotorBridgeController = None
MotorBridgeMode = None
logger = logging.getLogger(__name__)
# Joint controlled in FORCE_POS mode; every other joint runs in POS_VEL mode.
GRIPPER_MOTOR = "gripper"
# Per-joint Damiao motor models for the B601-DM (passed to motorbridge).
MOTOR_MODELS = {
"shoulder_pan": "4340P",
"shoulder_lift": "4340P",
"elbow_flex": "4340P",
"wrist_flex": "4310",
"wrist_yaw": "4310",
"wrist_roll": "4310",
"gripper": "4310",
}
_ENSURE_MODE_RETRIES = 9
_SETTLE_SEC = 0.01
_ZERO_SETTLE_SEC = 0.1
class RebotB601Follower(Robot):
"""Seeed Studio reBot B601-DM follower arm (6-DOF + gripper, Damiao CAN motors).
Motor communication is handled by the ``motorbridge`` package over a CAN bus,
reached either through a Damiao serial bridge or a SocketCAN adapter.
"""
config_class = RebotB601FollowerRobotConfig
name = "rebot_b601_follower"
def __init__(self, config: RebotB601FollowerRobotConfig):
require_package("motorbridge", extra="rebot")
super().__init__(config)
self.config = config
self.bus: MotorBridgeController | None = None
self.motors: dict = {}
self.motor_names = list(config.motor_can_ids.keys())
self.cameras = make_cameras_from_configs(config.cameras)
@property
def _motors_ft(self) -> dict[str, type]:
return {f"{motor}.pos": float for motor in self.motor_names}
@property
def _cameras_ft(self) -> dict[str, tuple]:
return {
cam: (self.config.cameras[cam].height, self.config.cameras[cam].width, 3) for cam in self.cameras
}
@cached_property
def observation_features(self) -> dict[str, type | tuple]:
return {**self._motors_ft, **self._cameras_ft}
@cached_property
def action_features(self) -> dict[str, type]:
return self._motors_ft
@property
def is_connected(self) -> bool:
return self.bus is not None and all(cam.is_connected for cam in self.cameras.values())
@check_if_already_connected
def connect(self, calibrate: bool = True) -> None:
logger.info(f"Connecting {self} on {self.config.port} (adapter={self.config.can_adapter})...")
if self.config.can_adapter == "damiao":
self.bus = MotorBridgeController.from_dm_serial(
serial_port=self.config.port,
baud=self.config.dm_serial_baud,
)
elif self.config.can_adapter == "socketcan":
self.bus = MotorBridgeController(channel=self.config.port)
else:
raise ValueError(
f"Unsupported can_adapter '{self.config.can_adapter}'. Use 'damiao' or 'socketcan'."
)
for motor_name, (send_id, recv_id) in self.config.motor_can_ids.items():
self.motors[motor_name] = self.bus.add_damiao_motor(send_id, recv_id, MOTOR_MODELS[motor_name])
if not self.is_calibrated and calibrate:
logger.info(
"Mismatch between calibration values in the motor and the calibration file or no calibration file found"
)
self.calibrate()
for cam in self.cameras.values():
cam.connect()
self.configure()
logger.info(f"{self} connected.")
@property
def is_calibrated(self) -> bool:
return bool(self.calibration)
def calibrate(self) -> None:
if self.calibration:
user_input = input(
f"Press ENTER to use provided calibration file associated with the id {self.id}, "
"or type 'c' and press ENTER to run calibration: "
)
if user_input.strip().lower() != "c":
logger.info(f"Using calibration file associated with the id {self.id}")
return
logger.info(f"\nRunning calibration of {self}")
self.bus.disable_all()
print(
"\nCalibration: set zero position.\n"
"Manually move the reBot B601 to its ZERO POSITION and close the gripper.\n"
"See the B601 manual for the zero pose (the default sit-down position).\n"
)
input("Press ENTER when ready...")
for motor in self.motors.values():
motor.set_zero_position()
time.sleep(_ZERO_SETTLE_SEC)
logger.info("Arm zero position set.")
self.calibration = {}
for motor_name, (send_id, _recv_id) in self.config.motor_can_ids.items():
self.calibration[motor_name] = MotorCalibration(
id=send_id,
drive_mode=0,
homing_offset=0,
range_min=-90,
range_max=90,
)
self._save_calibration()
print(f"Calibration saved to {self.calibration_fpath}")
def configure(self) -> None:
self.bus.enable_all()
for motor_name, motor in self.motors.items():
target_mode = (
MotorBridgeMode.FORCE_POS if motor_name == GRIPPER_MOTOR else MotorBridgeMode.POS_VEL
)
for attempt in range(_ENSURE_MODE_RETRIES + 1):
try:
motor.ensure_mode(target_mode)
break
except Exception:
if attempt == _ENSURE_MODE_RETRIES:
raise
time.sleep(_SETTLE_SEC)
logger.debug(f"{motor_name} mode set to {target_mode}")
@check_if_not_connected
def disable_torque(self) -> None:
"""Disable motor torque so the arm can be moved by hand (read-only debugging)."""
self.bus.disable_all()
logger.info(f"{self} torque disabled.")
def _present_pos(self) -> dict[str, float]:
"""Read present joint positions in degrees."""
for motor in self.motors.values():
motor.request_feedback()
try:
self.bus.poll_feedback_once()
except Exception:
logger.warning("CAN bus poll feedback failed.")
present_pos = {}
for motor_name, motor in self.motors.items():
state = motor.get_state()
present_pos[motor_name] = math.degrees(state.pos) if state is not None else 0.0
return present_pos
@check_if_not_connected
def get_observation(self) -> RobotObservation:
start = time.perf_counter()
obs_dict = {f"{motor}.pos": pos for motor, pos in self._present_pos().items()}
dt_ms = (time.perf_counter() - start) * 1e3
logger.debug(f"{self} read state: {dt_ms:.1f}ms")
for cam_key, cam in self.cameras.items():
start = time.perf_counter()
obs_dict[cam_key] = cam.read_latest()
dt_ms = (time.perf_counter() - start) * 1e3
logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
return obs_dict
@check_if_not_connected
def send_action(self, action: RobotAction) -> RobotAction:
"""Command the arm to a target joint configuration.
Positions are expressed in degrees. The relative action magnitude may be
clipped depending on `max_relative_target`, so the action actually sent is
always returned.
"""
goal_pos = {key.removesuffix(".pos"): val for key, val in action.items() if key.endswith(".pos")}
# Clip against soft joint limits.
for motor_name in list(goal_pos):
if motor_name in self.config.joint_limits:
min_limit, max_limit = self.config.joint_limits[motor_name]
clipped = max(min_limit, min(max_limit, goal_pos[motor_name]))
if clipped != goal_pos[motor_name]:
logger.debug(f"Clipped {motor_name} from {goal_pos[motor_name]:.2f} to {clipped:.2f}")
goal_pos[motor_name] = clipped
# Tolerate 6-DOF leaders without a wrist_yaw joint by holding it at zero.
if "wrist_yaw" not in goal_pos:
goal_pos["wrist_yaw"] = 0.0
# Cap relative target when too far from the present position.
if self.config.max_relative_target is not None:
present_pos = self._present_pos()
goal_present_pos = {key: (g, present_pos.get(key, g)) for key, g in goal_pos.items()}
goal_pos = ensure_safe_goal_position(goal_present_pos, self.config.max_relative_target)
for motor_name, position_deg in goal_pos.items():
motor = self.motors.get(motor_name)
if motor is None:
continue
idx = self.motor_names.index(motor_name)
vel_deg_s = (
self.config.pos_vel_velocity[idx]
if isinstance(self.config.pos_vel_velocity, list)
else self.config.pos_vel_velocity
)
pos_rad = math.radians(position_deg)
vel_rad = math.radians(vel_deg_s)
if motor_name == GRIPPER_MOTOR:
motor.send_force_pos(pos_rad, vel_rad, self.config.gripper_torque_ratio)
else:
motor.send_pos_vel(pos_rad, vel_rad)
return {f"{motor}.pos": val for motor, val in goal_pos.items()}
@check_if_not_connected
def disconnect(self) -> None:
for motor in self.motors.values():
if self.config.disable_torque_on_disconnect:
motor.disable()
motor.clear_error()
motor.close()
self.bus.close()
self.bus = None
self.motors = {}
for cam in self.cameras.values():
cam.disconnect()
logger.info(f"{self} disconnected.")
+8
View File
@@ -68,6 +68,14 @@ def make_robot_from_config(config: RobotConfig) -> Robot:
from .bi_openarm_follower import BiOpenArmFollower
return BiOpenArmFollower(config)
elif config.type == "rebot_b601_follower":
from .rebot_b601_follower import RebotB601Follower
return RebotB601Follower(config)
elif config.type == "bi_rebot_b601_follower":
from .bi_rebot_b601_follower import BiRebotB601Follower
return BiRebotB601Follower(config)
elif config.type == "mock_robot":
from tests.mocks.mock_robot import MockRobot
+4
View File
@@ -39,6 +39,7 @@ from lerobot.robots import ( # noqa: F401
Robot,
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
hope_jr,
koch_follower,
@@ -46,12 +47,14 @@ from lerobot.robots import ( # noqa: F401
make_robot_from_config,
omx_follower,
openarm_follower,
rebot_b601_follower,
so_follower,
)
from lerobot.teleoperators import ( # noqa: F401
Teleoperator,
TeleoperatorConfig,
bi_openarm_leader,
bi_rebot_102_leader,
bi_so_leader,
homunculus,
koch_leader,
@@ -59,6 +62,7 @@ from lerobot.teleoperators import ( # noqa: F401
omx_leader,
openarm_leader,
openarm_mini,
rebot_102_leader,
so_leader,
unitree_g1,
)
@@ -45,16 +45,19 @@ from lerobot.model import RobotKinematics
from lerobot.robots import ( # noqa: F401
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
koch_follower,
make_robot_from_config,
omx_follower,
openarm_follower,
rebot_b601_follower,
so_follower,
)
from lerobot.teleoperators import ( # noqa: F401
TeleoperatorConfig,
bi_openarm_leader,
bi_rebot_102_leader,
bi_so_leader,
gamepad,
koch_leader,
@@ -62,6 +65,7 @@ from lerobot.teleoperators import ( # noqa: F401
omx_leader,
openarm_leader,
openarm_mini,
rebot_102_leader,
so_leader,
)
from lerobot.utils.robot_utils import precise_sleep
+4
View File
@@ -99,6 +99,7 @@ from lerobot.robots import ( # noqa: F401
Robot,
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
earthrover_mini_plus,
hope_jr,
@@ -107,6 +108,7 @@ from lerobot.robots import ( # noqa: F401
omx_follower,
openarm_follower,
reachy2,
rebot_b601_follower,
so_follower,
unitree_g1 as unitree_g1_robot,
)
@@ -114,6 +116,7 @@ from lerobot.teleoperators import ( # noqa: F401
Teleoperator,
TeleoperatorConfig,
bi_openarm_leader,
bi_rebot_102_leader,
bi_so_leader,
homunculus,
koch_leader,
@@ -122,6 +125,7 @@ from lerobot.teleoperators import ( # noqa: F401
openarm_leader,
openarm_mini,
reachy2_teleoperator,
rebot_102_leader,
so_leader,
unitree_g1,
)
+2
View File
@@ -56,6 +56,7 @@ from lerobot.robots import ( # noqa: F401
Robot,
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
earthrover_mini_plus,
hope_jr,
@@ -64,6 +65,7 @@ from lerobot.robots import ( # noqa: F401
omx_follower,
openarm_follower,
reachy2,
rebot_b601_follower,
so_follower,
unitree_g1,
)
+4
View File
@@ -132,6 +132,7 @@ from lerobot.robots import ( # noqa: F401
Robot,
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
earthrover_mini_plus,
hope_jr,
@@ -139,6 +140,7 @@ from lerobot.robots import ( # noqa: F401
omx_follower,
openarm_follower,
reachy2,
rebot_b601_follower,
so_follower,
unitree_g1 as unitree_g1_robot,
)
@@ -147,6 +149,7 @@ from lerobot.teleoperators import ( # noqa: F401
Teleoperator,
TeleoperatorConfig,
bi_openarm_leader,
bi_rebot_102_leader,
bi_so_leader,
homunculus,
koch_leader,
@@ -154,6 +157,7 @@ from lerobot.teleoperators import ( # noqa: F401
openarm_leader,
openarm_mini,
reachy2_teleoperator,
rebot_102_leader,
so_leader,
unitree_g1,
)
@@ -30,20 +30,24 @@ import draccus
from lerobot.robots import ( # noqa: F401
RobotConfig,
bi_rebot_b601_follower,
bi_so_follower,
koch_follower,
lekiwi,
make_robot_from_config,
omx_follower,
rebot_b601_follower,
so_follower,
)
from lerobot.teleoperators import ( # noqa: F401
TeleoperatorConfig,
bi_rebot_102_leader,
bi_so_leader,
koch_leader,
make_teleoperator_from_config,
omx_leader,
openarm_mini,
rebot_102_leader,
so_leader,
)
@@ -72,6 +72,7 @@ from lerobot.robots import ( # noqa: F401
Robot,
RobotConfig,
bi_openarm_follower,
bi_rebot_b601_follower,
bi_so_follower,
earthrover_mini_plus,
hope_jr,
@@ -80,6 +81,7 @@ from lerobot.robots import ( # noqa: F401
omx_follower,
openarm_follower,
reachy2,
rebot_b601_follower,
so_follower,
unitree_g1 as unitree_g1_robot,
)
@@ -87,6 +89,7 @@ from lerobot.teleoperators import ( # noqa: F401
Teleoperator,
TeleoperatorConfig,
bi_openarm_leader,
bi_rebot_102_leader,
bi_so_leader,
gamepad,
homunculus,
@@ -97,6 +100,7 @@ from lerobot.teleoperators import ( # noqa: F401
openarm_leader,
openarm_mini,
reachy2_teleoperator,
rebot_102_leader,
so_leader,
unitree_g1,
)
@@ -0,0 +1,20 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from .bi_rebot_102_leader import BiRebotArm102Leader
from .config_bi_rebot_102_leader import BiRebotArm102LeaderConfig
__all__ = ["BiRebotArm102Leader", "BiRebotArm102LeaderConfig"]
@@ -0,0 +1,113 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import logging
from functools import cached_property
from lerobot.types import RobotAction
from lerobot.utils.decorators import check_if_already_connected, check_if_not_connected
from ..rebot_102_leader import RebotArm102Leader, RebotArm102LeaderTeleopConfig
from ..teleoperator import Teleoperator
from .config_bi_rebot_102_leader import BiRebotArm102LeaderConfig
logger = logging.getLogger(__name__)
class BiRebotArm102Leader(Teleoperator):
"""Bimanual Seeed Studio StarArm102 / reBot Arm 102 leader.
Composes two single-arm :class:`RebotArm102Leader` instances. Action keys of
each arm are namespaced with a ``left_`` / ``right_`` prefix, so a bimanual
leader can teleoperate a bimanual reBot B601 follower.
"""
config_class = BiRebotArm102LeaderConfig
name = "bi_rebot_102_leader"
def __init__(self, config: BiRebotArm102LeaderConfig):
super().__init__(config)
self.config = config
left_arm_config = RebotArm102LeaderTeleopConfig(
id=f"{config.id}_left" if config.id else None,
calibration_dir=config.calibration_dir,
port=config.left_arm_config.port,
baudrate=config.left_arm_config.baudrate,
joint_ids=config.left_arm_config.joint_ids,
joint_directions=config.left_arm_config.joint_directions,
joint_ranges=config.left_arm_config.joint_ranges,
)
right_arm_config = RebotArm102LeaderTeleopConfig(
id=f"{config.id}_right" if config.id else None,
calibration_dir=config.calibration_dir,
port=config.right_arm_config.port,
baudrate=config.right_arm_config.baudrate,
joint_ids=config.right_arm_config.joint_ids,
joint_directions=config.right_arm_config.joint_directions,
joint_ranges=config.right_arm_config.joint_ranges,
)
self.left_arm = RebotArm102Leader(left_arm_config)
self.right_arm = RebotArm102Leader(right_arm_config)
@cached_property
def action_features(self) -> dict[str, type]:
return {
**{f"left_{k}": v for k, v in self.left_arm.action_features.items()},
**{f"right_{k}": v for k, v in self.right_arm.action_features.items()},
}
@cached_property
def feedback_features(self) -> dict[str, type]:
return {}
@property
def is_connected(self) -> bool:
return self.left_arm.is_connected and self.right_arm.is_connected
@check_if_already_connected
def connect(self, calibrate: bool = True) -> None:
self.left_arm.connect(calibrate)
self.right_arm.connect(calibrate)
@property
def is_calibrated(self) -> bool:
return self.left_arm.is_calibrated and self.right_arm.is_calibrated
def calibrate(self) -> None:
self.left_arm.calibrate()
self.right_arm.calibrate()
def configure(self) -> None:
self.left_arm.configure()
self.right_arm.configure()
@check_if_not_connected
def get_action(self) -> RobotAction:
action_dict = {}
action_dict.update({f"left_{k}": v for k, v in self.left_arm.get_action().items()})
action_dict.update({f"right_{k}": v for k, v in self.right_arm.get_action().items()})
return action_dict
def send_feedback(self, feedback: dict[str, float]) -> None:
raise NotImplementedError("Feedback is not implemented for the reBot Arm 102 leader.")
@check_if_not_connected
def disconnect(self) -> None:
self.left_arm.disconnect()
self.right_arm.disconnect()
@@ -0,0 +1,29 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from dataclasses import dataclass
from ..config import TeleoperatorConfig
from ..rebot_102_leader import RebotArm102LeaderConfig
@TeleoperatorConfig.register_subclass("bi_rebot_102_leader")
@dataclass
class BiRebotArm102LeaderConfig(TeleoperatorConfig):
"""Configuration class for the bimanual reBot Arm 102 leader teleoperator."""
left_arm_config: RebotArm102LeaderConfig
right_arm_config: RebotArm102LeaderConfig
@@ -0,0 +1,20 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from .config_rebot_102_leader import RebotArm102LeaderConfig, RebotArm102LeaderTeleopConfig
from .rebot_102_leader import RebotArm102Leader
__all__ = ["RebotArm102Leader", "RebotArm102LeaderConfig", "RebotArm102LeaderTeleopConfig"]
@@ -0,0 +1,83 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from dataclasses import dataclass, field
from ..config import TeleoperatorConfig
@dataclass
class RebotArm102LeaderConfig:
"""Base configuration class for the Seeed Studio StarArm102 / reBot Arm 102 leader.
The reBot Arm 102 is a 7-joint (incl. gripper) leader arm driven by FashionStar
UART smart servos. Servo communication goes through ``motorbridge-smart-servo``.
"""
# USB-to-UART device the leader arm is connected to (e.g. "/dev/ttyUSB0").
port: str
baudrate: int = 1_000_000
# Servo id of each joint on the UART bus.
joint_ids: dict[str, int] = field(
default_factory=lambda: {
"shoulder_pan": 0,
"shoulder_lift": 1,
"elbow_flex": 2,
"wrist_flex": 3,
"wrist_yaw": 4,
"wrist_roll": 5,
"gripper": 6,
}
)
# Per-joint sign applied to raw servo angles so the leader matches the follower
# convention. The gripper additionally carries a scale (e.g. -6) to widen its
# range to the reBot B601 follower's gripper travel.
joint_directions: dict[str, int] = field(
default_factory=lambda: {
"shoulder_pan": -1,
"shoulder_lift": -1,
"elbow_flex": 1,
"wrist_flex": 1,
"wrist_yaw": 1,
"wrist_roll": -1,
"gripper": -6,
}
)
# Per-joint [min, max] output range in degrees. Matches the reBot B601 follower
# joint limits so leader actions can drive the follower key-for-key.
joint_ranges: dict[str, list[int]] = field(
default_factory=lambda: {
"shoulder_pan": [-150, 150],
"shoulder_lift": [-170, 1],
"elbow_flex": [-200, 1],
"wrist_flex": [-80, 90],
"wrist_yaw": [-90, 90],
"wrist_roll": [-90, 90],
"gripper": [-270, 0],
}
)
@TeleoperatorConfig.register_subclass("rebot_102_leader")
@dataclass
class RebotArm102LeaderTeleopConfig(TeleoperatorConfig, RebotArm102LeaderConfig):
"""Registered configuration for the reBot Arm 102 leader teleoperator."""
pass
@@ -0,0 +1,235 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import logging
import time
from typing import TYPE_CHECKING
from lerobot.motors import MotorCalibration
from lerobot.types import RobotAction
from lerobot.utils.decorators import check_if_already_connected, check_if_not_connected
from lerobot.utils.import_utils import _motorbridge_smart_servo_available, require_package
from ..teleoperator import Teleoperator
from .config_rebot_102_leader import RebotArm102LeaderTeleopConfig
if TYPE_CHECKING or _motorbridge_smart_servo_available:
from motorbridge_smart_servo import FashionStarServo, ServoMonitor
else:
FashionStarServo = None
ServoMonitor = None
logger = logging.getLogger(__name__)
_SETTLE_SEC = 0.01
class RebotArm102Leader(Teleoperator):
"""Seeed Studio StarArm102 / reBot Arm 102 leader arm.
A 7-joint (incl. gripper) leader built on FashionStar UART smart servos. Servo
communication is handled by the ``motorbridge-smart-servo`` package; this class
only reads joint angles, so it produces actions but accepts no feedback.
"""
config_class = RebotArm102LeaderTeleopConfig
name = "rebot_102_leader"
def __init__(self, config: RebotArm102LeaderTeleopConfig):
require_package("motorbridge-smart-servo", extra="rebot", import_name="motorbridge_smart_servo")
super().__init__(config)
self.config = config
self.bus: FashionStarServo | None = None
self.motor_names = list(config.joint_ids.keys())
self._last_raw_positions: dict[str, float] = {}
self._validate_config()
def _validate_config(self) -> None:
required_keys = set(self.config.joint_ids)
for field_name in ("joint_directions", "joint_ranges"):
keys = set(getattr(self.config, field_name))
if keys != required_keys:
raise ValueError(
f"{field_name} keys must match joint_ids keys. "
f"Expected {sorted(required_keys)}, got {sorted(keys)}."
)
for motor_name, joint_range in self.config.joint_ranges.items():
if len(joint_range) != 2:
raise ValueError(f"joint_ranges[{motor_name!r}] must contain exactly [min, max].")
if joint_range[0] > joint_range[1]:
raise ValueError(f"joint_ranges[{motor_name!r}] must satisfy min <= max.")
@property
def action_features(self) -> dict[str, type]:
return {f"{motor}.pos": float for motor in self.motor_names}
@property
def feedback_features(self) -> dict[str, type]:
return {}
@property
def is_connected(self) -> bool:
return self.bus is not None
@check_if_already_connected
def connect(self, calibrate: bool = True) -> None:
logger.info(f"Connecting {self} on {self.config.port}...")
bus = FashionStarServo(self.config.port, baudrate=self.config.baudrate)
try:
for motor_name, motor_id in self.config.joint_ids.items():
if not bus.ping(motor_id):
raise RuntimeError(f"Servo not found for {motor_name} (id={motor_id}).")
self._last_raw_positions[motor_name] = 0.0
self.bus = bus
if not self.is_calibrated and calibrate:
logger.info(
"Mismatch between calibration values in the motor and the calibration file or no calibration file found"
)
self.calibrate()
self.configure()
except Exception:
bus.close()
self.bus = None
raise
logger.info(f"{self} connected.")
@property
def is_calibrated(self) -> bool:
return bool(self.calibration) and set(self.calibration) == set(self.motor_names)
def calibrate(self) -> None:
if self.calibration:
user_input = input(
f"Press ENTER to use provided calibration file associated with the id {self.id}, "
"or type 'c' and press ENTER to run calibration: "
)
if user_input.strip().lower() != "c":
logger.info(f"Using calibration file associated with the id {self.id}")
return
logger.info(f"\nRunning calibration of {self}")
input(
"\nCalibration: set zero position.\n"
"Manually move the reBot Arm 102 to its zero pose and close the gripper.\n"
"Press ENTER when ready..."
)
self.calibration = {}
for motor_name, motor_id in self.config.joint_ids.items():
self.bus.unlock(motor_id)
time.sleep(_SETTLE_SEC)
self.bus.set_origin_point(motor_id)
self.calibration[motor_name] = MotorCalibration(
id=motor_id,
drive_mode=0,
homing_offset=0,
range_min=-90,
range_max=90,
)
self._save_calibration()
logger.info(f"Calibration saved to {self.calibration_fpath}")
def configure(self) -> None:
for motor_id in self.config.joint_ids.values():
self.bus.unlock(motor_id)
time.sleep(_SETTLE_SEC)
# Reset the multi-turn counter of each servo individually.
for motor_id in self.config.joint_ids.values():
self.bus.reset_multi_turn(motor_id)
def _read_raw_positions(self) -> dict[str, float]:
result: dict[int, ServoMonitor | None] = self.bus.sync_monitor(list(self.config.joint_ids.values()))
id_to_name = {v: k for k, v in self.config.joint_ids.items()}
raw_positions: dict[str, float] = {}
for motor_id, monitor in result.items():
motor_name = id_to_name[motor_id]
if monitor is None:
raise RuntimeError(f"Servo {motor_name} (id={motor_id}) has never responded.")
raw_positions[motor_name] = monitor.angle_deg
return raw_positions
@staticmethod
def _clamp(value: float, min_value: float, max_value: float) -> float:
return max(min_value, min(max_value, value))
@staticmethod
def _round_to_valid_range(value: float, min_value: float, max_value: float) -> tuple[float, int]:
"""Unwrap a multi-turn angle into the ±180° window centred on (min+max)/2.
The servo may report an angle that has accumulated extra full rotations
(value = true_angle + N*360). The sign of N is unknown, so a bidirectional
search tries value±k*360 for increasing k until a candidate lands inside
[center-180, center+180].
"""
center = (min_value + max_value) / 2.0
low = center - 180.0
high = center + 180.0
for k in range(4096):
candidate_plus = value + k * 360.0
if low <= candidate_plus <= high:
return candidate_plus, k
candidate_minus = value - k * 360.0
if low <= candidate_minus <= high:
return candidate_minus, k
# Fallback: direct modular arithmetic (should never be reached).
return value - round((value - center) / 360.0) * 360.0, 4096
@check_if_not_connected
def get_action(self) -> RobotAction:
start = time.perf_counter()
try:
raw_positions = self._read_raw_positions()
self._last_raw_positions = raw_positions
except Exception as e:
logger.error(f"Failed to read raw positions: {e}")
logger.warning("[EMERGENCY STOP] Hold the follower arm and cut off the main power to the arms.")
logger.warning(
"[EMERGENCY STOP] Break the teleoperation session and check the leader USB connection or power."
)
raw_positions = self._last_raw_positions
action_dict: dict[str, float] = {}
for motor_name in self.motor_names:
range_min, range_max = self.config.joint_ranges[motor_name]
direction = self.config.joint_directions[motor_name]
sign = 1.0 if direction >= 0 else -1.0
unwrapped, k = self._round_to_valid_range(
raw_positions[motor_name], range_min * sign, range_max * sign
)
position = unwrapped * direction
if k > 0:
logger.debug(
f"Servo {motor_name} (id={self.config.joint_ids[motor_name]}) wrapped {k} * 360°. "
f"Unwrapped pos: {unwrapped:.1f}° (raw: {raw_positions[motor_name]:.1f}°)"
)
action_dict[f"{motor_name}.pos"] = self._clamp(position, float(range_min), float(range_max))
dt_ms = (time.perf_counter() - start) * 1e3
logger.debug(f"{self} read action: {dt_ms:.1f}ms")
return action_dict
def send_feedback(self, feedback: dict[str, float]) -> None:
raise NotImplementedError("Feedback is not implemented for the reBot Arm 102 leader.")
@check_if_not_connected
def disconnect(self) -> None:
self.bus.close()
self.bus = None
logger.info(f"{self} disconnected.")
+8
View File
@@ -99,6 +99,14 @@ def make_teleoperator_from_config(config: TeleoperatorConfig) -> "Teleoperator":
from .openarm_mini import OpenArmMini
return OpenArmMini(config)
elif config.type == "rebot_102_leader":
from .rebot_102_leader import RebotArm102Leader
return RebotArm102Leader(config)
elif config.type == "bi_rebot_102_leader":
from .bi_rebot_102_leader import BiRebotArm102Leader
return BiRebotArm102Leader(config)
else:
try:
return cast("Teleoperator", make_device_from_device_class(config))
+4
View File
@@ -114,6 +114,10 @@ _dynamixel_sdk_available = is_package_available("dynamixel-sdk", import_name="dy
_feetech_sdk_available = is_package_available("feetech-servo-sdk", import_name="scservo_sdk")
_reachy2_sdk_available = is_package_available("reachy2_sdk")
_can_available = is_package_available("python-can", "can")
_motorbridge_available = is_package_available("motorbridge")
_motorbridge_smart_servo_available = is_package_available(
"motorbridge-smart-servo", import_name="motorbridge_smart_servo"
)
_unitree_sdk_available = is_package_available("unitree-sdk2py", "unitree_sdk2py")
_pyrealsense2_available = is_package_available("pyrealsense2") or is_package_available(
"pyrealsense2-macosx", import_name="pyrealsense2"
+116
View File
@@ -0,0 +1,116 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
import math
from unittest.mock import MagicMock, patch
import pytest
from lerobot.robots.bi_rebot_b601_follower import BiRebotB601Follower, BiRebotB601FollowerConfig
from lerobot.robots.rebot_b601_follower import (
RebotB601Follower,
RebotB601FollowerConfig,
RebotB601FollowerRobotConfig,
)
_MODULE = "lerobot.robots.rebot_b601_follower.rebot_b601_follower"
def _make_motor_mock(position_rad: float = 0.0) -> MagicMock:
motor = MagicMock(name="MotorMock")
state = MagicMock()
state.pos = position_rad
motor.get_state.return_value = state
return motor
def _make_bus_mock() -> MagicMock:
bus = MagicMock(name="MotorBridgeControllerMock")
# add_damiao_motor returns a fresh motor mock; position encodes the call order.
bus._motor_count = 0
def _add_motor(_send_id, _recv_id, _model):
bus._motor_count += 1
return _make_motor_mock(position_rad=math.radians(bus._motor_count))
bus.add_damiao_motor.side_effect = _add_motor
return bus
@pytest.fixture
def follower():
bus_mock = _make_bus_mock()
with (
patch(f"{_MODULE}.require_package", lambda *a, **kw: None),
patch(f"{_MODULE}.MotorBridgeController") as controller_cls,
patch(f"{_MODULE}.MotorBridgeMode", MagicMock()),
):
controller_cls.from_dm_serial.return_value = bus_mock
cfg = RebotB601FollowerRobotConfig(port="/dev/null")
robot = RebotB601Follower(cfg)
robot.connect(calibrate=False)
yield robot
if robot.is_connected:
robot.disconnect()
def test_features_match_joints():
with patch(f"{_MODULE}.require_package", lambda *a, **kw: None):
robot = RebotB601Follower(RebotB601FollowerRobotConfig(port="/dev/null"))
expected = {f"{m}.pos" for m in robot.motor_names}
assert set(robot.action_features) == expected
assert set(robot.observation_features) == expected
assert "gripper.pos" in expected
def test_connect_disconnect(follower):
assert follower.is_connected
follower.disconnect()
assert not follower.is_connected
def test_get_observation_converts_to_degrees(follower):
obs = follower.get_observation()
assert set(obs) == {f"{m}.pos" for m in follower.motor_names}
# The bus mock seeds each motor's position with its 1-indexed creation order (radians).
for idx, motor in enumerate(follower.motor_names, 1):
assert obs[f"{motor}.pos"] == pytest.approx(math.degrees(math.radians(idx)))
def test_send_action_clips_to_joint_limits(follower):
# shoulder_pan limit is (-145, 145); request beyond the upper bound.
returned = follower.send_action({"shoulder_pan.pos": 999.0})
assert returned["shoulder_pan.pos"] == 145.0
follower.motors["shoulder_pan"].send_pos_vel.assert_called_once()
def test_send_action_routes_gripper_to_force_pos(follower):
follower.send_action({"gripper.pos": -10.0})
follower.motors["gripper"].send_force_pos.assert_called_once()
follower.motors["gripper"].send_pos_vel.assert_not_called()
def test_bimanual_prefixes_features():
with patch(f"{_MODULE}.require_package", lambda *a, **kw: None):
cfg = BiRebotB601FollowerConfig(
left_arm_config=RebotB601FollowerConfig(port="/dev/null0"),
right_arm_config=RebotB601FollowerConfig(port="/dev/null1"),
)
robot = BiRebotB601Follower(cfg)
assert any(k.startswith("left_") for k in robot.action_features)
assert any(k.startswith("right_") for k in robot.action_features)
assert "left_gripper.pos" in robot.action_features
assert "right_gripper.pos" in robot.action_features
@@ -0,0 +1,109 @@
#!/usr/bin/env python
# Copyright 2026 The HuggingFace Inc. team. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
from unittest.mock import MagicMock, patch
import pytest
from lerobot.teleoperators.bi_rebot_102_leader import BiRebotArm102Leader, BiRebotArm102LeaderConfig
from lerobot.teleoperators.rebot_102_leader import (
RebotArm102Leader,
RebotArm102LeaderConfig,
RebotArm102LeaderTeleopConfig,
)
_MODULE = "lerobot.teleoperators.rebot_102_leader.rebot_102_leader"
def _make_bus_mock(joint_ids: dict[str, int]) -> MagicMock:
bus = MagicMock(name="FashionStarServoMock")
bus.ping.return_value = True
def _sync_monitor(ids):
# Report each servo at 5 degrees raw.
monitors = {}
for servo_id in ids:
monitor = MagicMock()
monitor.angle_deg = 5.0
monitors[servo_id] = monitor
return monitors
bus.sync_monitor.side_effect = _sync_monitor
return bus
@pytest.fixture
def leader():
cfg = RebotArm102LeaderTeleopConfig(port="/dev/null")
bus_mock = _make_bus_mock(cfg.joint_ids)
with (
patch(f"{_MODULE}.require_package", lambda *a, **kw: None),
patch(f"{_MODULE}.FashionStarServo", return_value=bus_mock),
):
teleop = RebotArm102Leader(cfg)
teleop.connect(calibrate=False)
yield teleop
if teleop.is_connected:
teleop.disconnect()
def test_action_features_match_joints():
with patch(f"{_MODULE}.require_package", lambda *a, **kw: None):
teleop = RebotArm102Leader(RebotArm102LeaderTeleopConfig(port="/dev/null"))
assert set(teleop.action_features) == {f"{m}.pos" for m in teleop.motor_names}
assert teleop.feedback_features == {}
def test_invalid_config_rejected():
with patch(f"{_MODULE}.require_package", lambda *a, **kw: None):
bad = RebotArm102LeaderTeleopConfig(port="/dev/null", joint_directions={"shoulder_pan": 1})
with pytest.raises(ValueError, match="joint_directions"):
RebotArm102Leader(bad)
def test_connect_disconnect(leader):
assert leader.is_connected
leader.disconnect()
assert not leader.is_connected
def test_get_action_applies_direction_and_clamp(leader):
action = leader.get_action()
assert set(action) == {f"{m}.pos" for m in leader.motor_names}
# shoulder_pan has direction -1, so a +5deg raw reading flips to -5deg.
assert action["shoulder_pan.pos"] == pytest.approx(-5.0)
# Every joint stays within its configured range.
for motor, value in action.items():
lo, hi = leader.config.joint_ranges[motor.removesuffix(".pos")]
assert lo <= value <= hi
def test_send_feedback_not_implemented(leader):
with pytest.raises(NotImplementedError):
leader.send_feedback({})
def test_bimanual_prefixes_features():
with patch(f"{_MODULE}.require_package", lambda *a, **kw: None):
cfg = BiRebotArm102LeaderConfig(
left_arm_config=RebotArm102LeaderConfig(port="/dev/null0"),
right_arm_config=RebotArm102LeaderConfig(port="/dev/null1"),
)
teleop = BiRebotArm102Leader(cfg)
assert any(k.startswith("left_") for k in teleop.action_features)
assert any(k.startswith("right_") for k in teleop.action_features)
assert "left_gripper.pos" in teleop.action_features
assert "right_gripper.pos" in teleop.action_features
Generated
+49 -3
View File
@@ -1,5 +1,5 @@
version = 1
revision = 2
revision = 3
requires-python = ">=3.12"
resolution-markers = [
"(python_full_version >= '3.15' and platform_machine == 'AMD64' and sys_platform == 'linux') or (python_full_version >= '3.15' and platform_machine == 'x86_64' and sys_platform == 'linux')",
@@ -1142,7 +1142,7 @@ name = "decord"
version = "0.6.0"
source = { registry = "https://pypi.org/simple" }
dependencies = [
{ name = "numpy", marker = "(platform_machine != 'arm64' and sys_platform == 'darwin') or (platform_machine == 'AMD64' and sys_platform == 'linux') or (platform_machine == 'x86_64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" },
{ name = "numpy", marker = "(platform_machine != 'arm64' and platform_machine != 's390x' and sys_platform == 'darwin') or (platform_machine == 'AMD64' and sys_platform == 'linux') or (platform_machine == 'x86_64' and sys_platform == 'linux') or (platform_machine != 's390x' and sys_platform != 'darwin' and sys_platform != 'linux')" },
]
wheels = [
{ url = "https://files.pythonhosted.org/packages/11/79/936af42edf90a7bd4e41a6cac89c913d4b47fa48a26b042d5129a9242ee3/decord-0.6.0-py3-none-manylinux2010_x86_64.whl", hash = "sha256:51997f20be8958e23b7c4061ba45d0efcd86bffd5fe81c695d0befee0d442976", size = 13602299, upload-time = "2021-06-14T21:30:55.486Z" },
@@ -2710,6 +2710,8 @@ all = [
{ name = "matplotlib" },
{ name = "metaworld" },
{ name = "mock-serial", marker = "sys_platform != 'win32'" },
{ name = "motorbridge" },
{ name = "motorbridge-smart-servo" },
{ name = "mypy" },
{ name = "num2words" },
{ name = "pandas" },
@@ -2913,6 +2915,12 @@ metaworld = [
{ name = "scipy" },
{ name = "torchcodec", marker = "(platform_machine == 'arm64' and sys_platform == 'darwin') or (platform_machine == 'AMD64' and sys_platform == 'linux') or (platform_machine == 'aarch64' and sys_platform == 'linux') or (platform_machine == 'arm64' and sys_platform == 'linux') or (platform_machine == 'x86_64' and sys_platform == 'linux') or sys_platform == 'win32'" },
]
motorbridge-dep = [
{ name = "motorbridge" },
]
motorbridge-smart-servo-dep = [
{ name = "motorbridge-smart-servo" },
]
multi-task-dit = [
{ name = "diffusers" },
{ name = "transformers" },
@@ -2972,6 +2980,10 @@ qwen-vl-utils-dep = [
reachy2 = [
{ name = "reachy2-sdk" },
]
rebot = [
{ name = "motorbridge" },
{ name = "motorbridge-smart-servo" },
]
robstride = [
{ name = "python-can" },
]
@@ -3116,6 +3128,8 @@ requires-dist = [
{ name = "lerobot", extras = ["matplotlib-dep"], marker = "extra == 'sarm'" },
{ name = "lerobot", extras = ["matplotlib-dep"], marker = "extra == 'unitree-g1'" },
{ name = "lerobot", extras = ["metaworld"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["motorbridge-dep"], marker = "extra == 'rebot'" },
{ name = "lerobot", extras = ["motorbridge-smart-servo-dep"], marker = "extra == 'rebot'" },
{ name = "lerobot", extras = ["multi-task-dit"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["notebook"], marker = "extra == 'dev'" },
{ name = "lerobot", extras = ["openarms"], marker = "extra == 'all'" },
@@ -3142,6 +3156,7 @@ requires-dist = [
{ name = "lerobot", extras = ["qwen-vl-utils-dep"], marker = "extra == 'sarm'" },
{ name = "lerobot", extras = ["qwen-vl-utils-dep"], marker = "extra == 'wallx'" },
{ name = "lerobot", extras = ["reachy2"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["rebot"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["robstride"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["sarm"], marker = "extra == 'all'" },
{ name = "lerobot", extras = ["scipy-dep"], marker = "extra == 'aloha'" },
@@ -3174,6 +3189,8 @@ requires-dist = [
{ name = "meshcat", marker = "extra == 'unitree-g1'", specifier = ">=0.3.0,<0.4.0" },
{ name = "metaworld", marker = "extra == 'metaworld'", specifier = "==3.0.0" },
{ name = "mock-serial", marker = "sys_platform != 'win32' and extra == 'test'", specifier = ">=0.0.1,<0.1.0" },
{ name = "motorbridge", marker = "extra == 'motorbridge-dep'", specifier = ">=0.3.2,<0.4.0" },
{ name = "motorbridge-smart-servo", marker = "extra == 'motorbridge-smart-servo-dep'", specifier = ">=0.0.4,<0.1.0" },
{ name = "mypy", marker = "extra == 'dev'", specifier = ">=1.19.1" },
{ name = "ninja", marker = "extra == 'groot'", specifier = ">=1.11.1,<2.0.0" },
{ name = "num2words", marker = "extra == 'smolvla'", specifier = ">=0.5.14,<0.6.0" },
@@ -3227,7 +3244,7 @@ requires-dist = [
{ name = "transformers", marker = "extra == 'transformers-dep'", specifier = ">=5.4.0,<5.6.0" },
{ name = "wandb", marker = "extra == 'training'", specifier = ">=0.24.0,<0.25.0" },
]
provides-extras = ["dataset", "training", "hardware", "viz", "core-scripts", "evaluation", "dataset-viz", "av-dep", "pygame-dep", "placo-dep", "transformers-dep", "grpcio-dep", "can-dep", "peft-dep", "scipy-dep", "diffusers-dep", "qwen-vl-utils-dep", "matplotlib-dep", "pyserial-dep", "deepdiff-dep", "pynput-dep", "pyzmq-dep", "feetech", "dynamixel", "damiao", "robstride", "openarms", "gamepad", "hopejr", "lekiwi", "unitree-g1", "reachy2", "kinematics", "intelrealsense", "phone", "diffusion", "wallx", "pi", "smolvla", "multi-task-dit", "groot", "sarm", "xvla", "eo1", "hilserl", "async", "peft", "dev", "notebook", "test", "video-benchmark", "aloha", "pusht", "libero", "metaworld", "all"]
provides-extras = ["dataset", "training", "hardware", "viz", "core-scripts", "evaluation", "dataset-viz", "av-dep", "pygame-dep", "placo-dep", "transformers-dep", "grpcio-dep", "can-dep", "peft-dep", "scipy-dep", "diffusers-dep", "qwen-vl-utils-dep", "matplotlib-dep", "pyserial-dep", "deepdiff-dep", "pynput-dep", "pyzmq-dep", "motorbridge-dep", "motorbridge-smart-servo-dep", "feetech", "dynamixel", "damiao", "robstride", "openarms", "gamepad", "hopejr", "lekiwi", "unitree-g1", "reachy2", "rebot", "kinematics", "intelrealsense", "phone", "diffusion", "wallx", "pi", "smolvla", "multi-task-dit", "groot", "sarm", "xvla", "eo1", "hilserl", "async", "peft", "dev", "notebook", "test", "video-benchmark", "aloha", "pusht", "libero", "metaworld", "all"]
[[package]]
name = "librt"
@@ -3653,6 +3670,35 @@ wheels = [
{ url = "https://files.pythonhosted.org/packages/98/c2/8c1e6bf77cf62a10203a107179e34e0965fc5369386e0b7034a247ed054d/mock_serial-0.0.1-py3-none-any.whl", hash = "sha256:b6b8cc10c302354bf3ca270a3d4d6bf199c4bbe41478c65046db8f30ea967675", size = 6080, upload-time = "2021-11-23T09:34:51.108Z" },
]
[[package]]
name = "motorbridge"
version = "0.3.2"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/58/f2/b824ac4d611c71020dccdb72fc50606e543c77c68455ea824b26d9a6de03/motorbridge-0.3.2.tar.gz", hash = "sha256:5cf85dd22c46c7f3c5e6981e90b1034af2deb1bc4e7d74c13074d1d4a7b75ceb", size = 30158, upload-time = "2026-05-18T07:13:17.239Z" }
wheels = [
{ url = "https://files.pythonhosted.org/packages/2c/1a/7d367039a8325c0e2796c14a1503dfc563e7b244c815b26e079114244b4b/motorbridge-0.3.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8ad158928e93fafd2a7814eaffe8e6ecbec4686f64c2df85f80d7979dfc82532", size = 1108065, upload-time = "2026-05-18T07:13:04.669Z" },
{ url = "https://files.pythonhosted.org/packages/fe/d6/fafa2b8a3635a6fe7f6e8129e140a68d30f4d6438350a86e51b8198b7834/motorbridge-0.3.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2adde5f26ea4e37d05da6b41b03b637efa6c80db4676bc6dbdb91ac6e811e54a", size = 1184657, upload-time = "2026-05-18T07:13:06.081Z" },
{ url = "https://files.pythonhosted.org/packages/d8/30/aca01e81ec523d37b98a1ce6e41688d31827625eb15ecf0cf0485d91d62c/motorbridge-0.3.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a03b6dc0be80db7b47d3f190f8c6f4fc43b0b4089235283f53763153a6d4e58c", size = 1201394, upload-time = "2026-05-18T07:13:07.476Z" },
{ url = "https://files.pythonhosted.org/packages/70/eb/97b2f93682a1ce67bad50e9b598af889be4a3156ebcec129ebb41fa44e5b/motorbridge-0.3.2-cp312-cp312-win_amd64.whl", hash = "sha256:b0657d47aa94f8535d0663538be4a86c46e314303fba513122d17612b584c6e6", size = 839087, upload-time = "2026-05-18T07:13:08.664Z" },
{ url = "https://files.pythonhosted.org/packages/6e/b0/03246c25ae67c2b33bd19b5d11bae668bb8baa7d9cbd75b035a8bef61d62/motorbridge-0.3.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:f305a69c7c3c91dca19c43084beb4cd30a93fd85ff35c712cc3fb0ae33a5c7d3", size = 1108065, upload-time = "2026-05-18T07:13:10.032Z" },
{ url = "https://files.pythonhosted.org/packages/a9/40/b82d86fbfcc6b18946567f15a7d76d1c673d43bc0c8d268b668506811981/motorbridge-0.3.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:778fdde2b12df20184fb8c8f4c7665919d969bd582589a267c7956d4c57336ad", size = 1184657, upload-time = "2026-05-18T07:13:11.812Z" },
{ url = "https://files.pythonhosted.org/packages/f2/3e/90e41d798814db89605d9a021e0c182608aec3d40eef2be211427e2bb863/motorbridge-0.3.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eac3a2d27ca387e8d537ec148bea0c28b9517ff4fb9ea0b12f6e78c1e9a7faa4", size = 1201393, upload-time = "2026-05-18T07:13:13.396Z" },
{ url = "https://files.pythonhosted.org/packages/34/75/3c9ba7514fd0ec330c1fe0b4d76dedfd221abc1b750fe063b6e3f9a88075/motorbridge-0.3.2-cp313-cp313-win_amd64.whl", hash = "sha256:d7d1eb76ae29e8673a320fd1a86b944fb0869129fd4114f0983e43cd48f67372", size = 839087, upload-time = "2026-05-18T07:13:14.555Z" },
{ url = "https://files.pythonhosted.org/packages/87/33/6787dd22914291a640c2821f175abc7cbb9a1e0fe6c1143f92d7ac362903/motorbridge-0.3.2-cp314-cp314-win_amd64.whl", hash = "sha256:c5f05e36c6607d2145f38fb6f1f11090bb01dbd1012e8251b0d2ae4d60fa4f50", size = 870167, upload-time = "2026-05-18T07:13:15.898Z" },
]
[[package]]
name = "motorbridge-smart-servo"
version = "0.0.4"
source = { registry = "https://pypi.org/simple" }
sdist = { url = "https://files.pythonhosted.org/packages/e6/56/45af87189dc49abbe46157b792b7c71f502a5f819f04e7485de0cfa52d9b/motorbridge_smart_servo-0.0.4.tar.gz", hash = "sha256:fb65f3f6e765e6b1915071c255caaf112fad3796fa1761aeee0132d15b8a0989", size = 20415, upload-time = "2026-05-08T09:24:57.563Z" }
wheels = [
{ url = "https://files.pythonhosted.org/packages/e9/ee/bec4b3acf55cd18e7db83a6d951caccf699533dbd038c1f0b5f2d16d5208/motorbridge_smart_servo-0.0.4-cp39-abi3-macosx_11_0_arm64.whl", hash = "sha256:8bc1f034fa9f96e23229a834db6e7cfe1368dba7b9a2a6f6dbd316448c4390dc", size = 304384, upload-time = "2026-05-08T09:24:52.619Z" },
{ url = "https://files.pythonhosted.org/packages/3f/d2/71c87063b826433553ce8869b99df3e4f191b107710dd5c905e637512b10/motorbridge_smart_servo-0.0.4-cp39-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:348cef6a647e5c7f9cc8e8ce1f3c806af4522e1087172bac2f8a1a0daa3592b6", size = 345668, upload-time = "2026-05-08T09:24:53.735Z" },
{ url = "https://files.pythonhosted.org/packages/9b/6b/e65e7227a510236c6334cf054c501d3de2cbd463f4c594e42c6e965d5143/motorbridge_smart_servo-0.0.4-cp39-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8c1982643c496c9f425fa9238f9a92ba601d77f4f2279df68c6868e7b997cbe1", size = 348123, upload-time = "2026-05-08T09:24:55.191Z" },
{ url = "https://files.pythonhosted.org/packages/2d/fa/539ea123a5660c22c5e5cdad62d7bc5e931c816a0ffd402ae6e4623ab45b/motorbridge_smart_servo-0.0.4-cp39-abi3-win_amd64.whl", hash = "sha256:ea3baa9ba25bcec5541f3d86d73a3406ba2fcffe5dbf900c22e058638fc31ab0", size = 194130, upload-time = "2026-05-08T09:24:56.369Z" },
]
[[package]]
name = "mpmath"
version = "1.3.0"