mirror of
https://github.com/huggingface/lerobot.git
synced 2026-06-03 12:21:27 +00:00
* Fix imports * Add feetech write tests * Nit * Add autoclosing fixture * Assert ping stub called * Add CalibrationMode * Add Motor in dxl robots * Simplify split_int_bytes * Rename read/write -> sync_read/write, refactor, add write * Rename tests * Refactor dxl tests by functionality * Add dxl write test * Refactor _is_comm_success * Refactor feetech tests by functionality * Add feetech write test * Simplify _is_comm_success & _is_error * Move mock_serial patch to dedicated file * Remove test skips & fix docstrings * Nit * Add dxl operating modes * Add is_connected in robots and teleops * Update Koch * Add feetech operating modes * Caps dxl OperatingMode * Update ensure_safe_goal_position * Update so100 * Privatize methods & renames * Fix dict * Add _configure_motors & move ping methods * Return models (str) with pings * Implement feetech broadcast ping * Add raw_values option * Rename idx -> id_ * Improve errors * Fix feetech ping tests * Ensure motors exist at connection time * Update tests * Add test_motors_bus * Move DriveMode & TorqueMode * Update Koch imports * Update so100 imports * Fix visualize_motors_bus * Fix imports * Add calibration * Rename idx -> id_ * Rename idx -> id_ * (WIP) _async_read * Add new calibration method for robot refactor (#896) Co-authored-by: Simon Alibert <simon.alibert@huggingface.co> * Remove deprecated scripts * Rename CalibrationMode -> MotorNormMode * Fix calibration functions * Remove todo * Add scan_port utility * Add calibration utilities * Move encoding functions to encoding_utils * Add test_encoding_utils * Rename test * Add more calibration utilities * Format baudrate tables * Implement SO-100 leader calibration * Implement SO-100 follower calibration * Implement Koch calibration * Add test_scan_port (TODO) * Fix calibration * Hack feetech firmware bug * Update tests * Update Koch & SO-100 * Improve format * Rename SO-100 classes * Rename Koch classes * Add calibration tests * Remove old calibration tests * Revert feetech hack and monkeypatch instead * Simplify motors mocks * Add is_calibrated test * Update viperx & widowx * Rename viperx & widowx * Remove old calibration * feat(teleop): thread-safe keyboard teleop implementation (#869) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> * Add support for feetech scs series + various fixes * Update dynamixel with motors bus & tables changes * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * (WIP) Add Hope Jr * Rename arm -> hand * (WIP) Add homonculus arm & glove * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * Add Feetech protocol version * Implement read * Use constants from sdks * (nit) move write * Fix broadcast ping type hint * Add protocol 1 broadcast ping * Refactor & add _serialize_data * Add feetech sm8512bl * Make feetech broadcast ping faster in protocol 1 * Cleanup * Add support for feetech protocol 1 to _split_into_byte_chunks * Fix unormalize * Remove test_motors_bus fixtures * Add more segmented tests (base motor bus & feetech), add feetech protocol 1 support * Add more segmented tests (dynamixel) * Refactor tests * Add handshake, fix feetech _read_firmware_version * Fix tests * Motors config & disconnect fixes * Add torque_disabled context * Update branch & fix pre-commit errors * Fix hand & glove readings * Update feetech tables * Move read/write_calibration implementations * Add setup_motor * Fix calibration msg display * Fix setup_motor & add it to robots * Fix _find_single_motor * Remove deprecated configure_motor * Remove deprecated dynamixel_calibration * Remove names * Remove deprecated import * refactor/lekiwi robot (#863) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Simon Alibert <simon.alibert@huggingface.co> Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> * fix(teleoperators): use property is_connected (#1075) * Remove deprecated manipulator * Update robot features & naming * Update teleop features & naming * Add make_teleoperator_from_config * Rename find_port * Fix config parsing * Remove app script * Add setup_motors * Add teleoperate * Add record * Add replay * Fix test_datasets * Add mock robot & teleop * Add new test_control_robot * Add test_record_and_resume * Remove deprecated scripts & tests * Add calibrate * Add docstrings * Fix tests (no-extras install) * Add SO101 * Remove pynput from optional deps * Rename example 7 * Remove unecessary id * Add MotorsBus docstrings * Rename arm -> bus * Remove Moss arm * Fix setup_motors & calibrate configs * Fix test_calibrate * Add copyrights * Update hand & arm * Update homonculus hand & arm * Fix dxl _find_single_motor * Update glove * Add setup_motors for lekiwi * Fix glove calibration * Complete docstring * Add check for same min and max during calibration * Move MockMotorsBus * Add so100_follower tests * (WIP) add calibration gui * Fix test * Add setup_motors * Update calibration gui * Remove old .cache folder * Replace deprecated abc.abstractproperty * Fix feetech protocol 1 configure * Cleanup gui & add copyrights * Anatomically precise joint names * (WIP) Add glove to hand joints translation * Move make_robot_config * Add drive_mode & norm_mode in glove calibration * Fix joints translation * Fix normalization drive_mode * nit * Fix glove to hand conversion * Adapt feetech calibration * Remove pygame prompt * Implement arm calibration (hacks) * Better MotorsBus error messages * Update feetech read_calibration * Fix feetech test_is_calibrated * Cleanup glove * (WIP) Update arm * Add changes from #1117 * refactor(cameras): cameras implementations + tests improvements (#1108) Co-authored-by: Simon Alibert <simon.alibert@huggingface.co> Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * Fix arm joints order * Add timeout/event logic * Fix arm & glove * Fix predict_action from record * fix(cameras): update docstring + handle sn when starts with 0 + update timeouts to more reasonable value (#1154) * fix(scripts): parser instead of draccus in record + add __get_path_fields__() to RecordConfig (#1155) * Left/Right sides + other fixes * Arm fixes and add config * More hacks * Add control scripts * Fix merge errors * push changes to calibration, teleop and docs * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * Move readme to docs * update readme Signed-off-by: Martino Russi <77496684+nepyope@users.noreply.github.com> * Add files via upload Signed-off-by: Martino Russi <77496684+nepyope@users.noreply.github.com> * Update image sources * Symlink doc * Compress image * Move image * Update docs link * fix docs * simplify teleop scripts * fix variable names * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * Address code review * add EMA to glove * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * integrate teleoperation for hand * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * update docs * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * import hopejr/homunculus in teleoperate * update docs for teleoperate, record, replay, train and inference * [pre-commit.ci] auto fixes from pre-commit.com hooks for more information, see https://pre-commit.ci * chore(hopejr): address comments * chore(hopejr): address coments 2 * chore(docs): update teleoperation instructions for the hand/glove * fix(hopejr): calibration int + update docs --------- Signed-off-by: Martino Russi <77496684+nepyope@users.noreply.github.com> Signed-off-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> Co-authored-by: Pepijn <138571049+pkooij@users.noreply.github.com> Co-authored-by: Steven Palma <imstevenpmwork@ieee.org> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: nepyope <nopyeps@gmail.com> Co-authored-by: Martino Russi <77496684+nepyope@users.noreply.github.com> Co-authored-by: Steven Palma <steven.palma@huggingface.co>
265 lines
11 KiB
Python
265 lines
11 KiB
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.
|
|
|
|
# TODO(aliberts): Should we implement FastSyncRead/Write?
|
|
# https://github.com/ROBOTIS-GIT/DynamixelSDK/pull/643
|
|
# https://github.com/ROBOTIS-GIT/DynamixelSDK/releases/tag/3.8.2
|
|
# https://emanual.robotis.com/docs/en/dxl/protocol2/#fast-sync-read-0x8a
|
|
# -> Need to check compatibility across models
|
|
|
|
import logging
|
|
from copy import deepcopy
|
|
from enum import Enum
|
|
|
|
from lerobot.utils.encoding_utils import decode_twos_complement, encode_twos_complement
|
|
|
|
from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value, get_address
|
|
from .tables import (
|
|
AVAILABLE_BAUDRATES,
|
|
MODEL_BAUDRATE_TABLE,
|
|
MODEL_CONTROL_TABLE,
|
|
MODEL_ENCODING_TABLE,
|
|
MODEL_NUMBER_TABLE,
|
|
MODEL_RESOLUTION,
|
|
)
|
|
|
|
PROTOCOL_VERSION = 2.0
|
|
DEFAULT_BAUDRATE = 1_000_000
|
|
DEFAULT_TIMEOUT_MS = 1000
|
|
|
|
NORMALIZED_DATA = ["Goal_Position", "Present_Position"]
|
|
|
|
logger = logging.getLogger(__name__)
|
|
|
|
|
|
class OperatingMode(Enum):
|
|
# DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
|
|
# gripper or a system that only uses current(torque) control or a system that has additional
|
|
# velocity/position controllers.
|
|
CURRENT = 0
|
|
|
|
# This mode controls velocity. This mode is identical to the Wheel Mode(endless) from existing DYNAMIXEL.
|
|
# This mode is ideal for wheel-type robots.
|
|
VELOCITY = 1
|
|
|
|
# This mode controls position. This mode is identical to the Joint Mode from existing DYNAMIXEL. Operating
|
|
# position range is limited by the Max Position Limit(48) and the Min Position Limit(52). This mode is
|
|
# ideal for articulated robots that each joint rotates less than 360 degrees.
|
|
POSITION = 3
|
|
|
|
# This mode controls position. This mode is identical to the Multi-turn Position Control from existing
|
|
# DYNAMIXEL. 512 turns are supported(-256[rev] ~ 256[rev]). This mode is ideal for multi-turn wrists or
|
|
# conveyer systems or a system that requires an additional reduction gear. Note that Max Position
|
|
# Limit(48), Min Position Limit(52) are not used on Extended Position Control Mode.
|
|
EXTENDED_POSITION = 4
|
|
|
|
# This mode controls both position and current(torque). Up to 512 turns are supported (-256[rev] ~
|
|
# 256[rev]). This mode is ideal for a system that requires both position and current control such as
|
|
# articulated robots or grippers.
|
|
CURRENT_POSITION = 5
|
|
|
|
# This mode directly controls PWM output. (Voltage Control Mode)
|
|
PWM = 16
|
|
|
|
|
|
class DriveMode(Enum):
|
|
NON_INVERTED = 0
|
|
INVERTED = 1
|
|
|
|
|
|
class TorqueMode(Enum):
|
|
ENABLED = 1
|
|
DISABLED = 0
|
|
|
|
|
|
def _split_into_byte_chunks(value: int, length: int) -> list[int]:
|
|
import dynamixel_sdk as dxl
|
|
|
|
if length == 1:
|
|
data = [value]
|
|
elif length == 2:
|
|
data = [dxl.DXL_LOBYTE(value), dxl.DXL_HIBYTE(value)]
|
|
elif length == 4:
|
|
data = [
|
|
dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
|
|
dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
|
|
dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)),
|
|
dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
|
|
]
|
|
return data
|
|
|
|
|
|
class DynamixelMotorsBus(MotorsBus):
|
|
"""
|
|
The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
|
|
the motors. For more info, see the Dynamixel SDK Documentation:
|
|
https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20
|
|
"""
|
|
|
|
apply_drive_mode = False
|
|
available_baudrates = deepcopy(AVAILABLE_BAUDRATES)
|
|
default_baudrate = DEFAULT_BAUDRATE
|
|
default_timeout = DEFAULT_TIMEOUT_MS
|
|
model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
|
|
model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
|
|
model_encoding_table = deepcopy(MODEL_ENCODING_TABLE)
|
|
model_number_table = deepcopy(MODEL_NUMBER_TABLE)
|
|
model_resolution_table = deepcopy(MODEL_RESOLUTION)
|
|
normalized_data = deepcopy(NORMALIZED_DATA)
|
|
|
|
def __init__(
|
|
self,
|
|
port: str,
|
|
motors: dict[str, Motor],
|
|
calibration: dict[str, MotorCalibration] | None = None,
|
|
):
|
|
super().__init__(port, motors, calibration)
|
|
import dynamixel_sdk as dxl
|
|
|
|
self.port_handler = dxl.PortHandler(self.port)
|
|
self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
|
|
self.sync_reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
|
|
self.sync_writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
|
|
self._comm_success = dxl.COMM_SUCCESS
|
|
self._no_error = 0x00
|
|
|
|
def _assert_protocol_is_compatible(self, instruction_name: str) -> None:
|
|
pass
|
|
|
|
def _handshake(self) -> None:
|
|
self._assert_motors_exist()
|
|
|
|
def _find_single_motor(self, motor: str, initial_baudrate: int | None = None) -> tuple[int, int]:
|
|
model = self.motors[motor].model
|
|
search_baudrates = (
|
|
[initial_baudrate] if initial_baudrate is not None else self.model_baudrate_table[model]
|
|
)
|
|
|
|
for baudrate in search_baudrates:
|
|
self.set_baudrate(baudrate)
|
|
id_model = self.broadcast_ping()
|
|
if id_model:
|
|
found_id, found_model = next(iter(id_model.items()))
|
|
expected_model_nb = self.model_number_table[model]
|
|
if found_model != expected_model_nb:
|
|
raise RuntimeError(
|
|
f"Found one motor on {baudrate=} with id={found_id} but it has a "
|
|
f"model number '{found_model}' different than the one expected: '{expected_model_nb}'. "
|
|
f"Make sure you are connected only connected to the '{motor}' motor (model '{model}')."
|
|
)
|
|
return baudrate, found_id
|
|
|
|
raise RuntimeError(f"Motor '{motor}' (model '{model}') was not found. Make sure it is connected.")
|
|
|
|
def configure_motors(self, return_delay_time=0) -> None:
|
|
# By default, Dynamixel motors have a 500µs delay response time (corresponding to a value of 250 on
|
|
# the 'Return_Delay_Time' address). We ensure this is reduced to the minimum of 2µs (value of 0).
|
|
for motor in self.motors:
|
|
self.write("Return_Delay_Time", motor, return_delay_time)
|
|
|
|
@property
|
|
def is_calibrated(self) -> bool:
|
|
return self.calibration == self.read_calibration()
|
|
|
|
def read_calibration(self) -> dict[str, MotorCalibration]:
|
|
offsets = self.sync_read("Homing_Offset", normalize=False)
|
|
mins = self.sync_read("Min_Position_Limit", normalize=False)
|
|
maxes = self.sync_read("Max_Position_Limit", normalize=False)
|
|
drive_modes = self.sync_read("Drive_Mode", normalize=False)
|
|
|
|
calibration = {}
|
|
for motor, m in self.motors.items():
|
|
calibration[motor] = MotorCalibration(
|
|
id=m.id,
|
|
drive_mode=drive_modes[motor],
|
|
homing_offset=offsets[motor],
|
|
range_min=mins[motor],
|
|
range_max=maxes[motor],
|
|
)
|
|
|
|
return calibration
|
|
|
|
def write_calibration(self, calibration_dict: dict[str, MotorCalibration], cache: bool = True) -> None:
|
|
for motor, calibration in calibration_dict.items():
|
|
self.write("Homing_Offset", motor, calibration.homing_offset)
|
|
self.write("Min_Position_Limit", motor, calibration.range_min)
|
|
self.write("Max_Position_Limit", motor, calibration.range_max)
|
|
|
|
if cache:
|
|
self.calibration = calibration_dict
|
|
|
|
def disable_torque(self, motors: str | list[str] | None = None, num_retry: int = 0) -> None:
|
|
for motor in self._get_motors_list(motors):
|
|
self.write("Torque_Enable", motor, TorqueMode.DISABLED.value, num_retry=num_retry)
|
|
|
|
def _disable_torque(self, motor_id: int, model: str, num_retry: int = 0) -> None:
|
|
addr, length = get_address(self.model_ctrl_table, model, "Torque_Enable")
|
|
self._write(addr, length, motor_id, TorqueMode.DISABLED.value, num_retry=num_retry)
|
|
|
|
def enable_torque(self, motors: str | list[str] | None = None, num_retry: int = 0) -> None:
|
|
for motor in self._get_motors_list(motors):
|
|
self.write("Torque_Enable", motor, TorqueMode.ENABLED.value, num_retry=num_retry)
|
|
|
|
def _encode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
|
|
for id_ in ids_values:
|
|
model = self._id_to_model(id_)
|
|
encoding_table = self.model_encoding_table.get(model)
|
|
if encoding_table and data_name in encoding_table:
|
|
n_bytes = encoding_table[data_name]
|
|
ids_values[id_] = encode_twos_complement(ids_values[id_], n_bytes)
|
|
|
|
return ids_values
|
|
|
|
def _decode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
|
|
for id_ in ids_values:
|
|
model = self._id_to_model(id_)
|
|
encoding_table = self.model_encoding_table.get(model)
|
|
if encoding_table and data_name in encoding_table:
|
|
n_bytes = encoding_table[data_name]
|
|
ids_values[id_] = decode_twos_complement(ids_values[id_], n_bytes)
|
|
|
|
return ids_values
|
|
|
|
def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
|
|
"""
|
|
On Dynamixel Motors:
|
|
Present_Position = Actual_Position + Homing_Offset
|
|
"""
|
|
half_turn_homings = {}
|
|
for motor, pos in positions.items():
|
|
model = self._get_motor_model(motor)
|
|
max_res = self.model_resolution_table[model] - 1
|
|
half_turn_homings[motor] = int(max_res / 2) - pos
|
|
|
|
return half_turn_homings
|
|
|
|
def _split_into_byte_chunks(self, value: int, length: int) -> list[int]:
|
|
return _split_into_byte_chunks(value, length)
|
|
|
|
def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, int] | None:
|
|
for n_try in range(1 + num_retry):
|
|
data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
|
|
if self._is_comm_success(comm):
|
|
break
|
|
logger.debug(f"Broadcast ping failed on port '{self.port}' ({n_try=})")
|
|
logger.debug(self.packet_handler.getTxRxResult(comm))
|
|
|
|
if not self._is_comm_success(comm):
|
|
if raise_on_error:
|
|
raise ConnectionError(self.packet_handler.getTxRxResult(comm))
|
|
|
|
return
|
|
|
|
return {id_: data[0] for id_, data in data_list.items()}
|