mirror of
https://github.com/huggingface/lerobot.git
synced 2026-05-17 17:50:09 +00:00
feat(robot): Add support for OMX robot (#2614)
* upload * feat(omx): simplify motor initialization and remove default calibration files * feat(omx): read motor positions without normalization for improved accuracy * update calibration method for return factory value Signed-off-by: Junha Cha <ckwnsgk1@gachon.ac.kr> * change the drive mode * refactor: clean up code by removing unnecessary blank lines in omx_follower and omx_leader modules * feat(omx): update calibration method to set drive modes for motors * feat(pyproject): add 'ROBOTIS' to extend-ignore-identifiers-re list * feat(omx): enhance calibration method to write default drive modes to motors * Update src/lerobot/robots/omx_follower/__init__.py Add informations about the robot Co-authored-by: Steven Palma <imstevenpmwork@ieee.org> Signed-off-by: Woojin Wie <dnldnwls1123@gmail.com> --------- Signed-off-by: Junha Cha <ckwnsgk1@gachon.ac.kr> Signed-off-by: Woojin Wie <dnldnwls1123@gmail.com> Co-authored-by: Junha02 <chajunha2023@naver.com> Co-authored-by: Junha Cha <ckwnsgk1@gachon.ac.kr> Co-authored-by: Steven Palma <imstevenpmwork@ieee.org>
This commit is contained in:
@@ -263,6 +263,7 @@ default.extend-ignore-identifiers-re = [
|
|||||||
"ein",
|
"ein",
|
||||||
"thw",
|
"thw",
|
||||||
"inpt",
|
"inpt",
|
||||||
|
"ROBOTIS",
|
||||||
]
|
]
|
||||||
|
|
||||||
# TODO: Uncomment when ready to use
|
# TODO: Uncomment when ready to use
|
||||||
|
|||||||
@@ -26,4 +26,4 @@ DEFAULT_OBS_QUEUE_TIMEOUT = 2
|
|||||||
SUPPORTED_POLICIES = ["act", "smolvla", "diffusion", "tdmpc", "vqbet", "pi0", "pi05"]
|
SUPPORTED_POLICIES = ["act", "smolvla", "diffusion", "tdmpc", "vqbet", "pi0", "pi05"]
|
||||||
|
|
||||||
# TODO: Add all other robots
|
# TODO: Add all other robots
|
||||||
SUPPORTED_ROBOTS = ["so100_follower", "so101_follower", "bi_so100_follower"]
|
SUPPORTED_ROBOTS = ["so100_follower", "so101_follower", "bi_so100_follower", "omx_follower"]
|
||||||
|
|||||||
@@ -54,6 +54,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
bi_so100_follower,
|
bi_so100_follower,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -0,0 +1,21 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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.
|
||||||
|
|
||||||
|
# OMX is a fully open-source robot from ROBOTIS.
|
||||||
|
# More information at: https://ai.robotis.com/omx/introduction_omx.html
|
||||||
|
|
||||||
|
from .config_omx_follower import OmxFollowerConfig
|
||||||
|
from .omx_follower import OmxFollower
|
||||||
@@ -0,0 +1,39 @@
|
|||||||
|
# Copyright 2024 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
|
||||||
|
|
||||||
|
|
||||||
|
@RobotConfig.register_subclass("omx_follower")
|
||||||
|
@dataclass
|
||||||
|
class OmxFollowerConfig(RobotConfig):
|
||||||
|
# Port to connect to the arm
|
||||||
|
port: str
|
||||||
|
|
||||||
|
disable_torque_on_disconnect: bool = True
|
||||||
|
|
||||||
|
# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes.
|
||||||
|
# Set this to a positive scalar to have the same value for all motors, or a dictionary that maps motor
|
||||||
|
# names to the max_relative_target value for that motor.
|
||||||
|
max_relative_target: float | dict[str, float] | None = None
|
||||||
|
|
||||||
|
# cameras
|
||||||
|
cameras: dict[str, CameraConfig] = field(default_factory=dict)
|
||||||
|
|
||||||
|
# Set to `True` for backward compatibility with previous policies/dataset
|
||||||
|
use_degrees: bool = False
|
||||||
@@ -0,0 +1,225 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2024 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 functools import cached_property
|
||||||
|
from typing import Any
|
||||||
|
|
||||||
|
from lerobot.cameras.utils import make_cameras_from_configs
|
||||||
|
from lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
||||||
|
from lerobot.motors.dynamixel import (
|
||||||
|
DriveMode,
|
||||||
|
DynamixelMotorsBus,
|
||||||
|
OperatingMode,
|
||||||
|
)
|
||||||
|
from lerobot.utils.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
||||||
|
|
||||||
|
from ..robot import Robot
|
||||||
|
from ..utils import ensure_safe_goal_position
|
||||||
|
from .config_omx_follower import OmxFollowerConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
class OmxFollower(Robot):
|
||||||
|
"""
|
||||||
|
- [OMX](https://github.com/ROBOTIS-GIT/open_manipulator),
|
||||||
|
expansion, developed by Woojin Wie and Junha Cha from [ROBOTIS](https://ai.robotis.com/)
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = OmxFollowerConfig
|
||||||
|
name = "omx_follower"
|
||||||
|
|
||||||
|
def __init__(self, config: OmxFollowerConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
self.config = config
|
||||||
|
norm_mode_body = MotorNormMode.DEGREES if config.use_degrees else MotorNormMode.RANGE_M100_100
|
||||||
|
self.bus = DynamixelMotorsBus(
|
||||||
|
port=self.config.port,
|
||||||
|
motors={
|
||||||
|
"shoulder_pan": Motor(11, "xl430-w250", norm_mode_body),
|
||||||
|
"shoulder_lift": Motor(12, "xl430-w250", norm_mode_body),
|
||||||
|
"elbow_flex": Motor(13, "xl430-w250", norm_mode_body),
|
||||||
|
"wrist_flex": Motor(14, "xl330-m288", norm_mode_body),
|
||||||
|
"wrist_roll": Motor(15, "xl330-m288", norm_mode_body),
|
||||||
|
"gripper": Motor(16, "xl330-m288", MotorNormMode.RANGE_0_100),
|
||||||
|
},
|
||||||
|
calibration=self.calibration,
|
||||||
|
)
|
||||||
|
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.bus.motors}
|
||||||
|
|
||||||
|
@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_connected and all(cam.is_connected for cam in self.cameras.values())
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = True) -> None:
|
||||||
|
"""
|
||||||
|
For OMX robots that come pre-calibrated:
|
||||||
|
- If default calibration from package doesn't match motors, read from motors and save
|
||||||
|
- This allows using pre-calibrated robots without manual calibration
|
||||||
|
- If no calibration file exists, use factory default values (homing_offset=0, range_min=0, range_max=4095)
|
||||||
|
"""
|
||||||
|
if self.is_connected:
|
||||||
|
raise DeviceAlreadyConnectedError(f"{self} already connected")
|
||||||
|
|
||||||
|
self.bus.connect()
|
||||||
|
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 self.bus.is_calibrated
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
self.bus.disable_torque()
|
||||||
|
logger.info(f"\nUsing factory default calibration values for {self}")
|
||||||
|
logger.info(f"\nWriting default configuration of {self} to the motors")
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
self.bus.write("Drive_Mode", motor, DriveMode.NON_INVERTED.value)
|
||||||
|
|
||||||
|
self.calibration = {}
|
||||||
|
for motor, m in self.bus.motors.items():
|
||||||
|
self.calibration[motor] = MotorCalibration(
|
||||||
|
id=m.id,
|
||||||
|
drive_mode=0,
|
||||||
|
homing_offset=0,
|
||||||
|
range_min=0,
|
||||||
|
range_max=4095,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.bus.write_calibration(self.calibration)
|
||||||
|
self._save_calibration()
|
||||||
|
logger.info(f"Calibration saved to {self.calibration_fpath}")
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
with self.bus.torque_disabled():
|
||||||
|
self.bus.configure_motors()
|
||||||
|
# Use 'extended position mode' for all motors except gripper, because in joint mode the servos
|
||||||
|
# can't rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling
|
||||||
|
# the arm, you could end up with a servo with a position 0 or 4095 at a crucial point
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
if motor != "gripper":
|
||||||
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
# Use 'position control current based' for gripper to be limited by the limit of the current. For
|
||||||
|
# the follower gripper, it means it can grasp an object without forcing too much even tho, its
|
||||||
|
# goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch).
|
||||||
|
# For the leader gripper, it means we can use it as a physical trigger, since we can force with
|
||||||
|
# our finger to make it move, and it will move back to its original target position when we
|
||||||
|
# release the force.
|
||||||
|
self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
|
||||||
|
|
||||||
|
# Set better PID values to close the gap between recorded states and actions
|
||||||
|
# TODO(rcadene): Implement an automatic procedure to set optimal PID values for each motor
|
||||||
|
self.bus.write("Position_P_Gain", "elbow_flex", 1500)
|
||||||
|
self.bus.write("Position_I_Gain", "elbow_flex", 0)
|
||||||
|
self.bus.write("Position_D_Gain", "elbow_flex", 600)
|
||||||
|
|
||||||
|
def setup_motors(self) -> None:
|
||||||
|
for motor in reversed(self.bus.motors):
|
||||||
|
input(f"Connect the controller board to the '{motor}' motor only and press enter.")
|
||||||
|
self.bus.setup_motor(motor)
|
||||||
|
print(f"'{motor}' motor id set to {self.bus.motors[motor].id}")
|
||||||
|
|
||||||
|
def get_observation(self) -> dict[str, Any]:
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
# Read arm position
|
||||||
|
start = time.perf_counter()
|
||||||
|
obs_dict = self.bus.sync_read("Present_Position")
|
||||||
|
obs_dict = {f"{motor}.pos": val for motor, val in obs_dict.items()}
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read state: {dt_ms:.1f}ms")
|
||||||
|
|
||||||
|
# Capture images from cameras
|
||||||
|
for cam_key, cam in self.cameras.items():
|
||||||
|
start = time.perf_counter()
|
||||||
|
obs_dict[cam_key] = cam.async_read()
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
|
||||||
|
|
||||||
|
return obs_dict
|
||||||
|
|
||||||
|
def send_action(self, action: dict[str, float]) -> dict[str, float]:
|
||||||
|
"""Command arm to move to a target joint configuration.
|
||||||
|
|
||||||
|
The relative action magnitude may be clipped depending on the configuration parameter
|
||||||
|
`max_relative_target`. In this case, the action sent differs from original action.
|
||||||
|
Thus, this function always returns the action actually sent.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
action (dict[str, float]): The goal positions for the motors.
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
dict[str, float]: The action sent to the motors, potentially clipped.
|
||||||
|
"""
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
goal_pos = {key.removesuffix(".pos"): val for key, val in action.items() if key.endswith(".pos")}
|
||||||
|
|
||||||
|
# Cap goal position when too far away from present position.
|
||||||
|
# /!\ Slower fps expected due to reading from the follower.
|
||||||
|
if self.config.max_relative_target is not None:
|
||||||
|
present_pos = self.bus.sync_read("Present_Position")
|
||||||
|
goal_present_pos = {key: (g_pos, present_pos[key]) for key, g_pos in goal_pos.items()}
|
||||||
|
goal_pos = ensure_safe_goal_position(goal_present_pos, self.config.max_relative_target)
|
||||||
|
|
||||||
|
# Send goal position to the arm
|
||||||
|
self.bus.sync_write("Goal_Position", goal_pos)
|
||||||
|
return {f"{motor}.pos": val for motor, val in goal_pos.items()}
|
||||||
|
|
||||||
|
def disconnect(self):
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
self.bus.disconnect(self.config.disable_torque_on_disconnect)
|
||||||
|
for cam in self.cameras.values():
|
||||||
|
cam.disconnect()
|
||||||
|
|
||||||
|
logger.info(f"{self} disconnected.")
|
||||||
@@ -28,6 +28,10 @@ def make_robot_from_config(config: RobotConfig) -> Robot:
|
|||||||
from .koch_follower import KochFollower
|
from .koch_follower import KochFollower
|
||||||
|
|
||||||
return KochFollower(config)
|
return KochFollower(config)
|
||||||
|
elif config.type == "omx_follower":
|
||||||
|
from .omx_follower import OmxFollower
|
||||||
|
|
||||||
|
return OmxFollower(config)
|
||||||
elif config.type == "so100_follower":
|
elif config.type == "so100_follower":
|
||||||
from .so100_follower import SO100Follower
|
from .so100_follower import SO100Follower
|
||||||
|
|
||||||
|
|||||||
@@ -40,6 +40,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
koch_follower,
|
koch_follower,
|
||||||
lekiwi,
|
lekiwi,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
@@ -49,6 +50,7 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
homunculus,
|
homunculus,
|
||||||
koch_leader,
|
koch_leader,
|
||||||
make_teleoperator_from_config,
|
make_teleoperator_from_config,
|
||||||
|
omx_leader,
|
||||||
so100_leader,
|
so100_leader,
|
||||||
so101_leader,
|
so101_leader,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -46,6 +46,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
RobotConfig,
|
RobotConfig,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
@@ -54,6 +55,7 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
gamepad,
|
gamepad,
|
||||||
koch_leader,
|
koch_leader,
|
||||||
make_teleoperator_from_config,
|
make_teleoperator_from_config,
|
||||||
|
omx_leader,
|
||||||
so100_leader,
|
so100_leader,
|
||||||
so101_leader,
|
so101_leader,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -97,6 +97,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
hope_jr,
|
hope_jr,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
@@ -107,6 +108,7 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
homunculus,
|
homunculus,
|
||||||
koch_leader,
|
koch_leader,
|
||||||
make_teleoperator_from_config,
|
make_teleoperator_from_config,
|
||||||
|
omx_leader,
|
||||||
so100_leader,
|
so100_leader,
|
||||||
so101_leader,
|
so101_leader,
|
||||||
)
|
)
|
||||||
@@ -270,7 +272,12 @@ def record_loop(
|
|||||||
for t in teleop
|
for t in teleop
|
||||||
if isinstance(
|
if isinstance(
|
||||||
t,
|
t,
|
||||||
(so100_leader.SO100Leader | so101_leader.SO101Leader | koch_leader.KochLeader),
|
(
|
||||||
|
so100_leader.SO100Leader
|
||||||
|
| so101_leader.SO101Leader
|
||||||
|
| koch_leader.KochLeader
|
||||||
|
| omx_leader.OmxLeader
|
||||||
|
),
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
None,
|
None,
|
||||||
|
|||||||
@@ -58,6 +58,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
hope_jr,
|
hope_jr,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -33,6 +33,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
koch_follower,
|
koch_follower,
|
||||||
lekiwi,
|
lekiwi,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
@@ -40,6 +41,7 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
TeleoperatorConfig,
|
TeleoperatorConfig,
|
||||||
koch_leader,
|
koch_leader,
|
||||||
make_teleoperator_from_config,
|
make_teleoperator_from_config,
|
||||||
|
omx_leader,
|
||||||
so100_leader,
|
so100_leader,
|
||||||
so101_leader,
|
so101_leader,
|
||||||
)
|
)
|
||||||
@@ -47,6 +49,8 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
COMPATIBLE_DEVICES = [
|
COMPATIBLE_DEVICES = [
|
||||||
"koch_follower",
|
"koch_follower",
|
||||||
"koch_leader",
|
"koch_leader",
|
||||||
|
"omx_follower",
|
||||||
|
"omx_leader",
|
||||||
"so100_follower",
|
"so100_follower",
|
||||||
"so100_leader",
|
"so100_leader",
|
||||||
"so101_follower",
|
"so101_follower",
|
||||||
|
|||||||
@@ -75,6 +75,7 @@ from lerobot.robots import ( # noqa: F401
|
|||||||
hope_jr,
|
hope_jr,
|
||||||
koch_follower,
|
koch_follower,
|
||||||
make_robot_from_config,
|
make_robot_from_config,
|
||||||
|
omx_follower,
|
||||||
so100_follower,
|
so100_follower,
|
||||||
so101_follower,
|
so101_follower,
|
||||||
)
|
)
|
||||||
@@ -87,6 +88,7 @@ from lerobot.teleoperators import ( # noqa: F401
|
|||||||
keyboard,
|
keyboard,
|
||||||
koch_leader,
|
koch_leader,
|
||||||
make_teleoperator_from_config,
|
make_teleoperator_from_config,
|
||||||
|
omx_leader,
|
||||||
so100_leader,
|
so100_leader,
|
||||||
so101_leader,
|
so101_leader,
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -0,0 +1,18 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2025 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_omx_leader import OmxLeaderConfig
|
||||||
|
from .omx_leader import OmxLeader
|
||||||
@@ -0,0 +1,30 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2024 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
|
||||||
|
|
||||||
|
|
||||||
|
@TeleoperatorConfig.register_subclass("omx_leader")
|
||||||
|
@dataclass
|
||||||
|
class OmxLeaderConfig(TeleoperatorConfig):
|
||||||
|
# Port to connect to the arm
|
||||||
|
port: str
|
||||||
|
|
||||||
|
# Sets the arm in torque mode with the gripper motor set to this value. This makes it possible to squeeze
|
||||||
|
# the gripper and have it spring back to an open position on its own.
|
||||||
|
gripper_open_pos: float = 37.0
|
||||||
@@ -0,0 +1,165 @@
|
|||||||
|
#!/usr/bin/env python
|
||||||
|
|
||||||
|
# Copyright 2024 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 lerobot.motors import Motor, MotorCalibration, MotorNormMode
|
||||||
|
from lerobot.motors.dynamixel import (
|
||||||
|
DriveMode,
|
||||||
|
DynamixelMotorsBus,
|
||||||
|
OperatingMode,
|
||||||
|
)
|
||||||
|
from lerobot.utils.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
|
||||||
|
|
||||||
|
from ..teleoperator import Teleoperator
|
||||||
|
from .config_omx_leader import OmxLeaderConfig
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
|
||||||
|
|
||||||
|
class OmxLeader(Teleoperator):
|
||||||
|
"""
|
||||||
|
- [OMX](https://github.com/ROBOTIS-GIT/open_manipulator),
|
||||||
|
expansion, developed by Woojin Wie and Junha Cha from [ROBOTIS](https://ai.robotis.com/)
|
||||||
|
"""
|
||||||
|
|
||||||
|
config_class = OmxLeaderConfig
|
||||||
|
name = "omx_leader"
|
||||||
|
|
||||||
|
def __init__(self, config: OmxLeaderConfig):
|
||||||
|
super().__init__(config)
|
||||||
|
self.config = config
|
||||||
|
self.bus = DynamixelMotorsBus(
|
||||||
|
port=self.config.port,
|
||||||
|
motors={
|
||||||
|
"shoulder_pan": Motor(1, "xl330-m288", MotorNormMode.RANGE_M100_100),
|
||||||
|
"shoulder_lift": Motor(2, "xl330-m288", MotorNormMode.RANGE_M100_100),
|
||||||
|
"elbow_flex": Motor(3, "xl330-m288", MotorNormMode.RANGE_M100_100),
|
||||||
|
"wrist_flex": Motor(4, "xl330-m288", MotorNormMode.RANGE_M100_100),
|
||||||
|
"wrist_roll": Motor(5, "xl330-m288", MotorNormMode.RANGE_M100_100),
|
||||||
|
"gripper": Motor(6, "xl330-m077", MotorNormMode.RANGE_0_100),
|
||||||
|
},
|
||||||
|
calibration=self.calibration,
|
||||||
|
)
|
||||||
|
|
||||||
|
@property
|
||||||
|
def action_features(self) -> dict[str, type]:
|
||||||
|
return {f"{motor}.pos": float for motor in self.bus.motors}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def feedback_features(self) -> dict[str, type]:
|
||||||
|
return {}
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_connected(self) -> bool:
|
||||||
|
return self.bus.is_connected
|
||||||
|
|
||||||
|
def connect(self, calibrate: bool = True) -> None:
|
||||||
|
if self.is_connected:
|
||||||
|
raise DeviceAlreadyConnectedError(f"{self} already connected")
|
||||||
|
|
||||||
|
self.bus.connect()
|
||||||
|
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()
|
||||||
|
logger.info(f"{self} connected.")
|
||||||
|
|
||||||
|
@property
|
||||||
|
def is_calibrated(self) -> bool:
|
||||||
|
return self.bus.is_calibrated
|
||||||
|
|
||||||
|
def calibrate(self) -> None:
|
||||||
|
self.bus.disable_torque()
|
||||||
|
logger.info(f"\nUsing factory default calibration values for {self}")
|
||||||
|
logger.info(f"\nWriting default configuration of {self} to the motors")
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
if motor == "gripper":
|
||||||
|
self.bus.write("Drive_Mode", motor, DriveMode.INVERTED.value)
|
||||||
|
else:
|
||||||
|
self.bus.write("Drive_Mode", motor, DriveMode.NON_INVERTED.value)
|
||||||
|
drive_modes = {motor: 1 if motor == "gripper" else 0 for motor in self.bus.motors}
|
||||||
|
|
||||||
|
self.calibration = {}
|
||||||
|
for motor, m in self.bus.motors.items():
|
||||||
|
self.calibration[motor] = MotorCalibration(
|
||||||
|
id=m.id,
|
||||||
|
drive_mode=drive_modes[motor],
|
||||||
|
homing_offset=0,
|
||||||
|
range_min=0,
|
||||||
|
range_max=4095,
|
||||||
|
)
|
||||||
|
|
||||||
|
self.bus.write_calibration(self.calibration)
|
||||||
|
self._save_calibration()
|
||||||
|
logger.info(f"Calibration saved to {self.calibration_fpath}")
|
||||||
|
|
||||||
|
def configure(self) -> None:
|
||||||
|
self.bus.disable_torque()
|
||||||
|
self.bus.configure_motors()
|
||||||
|
for motor in self.bus.motors:
|
||||||
|
if motor != "gripper":
|
||||||
|
# Use 'extended position mode' for all motors except gripper, because in joint mode the servos
|
||||||
|
# can't rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while
|
||||||
|
# assembling the arm, you could end up with a servo with a position 0 or 4095 at a crucial
|
||||||
|
# point
|
||||||
|
self.bus.write("Operating_Mode", motor, OperatingMode.EXTENDED_POSITION.value)
|
||||||
|
|
||||||
|
# Use 'position control current based' for gripper to be limited by the limit of the current.
|
||||||
|
# For the follower gripper, it means it can grasp an object without forcing too much even tho,
|
||||||
|
# its goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch).
|
||||||
|
# For the leader gripper, it means we can use it as a physical trigger, since we can force with our finger
|
||||||
|
# to make it move, and it will move back to its original target position when we release the force.
|
||||||
|
self.bus.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
|
||||||
|
# Set gripper's goal pos in current position mode so that we can use it as a trigger.
|
||||||
|
self.bus.enable_torque("gripper")
|
||||||
|
if self.is_calibrated:
|
||||||
|
self.bus.write("Goal_Position", "gripper", self.config.gripper_open_pos)
|
||||||
|
|
||||||
|
def setup_motors(self) -> None:
|
||||||
|
for motor in reversed(self.bus.motors):
|
||||||
|
input(f"Connect the controller board to the '{motor}' motor only and press enter.")
|
||||||
|
self.bus.setup_motor(motor)
|
||||||
|
print(f"'{motor}' motor id set to {self.bus.motors[motor].id}")
|
||||||
|
|
||||||
|
def get_action(self) -> dict[str, float]:
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
start = time.perf_counter()
|
||||||
|
action = self.bus.sync_read("Present_Position")
|
||||||
|
action = {f"{motor}.pos": val for motor, val in action.items()}
|
||||||
|
dt_ms = (time.perf_counter() - start) * 1e3
|
||||||
|
logger.debug(f"{self} read action: {dt_ms:.1f}ms")
|
||||||
|
return action
|
||||||
|
|
||||||
|
def send_feedback(self, feedback: dict[str, float]) -> None:
|
||||||
|
# TODO(rcadene, aliberts): Implement force feedback
|
||||||
|
raise NotImplementedError
|
||||||
|
|
||||||
|
def disconnect(self) -> None:
|
||||||
|
if not self.is_connected:
|
||||||
|
raise DeviceNotConnectedError(f"{self} is not connected.")
|
||||||
|
|
||||||
|
self.bus.disconnect()
|
||||||
|
logger.info(f"{self} disconnected.")
|
||||||
@@ -41,6 +41,10 @@ def make_teleoperator_from_config(config: TeleoperatorConfig) -> Teleoperator:
|
|||||||
from .koch_leader import KochLeader
|
from .koch_leader import KochLeader
|
||||||
|
|
||||||
return KochLeader(config)
|
return KochLeader(config)
|
||||||
|
elif config.type == "omx_leader":
|
||||||
|
from .omx_leader import OmxLeader
|
||||||
|
|
||||||
|
return OmxLeader(config)
|
||||||
elif config.type == "so100_leader":
|
elif config.type == "so100_leader":
|
||||||
from .so100_leader import SO100Leader
|
from .so100_leader import SO100Leader
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user