Compare commits
4 Commits
2bb73ac431
...
bf1c737858
Author | SHA1 | Date |
---|---|---|
|
bf1c737858 | |
|
d07c7347f8 | |
|
57e5e4cc07 | |
|
2743c29a96 |
|
@ -35,7 +35,7 @@ from .tables import (
|
|||
)
|
||||
|
||||
PROTOCOL_VERSION = 2.0
|
||||
BAUDRATE = 1_000_000
|
||||
DEFAULT_BAUDRATE = 1_000_000
|
||||
DEFAULT_TIMEOUT_MS = 1000
|
||||
|
||||
NORMALIZED_DATA = ["Goal_Position", "Present_Position"]
|
||||
|
@ -109,6 +109,7 @@ class DynamixelMotorsBus(MotorsBus):
|
|||
"""
|
||||
|
||||
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)
|
||||
|
@ -139,12 +140,60 @@ class DynamixelMotorsBus(MotorsBus):
|
|||
def _handshake(self) -> None:
|
||||
self._assert_motors_exist()
|
||||
|
||||
def _find_single_motor(self, motor: str, initial_baudrate: int | 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) -> 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, 0)
|
||||
|
||||
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 name, motor in self.motors.items():
|
||||
calibration[name] = MotorCalibration(
|
||||
id=motor.id,
|
||||
drive_mode=drive_modes[name],
|
||||
homing_offset=offsets[name],
|
||||
range_min=mins[name],
|
||||
range_max=maxes[name],
|
||||
)
|
||||
|
||||
return calibration
|
||||
|
||||
def write_calibration(self, calibration_dict: dict[str, MotorCalibration]) -> 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)
|
||||
|
||||
self.calibration = calibration_dict
|
||||
|
||||
def disable_torque(self, motors: str | list[str] | None = None, num_retry: int = 0) -> None:
|
||||
for name in self._get_motors_list(motors):
|
||||
self.write("Torque_Enable", name, TorqueMode.DISABLED.value, num_retry=num_retry)
|
||||
|
|
|
@ -57,13 +57,13 @@ X_SERIES_CONTROL_TABLE = {
|
|||
|
||||
# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#baud-rate8
|
||||
X_SERIES_BAUDRATE_TABLE = {
|
||||
0: 9_600,
|
||||
1: 57_600,
|
||||
2: 115_200,
|
||||
3: 1_000_000,
|
||||
4: 2_000_000,
|
||||
5: 3_000_000,
|
||||
6: 4_000_000,
|
||||
9_600: 0,
|
||||
57_600: 1,
|
||||
115_200: 2,
|
||||
1_000_000: 3,
|
||||
2_000_000: 4,
|
||||
3_000_000: 5,
|
||||
4_000_000: 6,
|
||||
}
|
||||
|
||||
# {data_name: size_byte}
|
||||
|
|
|
@ -34,7 +34,7 @@ from .tables import (
|
|||
)
|
||||
|
||||
DEFAULT_PROTOCOL_VERSION = 0
|
||||
BAUDRATE = 1_000_000
|
||||
DEFAULT_BAUDRATE = 1_000_000
|
||||
DEFAULT_TIMEOUT_MS = 1000
|
||||
|
||||
NORMALIZED_DATA = ["Goal_Position", "Present_Position"]
|
||||
|
@ -103,6 +103,7 @@ class FeetechMotorsBus(MotorsBus):
|
|||
"""
|
||||
|
||||
available_baudrates = deepcopy(SCAN_BAUDRATES)
|
||||
default_baudrate = DEFAULT_BAUDRATE
|
||||
default_timeout = DEFAULT_TIMEOUT_MS
|
||||
model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
|
||||
model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
|
||||
|
@ -163,6 +164,57 @@ class FeetechMotorsBus(MotorsBus):
|
|||
self._assert_motors_exist()
|
||||
self._assert_same_firmware()
|
||||
|
||||
def _find_single_motor(self, motor: str, initial_baudrate: int | None = None) -> tuple[int, int]:
|
||||
if self.protocol_version == 0:
|
||||
return self._find_single_motor_p0(motor, initial_baudrate)
|
||||
else:
|
||||
return self._find_single_motor_p1(motor, initial_baudrate)
|
||||
|
||||
def _find_single_motor_p0(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]
|
||||
)
|
||||
expected_model_nb = self.model_number_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()))
|
||||
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 _find_single_motor_p1(self, motor: str, initial_baudrate: int | None = None) -> tuple[int, int]:
|
||||
import scservo_sdk as scs
|
||||
|
||||
model = self.motors[motor].model
|
||||
search_baudrates = (
|
||||
[initial_baudrate] if initial_baudrate is not None else self.model_baudrate_table[model]
|
||||
)
|
||||
expected_model_nb = self.model_number_table[model]
|
||||
|
||||
for baudrate in search_baudrates:
|
||||
self.set_baudrate(baudrate)
|
||||
for id_ in range(scs.MAX_ID + 1):
|
||||
found_model = self.ping(id_)
|
||||
if found_model is not None and found_model != expected_model_nb:
|
||||
raise RuntimeError(
|
||||
f"Found one motor on {baudrate=} with id={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, id_
|
||||
|
||||
raise RuntimeError(f"Motor '{motor}' (model '{model}') was not found. Make sure it is connected.")
|
||||
|
||||
def configure_motors(self) -> None:
|
||||
for motor in self.motors:
|
||||
# By default, Feetech motors have a 500µs delay response time (corresponding to a value of 250 on
|
||||
|
@ -173,6 +225,43 @@ class FeetechMotorsBus(MotorsBus):
|
|||
self.write("Maximum_Acceleration", motor, 254)
|
||||
self.write("Acceleration", motor, 254)
|
||||
|
||||
def read_calibration(self) -> dict[str, MotorCalibration]:
|
||||
if self.protocol_version == 0:
|
||||
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 = dict.fromkeys(self.motors, 0)
|
||||
else:
|
||||
offsets, mins, maxes, drive_modes = {}, {}, {}, {}
|
||||
for motor in self.motors:
|
||||
offsets[motor] = 0
|
||||
mins[motor] = self.read("Min_Position_Limit", motor, normalize=False)
|
||||
maxes[motor] = self.read("Max_Position_Limit", motor, normalize=False)
|
||||
drive_modes[motor] = 0
|
||||
|
||||
# TODO(aliberts): add set/get_drive_mode?
|
||||
|
||||
calibration = {}
|
||||
for name, motor in self.motors.items():
|
||||
calibration[name] = MotorCalibration(
|
||||
id=motor.id,
|
||||
drive_mode=drive_modes[name],
|
||||
homing_offset=offsets[name],
|
||||
range_min=mins[name],
|
||||
range_max=maxes[name],
|
||||
)
|
||||
|
||||
return calibration
|
||||
|
||||
def write_calibration(self, calibration_dict: dict[str, MotorCalibration]) -> None:
|
||||
for motor, calibration in calibration_dict.items():
|
||||
if self.protocol_version == 0:
|
||||
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)
|
||||
|
||||
self.calibration = calibration_dict
|
||||
|
||||
def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
|
||||
"""
|
||||
On Feetech Motors:
|
||||
|
@ -219,29 +308,7 @@ class FeetechMotorsBus(MotorsBus):
|
|||
def _split_into_byte_chunks(self, value: int, length: int) -> list[int]:
|
||||
return _split_into_byte_chunks(value, length)
|
||||
|
||||
def _broadcast_ping_p1(
|
||||
self, known_motors_only: bool = True, n_motors: int | None = None, num_retry: int = 0
|
||||
) -> dict[int, int]:
|
||||
if known_motors_only:
|
||||
ids = self.ids
|
||||
else:
|
||||
import scservo_sdk as scs
|
||||
|
||||
ids = range(scs.MAX_ID + 1)
|
||||
|
||||
ids_models = {}
|
||||
motors_found = 0
|
||||
for id_ in ids:
|
||||
model_number = self.ping(id_, num_retry)
|
||||
if model_number is not None:
|
||||
ids_models[id_] = model_number
|
||||
motors_found += 1
|
||||
if motors_found >= n_motors:
|
||||
break
|
||||
|
||||
return ids_models
|
||||
|
||||
def _broadcast_ping_p0(self) -> tuple[dict[int, int], int]:
|
||||
def _broadcast_ping(self) -> tuple[dict[int, int], int]:
|
||||
import scservo_sdk as scs
|
||||
|
||||
data_list = {}
|
||||
|
@ -318,7 +385,7 @@ class FeetechMotorsBus(MotorsBus):
|
|||
def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, int] | None:
|
||||
self._assert_protocol_is_compatible("broadcast_ping")
|
||||
for n_try in range(1 + num_retry):
|
||||
ids_status, comm = self._broadcast_ping_p0()
|
||||
ids_status, comm = self._broadcast_ping()
|
||||
if self._is_comm_success(comm):
|
||||
break
|
||||
logger.debug(f"Broadcast ping failed on port '{self.port}' ({n_try=})")
|
||||
|
|
|
@ -2,9 +2,8 @@ FIRMWARE_MAJOR_VERSION = (0, 1)
|
|||
FIRMWARE_MINOR_VERSION = (1, 1)
|
||||
MODEL_NUMBER = (3, 2)
|
||||
|
||||
# See this link for STS3215 Memory Table:
|
||||
# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
|
||||
# data_name: (address, size_byte)
|
||||
# http://doc.feetech.cn/#/prodinfodownload?srcType=FT-SMS-STS-emanual-229f4476422d4059abfb1cb0
|
||||
STS_SMS_SERIES_CONTROL_TABLE = {
|
||||
# EPROM
|
||||
"Firmware_Major_Version": FIRMWARE_MAJOR_VERSION, # read-only
|
||||
|
@ -36,7 +35,7 @@ STS_SMS_SERIES_CONTROL_TABLE = {
|
|||
"Protective_Torque": (34, 1),
|
||||
"Protection_Time": (35, 1),
|
||||
"Overload_Torque": (36, 1),
|
||||
"Speed_closed_loop_P_proportional_coefficient": (37, 1),
|
||||
"Velocity_closed_loop_P_proportional_coefficient": (37, 1),
|
||||
"Over_Current_Protection_Time": (38, 1),
|
||||
"Velocity_closed_loop_I_integral_coefficient": (39, 1),
|
||||
# SRAM
|
||||
|
@ -44,21 +43,30 @@ STS_SMS_SERIES_CONTROL_TABLE = {
|
|||
"Acceleration": (41, 1),
|
||||
"Goal_Position": (42, 2),
|
||||
"Goal_Time": (44, 2),
|
||||
"Goal_Speed": (46, 2),
|
||||
"Goal_Velocity": (46, 2),
|
||||
"Torque_Limit": (48, 2),
|
||||
"Lock": (55, 1),
|
||||
"Present_Position": (56, 2), # read-only
|
||||
"Present_Speed": (58, 2), # read-only
|
||||
"Present_Velocity": (58, 2), # read-only
|
||||
"Present_Load": (60, 2), # read-only
|
||||
"Present_Voltage": (62, 1), # read-only
|
||||
"Present_Temperature": (63, 1), # read-only
|
||||
"Status": (65, 1), # read-only
|
||||
"Moving": (66, 1), # read-only
|
||||
"Present_Current": (69, 2), # read-only
|
||||
# Not in the Memory Table
|
||||
"Maximum_Acceleration": (85, 2),
|
||||
"Goal_Position_2": (71, 2), # read-only
|
||||
# Factory
|
||||
"Moving_Velocity": (80, 1),
|
||||
"Moving_Velocity_Threshold": (80, 1),
|
||||
"DTs": (81, 1), # (ms)
|
||||
"Velocity_Unit_factor": (82, 1),
|
||||
"Hts": (83, 1), # (ns) valid for firmware >= 2.54, other versions keep 0
|
||||
"Maximum_Velocity_Limit": (84, 1),
|
||||
"Maximum_Acceleration": (85, 1),
|
||||
"Acceleration_Multiplier ": (86, 1), # Acceleration multiplier in effect when acceleration is 0
|
||||
}
|
||||
|
||||
# http://doc.feetech.cn/#/prodinfodownload?srcType=FT-SCSCL-emanual-cbcc8ab2e3384282a01d4bf3
|
||||
SCS_SERIES_CONTROL_TABLE = {
|
||||
# EPROM
|
||||
"Firmware_Major_Version": FIRMWARE_MAJOR_VERSION, # read-only
|
||||
|
@ -66,7 +74,7 @@ SCS_SERIES_CONTROL_TABLE = {
|
|||
"Model_Number": MODEL_NUMBER, # read-only
|
||||
"ID": (5, 1),
|
||||
"Baud_Rate": (6, 1),
|
||||
"Return_Delay": (7, 1),
|
||||
"Return_Delay_Time": (7, 1),
|
||||
"Response_Status_Level": (8, 1),
|
||||
"Min_Position_Limit": (9, 2),
|
||||
"Max_Position_Limit": (11, 2),
|
||||
|
@ -90,38 +98,45 @@ SCS_SERIES_CONTROL_TABLE = {
|
|||
"Acceleration": (41, 1),
|
||||
"Goal_Position": (42, 2),
|
||||
"Running_Time": (44, 2),
|
||||
"Goal_Speed": (46, 2),
|
||||
"Goal_Velocity": (46, 2),
|
||||
"Lock": (48, 1),
|
||||
"Present_Position": (56, 2), # read-only
|
||||
"Present_Speed": (58, 2), # read-only
|
||||
"Present_Velocity": (58, 2), # read-only
|
||||
"Present_Load": (60, 2), # read-only
|
||||
"Present_Voltage": (62, 1), # read-only
|
||||
"Present_Temperature": (63, 1), # read-only
|
||||
"Sync_Write_Flag": (64, 1), # read-only
|
||||
"Status": (65, 1), # read-only
|
||||
"Moving": (66, 1), # read-only
|
||||
# Factory
|
||||
"PWM_Maximum_Step": (78, 1),
|
||||
"Moving_Velocity_Threshold*50": (79, 1),
|
||||
"DTs": (80, 1), # (ms)
|
||||
"Minimum_Velocity_Limit*50": (81, 1),
|
||||
"Maximum_Velocity_Limit*50": (82, 1),
|
||||
"Acceleration_2": (83, 1), # don't know what that is
|
||||
}
|
||||
|
||||
STS_SMS_SERIES_BAUDRATE_TABLE = {
|
||||
0: 1_000_000,
|
||||
1: 500_000,
|
||||
2: 250_000,
|
||||
3: 128_000,
|
||||
4: 115_200,
|
||||
5: 57_600,
|
||||
6: 38_400,
|
||||
7: 19_200,
|
||||
1_000_000: 0,
|
||||
500_000: 1,
|
||||
250_000: 2,
|
||||
128_000: 3,
|
||||
115_200: 4,
|
||||
57_600: 5,
|
||||
38_400: 6,
|
||||
19_200: 7,
|
||||
}
|
||||
|
||||
SCS_SERIES_BAUDRATE_TABLE = {
|
||||
0: 1_000_000,
|
||||
1: 500_000,
|
||||
2: 250_000,
|
||||
3: 128_000,
|
||||
4: 115_200,
|
||||
5: 57_600,
|
||||
6: 38_400,
|
||||
7: 19_200,
|
||||
1_000_000: 0,
|
||||
500_000: 1,
|
||||
250_000: 2,
|
||||
128_000: 3,
|
||||
115_200: 4,
|
||||
57_600: 5,
|
||||
38_400: 6,
|
||||
19_200: 7,
|
||||
}
|
||||
|
||||
MODEL_CONTROL_TABLE = {
|
||||
|
@ -157,7 +172,7 @@ MODEL_BAUDRATE_TABLE = {
|
|||
# Sign-Magnitude encoding bits
|
||||
STS_SMS_SERIES_ENCODINGS_TABLE = {
|
||||
"Homing_Offset": 11,
|
||||
"Goal_Speed": 15,
|
||||
"Goal_Velocity": 15,
|
||||
}
|
||||
|
||||
MODEL_ENCODING_TABLE = {
|
||||
|
|
|
@ -255,6 +255,7 @@ class MotorsBus(abc.ABC):
|
|||
"""
|
||||
|
||||
available_baudrates: list[int]
|
||||
default_baudrate: int
|
||||
default_timeout: int
|
||||
model_baudrate_table: dict[str, dict]
|
||||
model_ctrl_table: dict[str, dict]
|
||||
|
@ -414,6 +415,11 @@ class MotorsBus(abc.ABC):
|
|||
f"{self.__class__.__name__}('{self.port}') is already connected. Do not call `{self.__class__.__name__}.connect()` twice."
|
||||
)
|
||||
|
||||
self._connect(handshake)
|
||||
self.set_timeout()
|
||||
logger.debug(f"{self.__class__.__name__} connected.")
|
||||
|
||||
def _connect(self, handshake: bool = True) -> None:
|
||||
try:
|
||||
if not self.port_handler.openPort():
|
||||
raise OSError(f"Failed to open port '{self.port}'.")
|
||||
|
@ -425,9 +431,6 @@ class MotorsBus(abc.ABC):
|
|||
"\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
|
||||
) from e
|
||||
|
||||
self.set_timeout()
|
||||
logger.debug(f"{self.__class__.__name__} connected.")
|
||||
|
||||
@abc.abstractmethod
|
||||
def _handshake(self) -> None:
|
||||
pass
|
||||
|
@ -435,13 +438,7 @@ class MotorsBus(abc.ABC):
|
|||
@classmethod
|
||||
def scan_port(cls, port: str, *args, **kwargs) -> dict[int, list[int]]:
|
||||
bus = cls(port, {}, *args, **kwargs)
|
||||
try:
|
||||
bus.port_handler.openPort()
|
||||
except (FileNotFoundError, OSError, serial.SerialException) as e:
|
||||
raise ConnectionError(
|
||||
f"Could not connect to port '{port}'. Make sure you are using the correct port."
|
||||
"\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
|
||||
) from e
|
||||
bus._connect(handshake=False)
|
||||
baudrate_ids = {}
|
||||
for baudrate in tqdm(bus.available_baudrates, desc="Scanning port"):
|
||||
bus.set_baudrate(baudrate)
|
||||
|
@ -452,6 +449,37 @@ class MotorsBus(abc.ABC):
|
|||
|
||||
return baudrate_ids
|
||||
|
||||
def setup_motor(
|
||||
self, motor: str, initial_baudrate: int | None = None, initial_id: int | None = None
|
||||
) -> None:
|
||||
if not self.is_connected:
|
||||
self._connect(handshake=False)
|
||||
|
||||
if initial_baudrate is None:
|
||||
initial_baudrate, initial_id = self._find_single_motor(motor)
|
||||
|
||||
if initial_id is None:
|
||||
_, initial_id = self._find_single_motor(motor, initial_baudrate)
|
||||
|
||||
model = self.motors[motor].model
|
||||
target_id = self.motors[motor].id
|
||||
self.set_baudrate(initial_baudrate)
|
||||
|
||||
# Set ID
|
||||
addr, length = get_address(self.model_ctrl_table, "ID", model)
|
||||
self._write(addr, length, initial_id, target_id)
|
||||
|
||||
# Set Baudrate
|
||||
addr, length = get_address(self.model_ctrl_table, "Baud_Rate", model)
|
||||
baudrate_value = self.model_baudrate_table[model][self.default_baudrate]
|
||||
self._write(addr, length, target_id, baudrate_value)
|
||||
|
||||
self.set_baudrate(self.default_baudrate)
|
||||
|
||||
@abc.abstractmethod
|
||||
def _find_single_motor(self, motor: str, initial_baudrate: int | None) -> tuple[int, int]:
|
||||
pass
|
||||
|
||||
@abc.abstractmethod
|
||||
def configure_motors(self) -> None:
|
||||
pass
|
||||
|
@ -492,35 +520,13 @@ class MotorsBus(abc.ABC):
|
|||
def is_calibrated(self) -> bool:
|
||||
return self.calibration == self.read_calibration()
|
||||
|
||||
@abc.abstractmethod
|
||||
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)
|
||||
|
||||
try:
|
||||
drive_modes = self.sync_read("Drive_Mode", normalize=False)
|
||||
except KeyError:
|
||||
drive_modes = dict.fromkeys(self.names, 0)
|
||||
|
||||
calibration = {}
|
||||
for name, motor in self.motors.items():
|
||||
calibration[name] = MotorCalibration(
|
||||
id=motor.id,
|
||||
drive_mode=drive_modes[name],
|
||||
homing_offset=offsets[name],
|
||||
range_min=mins[name],
|
||||
range_max=maxes[name],
|
||||
)
|
||||
|
||||
return calibration
|
||||
pass
|
||||
|
||||
@abc.abstractmethod
|
||||
def write_calibration(self, calibration_dict: dict[str, MotorCalibration]) -> 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)
|
||||
|
||||
self.calibration = calibration_dict
|
||||
pass
|
||||
|
||||
def reset_calibration(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
|
||||
if motors is None:
|
||||
|
|
|
@ -122,7 +122,7 @@ class KochFollower(Robot):
|
|||
|
||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
||||
unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except {full_turn_motors} sequentially through their entire "
|
||||
"ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -672,7 +672,7 @@ class LeKiwi:
|
|||
"""
|
||||
Reads the raw speeds for all wheels. Returns a dictionary with motor names:
|
||||
"""
|
||||
raw_speeds = self.motor_bus.read("Present_Speed", self.motor_ids)
|
||||
raw_speeds = self.motor_bus.read("Present_Velocity", self.motor_ids)
|
||||
return {
|
||||
"left_wheel": int(raw_speeds[0]),
|
||||
"back_wheel": int(raw_speeds[1]),
|
||||
|
@ -684,9 +684,9 @@ class LeKiwi:
|
|||
Sends raw velocity commands (16-bit encoded values) directly to the motor bus.
|
||||
The order of speeds must correspond to self.motor_ids.
|
||||
"""
|
||||
self.motor_bus.write("Goal_Speed", command_speeds, self.motor_ids)
|
||||
self.motor_bus.write("Goal_Velocity", command_speeds, self.motor_ids)
|
||||
|
||||
def stop(self):
|
||||
"""Stops the robot by setting all motor speeds to zero."""
|
||||
self.motor_bus.write("Goal_Speed", [0, 0, 0], self.motor_ids)
|
||||
self.motor_bus.write("Goal_Velocity", [0, 0, 0], self.motor_ids)
|
||||
print("Motors stopped.")
|
||||
|
|
|
@ -684,7 +684,7 @@ class LeKiwi:
|
|||
"""
|
||||
Reads the raw speeds for all wheels. Returns a dictionary with motor names:
|
||||
"""
|
||||
raw_speeds = self.motor_bus.read("Present_Speed", self.motor_ids)
|
||||
raw_speeds = self.motor_bus.read("Present_Velocity", self.motor_ids)
|
||||
return {
|
||||
"left_wheel": int(raw_speeds[0]),
|
||||
"back_wheel": int(raw_speeds[1]),
|
||||
|
@ -696,9 +696,9 @@ class LeKiwi:
|
|||
Sends raw velocity commands (16-bit encoded values) directly to the motor bus.
|
||||
The order of speeds must correspond to self.motor_ids.
|
||||
"""
|
||||
self.motor_bus.write("Goal_Speed", command_speeds, self.motor_ids)
|
||||
self.motor_bus.write("Goal_Velocity", command_speeds, self.motor_ids)
|
||||
|
||||
def stop(self):
|
||||
"""Stops the robot by setting all motor speeds to zero."""
|
||||
self.motor_bus.write("Goal_Speed", [0, 0, 0], self.motor_ids)
|
||||
self.motor_bus.write("Goal_Velocity", [0, 0, 0], self.motor_ids)
|
||||
print("Motors stopped.")
|
||||
|
|
|
@ -121,7 +121,7 @@ class SO100Follower(Robot):
|
|||
|
||||
full_turn_motor = "wrist_roll"
|
||||
unknown_range_motors = [name for name in self.arm.names if name != full_turn_motor]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except '{full_turn_motor}' sequentially through their "
|
||||
"entire ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -117,7 +117,7 @@ class ViperX(Robot):
|
|||
|
||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
||||
unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except {full_turn_motors} sequentially through their entire "
|
||||
"ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -102,7 +102,7 @@ class KochLeader(Teleoperator):
|
|||
|
||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
||||
unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except {full_turn_motors} sequentially through their "
|
||||
"entire ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -96,7 +96,7 @@ class SO100Leader(Teleoperator):
|
|||
|
||||
full_turn_motor = "wrist_roll"
|
||||
unknown_range_motors = [name for name in self.arm.names if name != full_turn_motor]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except '{full_turn_motor}' sequentially through their "
|
||||
"entire ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -99,7 +99,7 @@ class WidowX(Teleoperator):
|
|||
|
||||
full_turn_motors = ["shoulder_pan", "wrist_roll"]
|
||||
unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
|
||||
logger.info(
|
||||
print(
|
||||
f"Move all joints except {full_turn_motors} sequentially through their "
|
||||
"entire ranges of motion.\nRecording positions. Press ENTER to stop..."
|
||||
)
|
||||
|
|
|
@ -132,7 +132,10 @@ class MockMotorsBus(MotorsBus):
|
|||
|
||||
def _assert_protocol_is_compatible(self, instruction_name): ...
|
||||
def _handshake(self): ...
|
||||
def _find_single_motor(self, motor, initial_baudrate): ...
|
||||
def configure_motors(self): ...
|
||||
def read_calibration(self): ...
|
||||
def write_calibration(self, calibration_dict): ...
|
||||
def disable_torque(self, motors): ...
|
||||
def enable_torque(self, motors): ...
|
||||
def _get_half_turn_homings(self, positions): ...
|
||||
|
|
Loading…
Reference in New Issue