From c717d52e61684971d3cf0a894e645b31947e2e23 Mon Sep 17 00:00:00 2001 From: HanaeRateau Date: Mon, 16 Mar 2026 15:02:43 +0100 Subject: [PATCH 01/27] Refactors to have different models --- .../_dynamixelmotorsparameters.py | 425 ++++++++-- dynamixelmotorsapi/_motorgroup.py | 745 +++++++++--------- dynamixelmotorsapi/dynamixelmotors.py | 317 ++++---- examples/motors_example.py | 30 +- pyproject.toml | 6 +- uv.lock | 188 ++++- 6 files changed, 1084 insertions(+), 627 deletions(-) diff --git a/dynamixelmotorsapi/_dynamixelmotorsparameters.py b/dynamixelmotorsapi/_dynamixelmotorsparameters.py index f381fa0..d1832c3 100644 --- a/dynamixelmotorsapi/_dynamixelmotorsparameters.py +++ b/dynamixelmotorsapi/_dynamixelmotorsparameters.py @@ -1,92 +1,357 @@ -#********* DYNAMIXEL Model definition ********* -# https://emanual.robotis.com/docs/en/dxl/p/pm42-010-s260-r/ - -#***** (Use only one definition at a time) ***** -MY_DXL = 'X_SERIES' # X330 (5.0 V recommended), X430, X540, 2X430 -# MY_DXL = 'MX_SERIES' # MX series with 2.0 firmware update. -# MY_DXL = 'PRO_SERIES' # H54, H42, M54, M42, L54, L42 -# MY_DXL = 'PRO_A_SERIES' # PRO series with (A) firmware update. -# MY_DXL = 'P_SERIES' # PH54, PH42, PM54 -# MY_DXL = 'XL320' # [WARNING] Operating Voltage : 7.4V - +from dataclasses import dataclass +from math import pi +from typing import Dict, Optional # DYNAMIXEL Protocol Version (1.0 / 2.0) # https://emanual.robotis.com/docs/en/dxl/protocol2/ -PROTOCOL_VERSION = 2.0 +PROTOCOL_VERSION = 2.0 -# Make sure that each DYNAMIXEL ID should have unique ID. +BAUDRATE = 1000000 +# Generic motor parameters +TORQUE_ENABLE = 1 +TORQUE_DISABLE = 0 +VELOCITY_MODE = 1 +POSITION_MODE = 3 +EXT_POSITION_MODE = 4 -DXL_IDs = (0, 1, 2, 3) -import serial.tools.list_ports as list_ports +@dataclass(frozen=True) +class ModelConfig: + """ + Hardware-level register map and resolution for a Dynamixel motor model. + Frozen because these are fixed hardware constants — never mutated at runtime. -# Use the actual port assigned to the U2D2. -# ex) Windows: "COM*", Linux: "/dev/ttyUSB*", Mac: "/dev/tty.usbserial-*" -BAUDRATE = 1000000 + To add a custom model at runtime, use register_model() rather than + editing this file. + """ + model: str + series: str + url: str + resolution: Optional[int] = None + addr_torque_enable: Optional[int] = None + addr_operating_mode: Optional[int] = None + addr_goal_position: Optional[int] = None + len_goal_position: Optional[int] = None + addr_goal_velocity: Optional[int] = None + len_goal_velocity: Optional[int] = None + addr_present_position: Optional[int] = None + len_present_position: Optional[int] = None + addr_present_velocity: Optional[int] = None + len_present_velocity: Optional[int] = None + addr_velocity_profile: Optional[int] = None + addr_moving: Optional[int] = None + addr_moving_status: Optional[int] = None + addr_velocity_trajectory: Optional[int] = None + len_velocity_trajectory: Optional[int] = None + addr_position_trajectory: Optional[int] = None + len_position_trajectory: Optional[int] = None + addr_position_p_gain: Optional[int] = None + len_position_p_gain: Optional[int] = None + addr_position_i_gain: Optional[int] = None + len_position_i_gain: Optional[int] = None + addr_position_d_gain: Optional[int] = None + len_position_d_gain: Optional[int] = None + min_position_value: Optional[int] = None + max_position_value: Optional[int] = None -# Generic motor parameters + @property + def rad_to_pulse(self) -> float: + """Conversion factor from radians to pulses, derived from resolution.""" + return self.resolution / (2 * pi) + + +# Registry of all supported model configs. +# Add new model here, or at runtime via register_model(). +MODELS_CONFIGS: Dict[str, ModelConfig] = { + + "X_SERIES": ModelConfig( + model = "X_SERIES", + series = "X_SERIES", + url = "https://emanual.robotis.com/docs/en/dxl/x/xm430-w210/", + resolution = 4096, + addr_torque_enable = 64, + addr_operating_mode = 11, + addr_goal_position = 116, + len_goal_position = 4, + addr_goal_velocity = 104, + len_goal_velocity = 4, + addr_present_position = 132, + len_present_position = 4, + addr_present_velocity = 128, + len_present_velocity = 4, + addr_velocity_profile = 112, + addr_moving = 122, + addr_moving_status = 123, + addr_velocity_trajectory = 136, + len_velocity_trajectory = 4, + addr_position_trajectory = 140, + len_position_trajectory = 4, + addr_position_p_gain = 84, + len_position_p_gain = 2, + addr_position_i_gain = 82, + len_position_i_gain = 2, + addr_position_d_gain = 80, + len_position_d_gain = 2, + min_position_value = 0, + max_position_value = 4095, + ), + + "MX_SERIES": ModelConfig( + # MX series with 2.0 firmware — same register map as X_SERIES + model = "MX_SERIES", + series = "MX_SERIES", + url = "https://emanual.robotis.com/docs/en/dxl/mx/mx-106-2/", + resolution = 4096, + addr_torque_enable = 64, + addr_operating_mode = 11, + addr_goal_position = 116, + len_goal_position = 4, + addr_goal_velocity = 104, + len_goal_velocity = 4, + addr_present_position = 132, + len_present_position = 4, + addr_present_velocity = 128, + len_present_velocity = 4, + addr_velocity_profile = 112, + addr_moving = 122, + addr_moving_status = 123, + addr_velocity_trajectory = 136, + len_velocity_trajectory = 4, + addr_position_trajectory = 140, + len_position_trajectory = 4, + addr_position_p_gain = 84, + len_position_p_gain = 2, + addr_position_i_gain = 82, + len_position_i_gain = 2, + addr_position_d_gain = 80, + len_position_d_gain = 2, + min_position_value = 0, + max_position_value = 4095, + ), + + "P_SERIES": ModelConfig( + model = "P_SERIES", + series = "P_SERIES", + url = "https://emanual.robotis.com/docs/en/dxl/p/pm42-010-s260-r/", + resolution = 501923, + addr_torque_enable = 512, + addr_operating_mode = 11, + addr_goal_position = 564, + len_goal_position = 4, + addr_goal_velocity = 552, + len_goal_velocity = 4, + addr_present_position = 580, + len_present_position = 4, + addr_present_velocity = 576, + len_present_velocity = 4, + addr_velocity_profile = 560, + addr_moving = 570, + addr_moving_status = 571, + addr_velocity_trajectory = 584, + len_velocity_trajectory = 4, + addr_position_trajectory = 588, + len_position_trajectory = 4, + addr_position_p_gain = 532, + len_position_p_gain = 2, + addr_position_i_gain = 530, + len_position_i_gain = 2, + addr_position_d_gain = 528, + len_position_d_gain = 2, + min_position_value = -150000, + max_position_value = 150000, + ), +} + + +def register_model(config: ModelConfig, overwrite: bool = False) -> None: + """ + Register a custom modelConfig in the global registry at runtime. + + Use this for motor model not listed in this file, without needing to + modify the library source. + + Args: + config: A fully constructed modelConfig instance. + overwrite: If False (default), raises ValueError if the model name + is already registered. Set to True to replace an existing entry. + + Example: + ```python + from dynamixelmotorsapi._dynamixelmotorsparameters import modelConfig, register_model + + my_model = modelConfig(model="MY_CUSTOM_model", resolution=8192, ...) + register_model(my_model) + ``` + """ + if config.model in MODELS_CONFIGS and not overwrite: + raise ValueError( + f"model '{config.model}' is already registered. " + f"Pass overwrite=True to replace it." + ) + MODELS_CONFIGS[config.model] = config + + +def register_model_from_dict(data: dict, overwrite: bool = False) -> ModelConfig: + """ + Build a modelConfig from a dict and register it. + + Validates that all required fields are present and reports all missing + fields at once rather than failing on the first one. + + Args: + data: dict containing all ModelConfig fields. + overwrite: passed through to register_model. + + Returns: + The registered ModelConfig instance. + + Raises: + ValueError: if any required fields are missing, listing all of them. + """ + import dataclasses + required_fields = {f.name for f in dataclasses.fields(ModelConfig)} + missing = required_fields - data.keys() + if missing: + raise ValueError( + f"Missing required fields for ModelConfig: {sorted(missing)}" + ) + config = ModelConfig(**{k: data[k] for k in required_fields}) + register_model(config, overwrite=overwrite) + return config + + +def register_model_from_json(path: str, overwrite: bool = False) -> list: + """ + Load a JSON file containing a list of model config dicts and register + each one into model_CONFIGS. + + Args: + path: path to a JSON file containing a list of ModelConfig dicts. + overwrite: passed through to register_model for each entry. + + Returns: + List of registered ModelConfig instances. + + Example JSON: + ```json + [ + { + "model": "MY_CUSTOM_MODEL", + "resolution": 8192, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + ... + } + ] + ``` + """ + import json + with open(path) as f: + entries = json.load(f) + if not isinstance(entries, list): + raise ValueError( + f"Expected a JSON array of model configs, got {type(entries).__name__}." + ) + [register_model_from_dict(entry, overwrite=overwrite) for entry in entries] + return MODELS_CONFIGS + +@dataclass +class MotorConfig: + """ + Per-motor configuration. Holds the varying parameters for a single motor + alongside a reference to its model hardware config. + + The model can be specified in two ways: + - By name (str): looked up in the global model_CONFIGS registry. + - Directly (ModelConfig): for one-off or custom model without registering globally. + + If both are provided, they must refer to the same model name. + + Example (from name): + ```python + MotorConfig(id=0, model="XM430-W210", length_to_rad=0.05, pulse_center=2048, max_vel=1000) + ``` + + Example (ModelConfig directly): + ```python + MotorConfig(id=0, model_config=my_config, length_to_rad=0.05, pulse_center=2048, max_vel=1000) + ``` + + Example JSON (name-based, for from_dict / from_json): + ```json + { + "id": 0, + "model": "XM430-W210", + "length_to_rad": 0.05, + "pulse_center": 2048, + "max_vel": 1000 + } + ``` + """ + id: int + length_to_rad: float + pulse_center: int + max_vel: float + + # Provide one of these — not both (unless consistent), not neither + model: Optional[str] = None + model_config: Optional[ModelConfig] = None + + def __post_init__(self): + if self.model_config is not None and self.model is not None: + if self.model_config.model != self.model: + raise ValueError( + f"Conflicting model: model='{self.model}' but " + f"model_config.model='{self.model_config.model}'. " + f"Provide one or the other, or ensure they match." + ) + # Both given and consistent — model_config takes precedence + return + + if self.model_config is not None: + # ModelConfig provided directly — set model name for reference + self.model = self.model_config.model + return + + if self.model is not None: + # Model name provided — look up in registry + if self.model not in MODELS_CONFIGS: + raise ValueError( + f"Unknown motor model '{self.model}'. " + f"Available: {list(MODELS_CONFIGS.keys())}. " + f"Use register_model() to add a custom model, " + f"or pass a ModelConfig directly." + ) + self.model_config = MODELS_CONFIGS[self.model] + return + + raise ValueError( + "Either 'model' (str) or 'model_config' (ModelConfig) must be provided." + ) + + @property + def rad_to_pulse(self) -> float: + """Derived from the model resolution.""" + return self.model_config.rad_to_pulse + + @property + def length_to_pulse(self) -> float: + """Derived from length_to_rad and model resolution.""" + return self.length_to_rad * self.rad_to_pulse -TORQUE_ENABLE = 1 # Value for enabling the torque -TORQUE_DISABLE = 0 # Value for disabling the torque -VELOCITY_MODE = 1 -POSITION_MODE = 3 -EXT_POSITION_MODE = 4 -if MY_DXL == 'X_SERIES' or MY_DXL == 'MX_SERIES': #from https://emanual.robotis.com/docs/en/dxl/x/xm430-w210/ - ADDR_TORQUE_ENABLE = 64 - ADDR_GOAL_POSITION = 116 - LEN_GOAL_POSITION = 4 # Data Byte Length - ADDR_GOAL_VELOCITY = 104 - LEN_GOAL_VELOCITY = 4 # Data Byte Length - ADDR_PRESENT_POSITION = 132 - LEN_PRESENT_POSITION = 4 # Data Byte Length - ADDR_PRESENT_VELOCITY = 128 - LEN_PRESENT_VELOCITY = 4 # Data Byte Length - DXL_MINIMUM_POSITION_VALUE = 0 # Refer to the Minimum Position Limit of product eManual - DXL_MAXIMUM_POSITION_VALUE = 4095 # Refer to the Maximum Position Limit of product eManual - ADDR_OPERATING_MODE = 11 - ADDR_VELOCITY_PROFILE = 112 - ADDR_MOVING = 122 - ADDR_MOVING_STATUS = 123 - ADDR_VELOCITY_TRAJECTORY = 136 - LEN_VELOCITY_TRAJECTORY = 4 - ADDR_POSITION_TRAJECTORY = 140 - LEN_POSITION_TRAJECTORY = 4 - ADDR_POSITION_P_GAIN = 84 - LEN_POSITION_P_GAIN = 2 - ADDR_POSITION_I_GAIN = 82 - LEN_POSITION_I_GAIN = 2 - ADDR_POSITION_D_GAIN = 80 - LEN_POSITION_D_GAIN = 2 - -elif MY_DXL == 'PRO_SERIES': - ADDR_TORQUE_ENABLE = 562 # Control table address is different in DYNAMIXEL model - ADDR_GOAL_POSITION = 596 - LEN_GOAL_POSITION = 4 - ADDR_PRESENT_POSITION = 611 - LEN_PRESENT_POSITION = 4 - DXL_MINIMUM_POSITION_VALUE = -150000 # Refer to the Minimum Position Limit of product eManual - DXL_MAXIMUM_POSITION_VALUE = 150000 # Refer to the Maximum Position Limit of product eManual - raise Exception("not defined yet") - -elif MY_DXL == 'P_SERIES' or MY_DXL == 'PRO_A_SERIES': #from https://emanual.robotis.com/docs/en/dxl/p/pm42-010-s260-r/ - ADDR_TORQUE_ENABLE = 512 # Control table address is different in DYNAMIXEL model - ADDR_GOAL_POSITION = 564 - ADDR_GOAL_VELOCITY = 552 - LEN_GOAL_POSITION = 4 # Data Byte Length - ADDR_PRESENT_POSITION = 580 - LEN_PRESENT_POSITION = 4 # Data Byte Length - ADDR_PRESENT_VELOCITY = 576 - LEN_PRESENT_VELOCITY = 4 # Data Byte Length - DXL_MINIMUM_POSITION_VALUE = -150000 # Refer to the Minimum Position Limit of product eManual - DXL_MAXIMUM_POSITION_VALUE = 150000 # Refer to the Maximum Position Limit of product eManual - ADDR_OPERATING_MODE = 11 - ADDR_VELOCITY_PROFILE = 560 - ADDR_MOVING = 570 - ADDR_MOVING_STATUS = 571 - ADDR_VELOCITY_TRAJECTORY = 584 - LEN_VELOCITY_TRAJECTORY = 4 - ADDR_POSITION_TRAJECTORY = 588 - LEN_POSITION_TRAJECTORY = 4 + @classmethod + def from_dict(cls, data: dict) -> "MotorConfig": + """ + Instantiate from a dict. The model must be specified as a string name + referring to a registered entry in MODEL_CONFIGS. + """ + return cls( + id = data["id"], + model = data["model"], + length_to_rad = data["length_to_rad"], + pulse_center = data["pulse_center"], + max_vel = data["max_vel"], + ) \ No newline at end of file diff --git a/dynamixelmotorsapi/_motorgroup.py b/dynamixelmotorsapi/_motorgroup.py index 6f83808..f01ba75 100644 --- a/dynamixelmotorsapi/_motorgroup.py +++ b/dynamixelmotorsapi/_motorgroup.py @@ -1,10 +1,20 @@ import ctypes +from threading import Lock +from math import pi +from typing import List, Dict +from itertools import groupby + +import serial.tools.list_ports as list_ports from dynamixel_sdk import * -import dynamixelmotorsapi._dynamixelmotorsparameters as MotorsParametersTemplate +from dynamixelmotorsapi._dynamixelmotorsparameters import ( + MotorConfig, ModelConfig, PROTOCOL_VERSION, BAUDRATE, + TORQUE_ENABLE, TORQUE_DISABLE, VELOCITY_MODE, POSITION_MODE, EXT_POSITION_MODE +) from dynamixelmotorsapi._logging_config import logger + def listMotors(): """ List all the FTDI devices connected to the computer. @@ -23,62 +33,60 @@ def listMotors(): elif p.serial_number is not None and "FTDI" in p.serial_number: ports.append(p.device) - if ports is None or len(ports) == 0: + if not ports: logger.warning("No motor found. Please check the connection.") - return ports return ports def getDevicePort(entry, method="manufacturer"): - """ - Get the device port based on the device name and method. This will get the first FTDI device found. - - Args: - entry (str): The name of the device to search for. - method (str): The method to use for searching (default is "manufacturer"). - Returns: - The first port of the device if found, otherwise None. - """ - ports = [] - comports = serial.tools.list_ports.comports() - - if comports is None or len(comports) == 0: - logger.error("Serial ports check failed, list of ports is empty.") - return - - if method == "manufacturer": - ports = [p for p in comports if p.manufacturer is not None and entry in p.manufacturer] - if method == "description": - ports = [p for p in comports if p.description is not None and entry in p.description] - if method == "serial_number": - ports = [p for p in comports if p.serial_number is not None and entry in p.serial_number] - - if not ports: - logger.error("No serial port found with " + method + " = " + entry) - return - - if len(ports) > 1: - logger.warning("Multiple port found with " + method + " = " + entry + ". Using the first.") - - logger.debug("Found port with " + method + " = " + entry + ": \n" + - "device : " + ports[0].device + "\n" + - "manufacturer : " + ports[0].manufacturer + "\n" + - "description : " + ports[0].description + "\n" + - "serial number : " + ports[0].serial_number - ) - return ports[0].device - + """ + Get the device port based on the device name and method. -def _valToArray( val): - """Convert a 32-bit integer to a list of 4 bytes. Args: - val (int): The 32-bit integer to convert. + entry (str): The name of the device to search for. + method (str): The method to use for searching (default is "manufacturer"). + Returns: - list of bytes: The list of 4 bytes representing the integer. + The first port of the device if found, otherwise None. """ - return [DXL_LOBYTE(DXL_LOWORD(val)), DXL_HIBYTE(DXL_LOWORD(val)), DXL_LOBYTE(DXL_HIWORD(val)), - DXL_HIBYTE(DXL_HIWORD(val))] + comports = serial.tools.list_ports.comports() + + if not comports: + logger.error("Serial ports check failed, list of ports is empty.") + return None + + if method == "manufacturer": + ports = [p for p in comports if p.manufacturer is not None and entry in p.manufacturer] + elif method == "description": + ports = [p for p in comports if p.description is not None and entry in p.description] + elif method == "serial_number": + ports = [p for p in comports if p.serial_number is not None and entry in p.serial_number] + else: + ports = [] + + if not ports: + logger.error(f"No serial port found with {method} = {entry}") + return None + + if len(ports) > 1: + logger.warning(f"Multiple ports found with {method} = {entry}. Using the first.") + + p = ports[0] + logger.debug( + f"Found port with {method} = {entry}:\n" + f" device: {p.device}\n" + f" manufacturer: {p.manufacturer}\n" + f" description: {p.description}\n" + f" serial number: {p.serial_number}" + ) + return p.device + + +def _valToArray(val): + """Convert a 32-bit integer to a list of 4 bytes.""" + return [DXL_LOBYTE(DXL_LOWORD(val)), DXL_HIBYTE(DXL_LOWORD(val)), + DXL_LOBYTE(DXL_HIWORD(val)), DXL_HIBYTE(DXL_HIWORD(val))] def _valTo2Bytes(val): @@ -87,434 +95,427 @@ def _valTo2Bytes(val): class DisconnectedException(Exception): - """Custom exception for disconnected motors.""" + """Raised when an operation is attempted on a disconnected motor group.""" def __init__(self): - message = "MotorGroup is not connected. It is either disconnected or permission denied." - super().__init__(message) + super().__init__( + "MotorGroup is not connected. It is either disconnected or permission denied." + ) + class MotorGroup: + """ + Controls a group of Dynamixel motors, supporting heterogeneous models. - def __init__(self, parameters: MotorsParametersTemplate) -> None: + Motors are grouped internally by models so that GroupSyncRead/Write — + which require a uniform address and data length — operate correctly even + when motors from different models (with different register maps) are mixed. - self.parameters = parameters + All public read methods return values ordered by the original motor_configs + list, regardless of internal grouping. + """ + + def __init__(self, motor_configs: List[MotorConfig]) -> None: + self.motorsConfig = motor_configs self.deviceName = None - self.packetHandler = PacketHandler(self.parameters.PROTOCOL_VERSION) + self.packetHandler = PacketHandler(PROTOCOL_VERSION) self.portHandler = PortHandler(self.deviceName) - self.groupReaders = {} - self.groupWriters = {} - - self.groupReaders["position"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_PRESENT_POSITION, - self.parameters.LEN_PRESENT_POSITION) - self.groupReaders["velocity"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_PRESENT_VELOCITY, - self.parameters.LEN_PRESENT_VELOCITY) - self.groupReaders["goal_position"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_GOAL_POSITION, - self.parameters.LEN_GOAL_POSITION) - self.groupReaders["goal_velocity"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_GOAL_VELOCITY, - self.parameters.LEN_GOAL_VELOCITY) - self.groupReaders["moving"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_MOVING, - 1) - self.groupReaders["moving_status"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_MOVING_STATUS, - 1) - self.groupReaders["velocity_trajectory"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_VELOCITY_TRAJECTORY, - self.parameters.LEN_VELOCITY_TRAJECTORY) - self.groupReaders["position_trajectory"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_TRAJECTORY, - self.parameters.LEN_POSITION_TRAJECTORY) - self.groupReaders["position_p_gain"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_P_GAIN, - self.parameters.LEN_POSITION_P_GAIN) - self.groupReaders["position_i_gain"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_I_GAIN, - self.parameters.LEN_POSITION_I_GAIN) - self.groupReaders["position_d_gain"] = GroupSyncRead(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_D_GAIN, - self.parameters.LEN_POSITION_D_GAIN) - - self.groupWriters["goal_position"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_GOAL_POSITION, - self.parameters.LEN_GOAL_POSITION) - self.groupWriters["goal_velocity"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_GOAL_VELOCITY, - self.parameters.LEN_GOAL_POSITION) - self.groupWriters["velocity_profile"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_VELOCITY_PROFILE, - self.parameters.LEN_GOAL_POSITION) - self.groupWriters["position_p_gain"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_P_GAIN, - self.parameters.LEN_POSITION_P_GAIN) - self.groupWriters["position_i_gain"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_I_GAIN, - self.parameters.LEN_POSITION_I_GAIN) - self.groupWriters["position_d_gain"] = GroupSyncWrite(self.portHandler, self.packetHandler, - self.parameters.ADDR_POSITION_D_GAIN, - self.parameters.LEN_POSITION_D_GAIN) - - for DXL_ID in self.parameters.DXL_IDs: - for group in self.groupReaders.values(): - group.addParam(DXL_ID) + # Group motors by models so each GroupSyncRead/Write uses a consistent + # address and length. Dict key is model name, value is list of MotorConfigs. + self._models_groups: Dict[str, List[MotorConfig]] = {} + for cfg in motor_configs: + self._models_groups.setdefault(cfg.model, []).append(cfg) + + # Per-models sync read/write groups: {model_name: {reader_name: GroupSyncRead}} + self.groupReaders: Dict[str, Dict[str, GroupSyncRead]] = {} + self.groupWriters: Dict[str, Dict[str, GroupSyncWrite]] = {} + + self._initGroups() + + # ------------------------------------------------------------------ # + # Initialisation helpers # + # ------------------------------------------------------------------ # + + def _initGroups(self): + """Create GroupSyncRead/Write objects for each models.""" + for model_name, configs in self._models_groups.items(): + sc: ModelConfig = configs[0].model_config # all share the same ModelConfig + + readers = { + "position": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_present_position, sc.len_present_position), + "velocity": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_present_velocity, sc.len_present_velocity), + "goal_position": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_goal_position, sc.len_goal_position), + "goal_velocity": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_goal_velocity, sc.len_goal_velocity), + "moving": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_moving, 1), + "moving_status": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_moving_status, 1), + "velocity_trajectory": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_velocity_trajectory, sc.len_velocity_trajectory), + "position_trajectory": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_position_trajectory, sc.len_position_trajectory), + "position_p_gain": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_position_p_gain, sc.len_position_p_gain), + "position_i_gain": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_position_i_gain, sc.len_position_i_gain), + "position_d_gain": GroupSyncRead( + self.portHandler, self.packetHandler, + sc.addr_position_d_gain, sc.len_position_d_gain), + } + + writers = { + "goal_position": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_goal_position, sc.len_goal_position), + "goal_velocity": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_goal_velocity, sc.len_goal_velocity), + "velocity_profile": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_velocity_profile, sc.len_goal_velocity), + "position_p_gain": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_position_p_gain, sc.len_position_p_gain), + "position_i_gain": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_position_i_gain, sc.len_position_i_gain), + "position_d_gain": GroupSyncWrite( + self.portHandler, self.packetHandler, + sc.addr_position_d_gain, sc.len_position_d_gain), + } + + # Register all motor IDs in this model with every reader + for cfg in configs: + for reader in readers.values(): + reader.addParam(cfg.id) + + self.groupReaders[model_name] = readers + self.groupWriters[model_name] = writers + + def _updateGroups(self): + """Propagate the new portHandler to all sync groups after reconnection.""" + for readers in self.groupReaders.values(): + for group in readers.values(): + group.port = self.portHandler + group.ph = self.packetHandler + for writers in self.groupWriters.values(): + for group in writers.values(): + group.port = self.portHandler + group.ph = self.packetHandler + + # ------------------------------------------------------------------ # + # Connection management # + # ------------------------------------------------------------------ # @property def isConnected(self): """Check if the motor group is connected.""" try: - if self.portHandler and self.portHandler.is_open and self._isDeviceDetected(): - return True + return bool(self.portHandler and self.portHandler.is_open and self._isDeviceDetected()) except Exception as e: logger.exception(f"Failed to check connection: {e}") return False - def _updateGroups(self): - """ - Update the port handler with the new device name. - """ - for group in self.groupReaders.values(): - group.port = self.portHandler - group.ph = self.packetHandler - - for group in self.groupWriters.values(): - group.port = self.portHandler - group.ph = self.packetHandler - - - def updateDeviceName(self, device_name: str=None): - """ - Update the device name based on the available ports. This will get the first FTDI device found if no device name is provided. - If no device is found, the device name will be None. - """ - self.deviceName = device_name if device_name is not None else getDevicePort("FTDI", method="manufacturer") - self.portHandler = PortHandler(self.deviceName) - self._updateGroups() - - logger.debug(f"Device name updated to: {self.deviceName}") - - return - - def _isDeviceDetected(self): for port in serial.tools.list_ports.comports(): if port.device == self.deviceName: return True return False + + def updateDeviceName(self, device_name: str = None): + """ + Update the device name. If not provided, uses the first FTDI device found. + """ + self.deviceName = device_name if device_name is not None else getDevicePort("FTDI") + self.portHandler = PortHandler(self.deviceName) + self._updateGroups() + logger.debug(f"Device name updated to: {self.deviceName}") - def _readSyncMotorsData(self, groupSyncRead:GroupSyncRead): - """Read data from the motor. - Args: - DXL_ID (int): The ID of the motor. - addr (int): The address to read from. - length (int): The length of the data to read. + def open(self) -> None: + """Open the port and set the baud rate.""" + try: + self.portHandler.openPort() + self.portHandler.setBaudRate(BAUDRATE) + except Exception as e: + raise Exception(f"Failed to open port: {e}") + - Returns: - int: The value read from the motor. + def close(self) -> None: + """Disable torque on all motors and close the port.""" + try: + for cfg in self.motorsConfig: + self.packetHandler.write1ByteTxRx( + self.portHandler, cfg.id, + cfg.model_config.addr_torque_enable, TORQUE_DISABLE + ) + self.portHandler.closePort() + self.deviceName = None + except Exception as e: + raise Exception(f"Failed to close port: {e}") + - Raises: - Exception: If the motor group is not connected or if the read operation fails. - """ + def clearPort(self) -> None: + """Clear the port buffer.""" if not self.isConnected: raise DisconnectedException() + if self.portHandler: + self.portHandler.clearPort() - dxl_comm_result = groupSyncRead.txRxPacket() - if dxl_comm_result != COMM_SUCCESS: - raise Exception(f"Failed to read data from motor: {self.packetHandler.getTxRxResult(dxl_comm_result)}") - result = list() + # ------------------------------------------------------------------ # + # Torque and operating mode # + # ------------------------------------------------------------------ # + + def enableTorque(self): + """Enable torque on all motors.""" + self._write1ByteAll( + lambda cfg: cfg.model_config.model.addr_torque_enable, TORQUE_ENABLE + ) - for DXL_ID in self.parameters.DXL_IDs: - dxl_getdata_result = groupSyncRead.isAvailable(DXL_ID, groupSyncRead.start_address, groupSyncRead.data_length) - if dxl_getdata_result != True: - return None - angle = ctypes.c_int(groupSyncRead.getData(DXL_ID, groupSyncRead.start_address, groupSyncRead.data_length)) - result.append(angle.value) + def disableTorque(self): + """Disable torque on all motors.""" + self._write1ByteAll( + lambda cfg: cfg.model_config.addr_torque_enable, TORQUE_DISABLE + ) + + + def isTorqueEnable(self) -> list: + """Return the torque enable state for each motor.""" + result = [] + for cfg in self.motorsConfig: + torque, dxl_comm_result, dxl_error = self.packetHandler.read1ByteTxRx( + self.portHandler, cfg.id, cfg.model_config.addr_torque_enable + ) + if dxl_comm_result != COMM_SUCCESS: + raise Exception(f"Failed to read torque (motor {cfg.id}): " + f"{self.packetHandler.getTxRxResult(dxl_comm_result)}") + if dxl_error != 0: + raise Exception(f"Failed to read torque (motor {cfg.id}): " + f"{self.packetHandler.getRxPacketError(dxl_error)}") + result.append(torque) return result - def __writeSyncMotorsData(self, group: GroupSyncWrite, values): - """Helper function to write data to the motors. - Args: - group (GroupSyncWrite): The group sync write object. - values (list of numbers): The values to write to the motors. + def __setOperatingMode(self, mode: int): """ - if not self.isConnected: - raise DisconnectedException() - - group.clearParam() - for index, DXL_ID in enumerate(self.parameters.DXL_IDs): - if group.data_length == 2: - data = _valTo2Bytes(values[index]) - elif group.data_length == 4: - data = _valToArray(values[index]) - else: - raise Exception(f"Unsupported data length: {group.data_length}") - group.addParam(DXL_ID, data) - group.txPacket() - - - def __write1Byte(self, paramAddress, paramValue): - if not self.isConnected: - raise DisconnectedException() - - for DXL_ID in self.parameters.DXL_IDs: - dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx(self.portHandler, DXL_ID, paramAddress, paramValue) - if dxl_comm_result != COMM_SUCCESS: - raise Exception(f"Failed to change operating mode: {self.packetHandler.getTxRxResult(dxl_comm_result)}") - elif dxl_error != 0: - raise Exception(f"Failed to change operating mode: {self.packetHandler.getTxRxResult(dxl_error)}") - else: - logger.debug("Motor Data %s changed to %s (%s,%s)" % (paramAddress, paramValue, self.deviceName, DXL_ID)) + Set the operating mode on all motors. - - def __setOperatingMode(self, mode): - """Set the operating mode of the motors. Args: - mode (int): The operating mode to set. - 0: Current Control Mode - 1: Velocity Control Mode - 3: (Default) Position Control Mode - 4: Extended Position Control Mode - 5: Current-bqsed Position Control Mode - 16: PWM Control Mode - - See https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/#operating-mode for more details. + mode: 1=Velocity, 3=Position, 4=Extended Position. + See https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/#operating-mode """ if not self.isConnected: raise DisconnectedException() - - self.__write1Byte(self.parameters.ADDR_OPERATING_MODE, mode) - + self._write1ByteAll(lambda cfg: cfg.model_config.addr_operating_mode, mode) def enableVelocityMode(self): torques = self.isTorqueEnable() - - if any(t==1 for t in torques): + if any(t == 1 for t in torques): self.disableTorque() - self.__setOperatingMode(self.parameters.VELOCITY_MODE) - if any(t==1 for t in torques): + self.__setOperatingMode(VELOCITY_MODE) + if any(t == 1 for t in torques): self.enableTorque() - def enableExtendedPositionMode(self): + def enablePositionMode(self): torques = self.isTorqueEnable() - - if any(t==1 for t in torques): + if any(t == 1 for t in torques): self.disableTorque() - self.__setOperatingMode(self.parameters.EXT_POSITION_MODE) - if any(t==1 for t in torques): + self.__setOperatingMode(POSITION_MODE) + if any(t == 1 for t in torques): self.enableTorque() - def enablePositionMode(self): + def enableExtendedPositionMode(self): torques = self.isTorqueEnable() - - if any(t==1 for t in torques): + if any(t == 1 for t in torques): self.disableTorque() - self.__setOperatingMode(self.parameters.POSITION_MODE) - if any(t==1 for t in torques): + self.__setOperatingMode(EXT_POSITION_MODE) + if any(t == 1 for t in torques): self.enableTorque() + # ------------------------------------------------------------------ # + # Low-level read / write helpers # + # ------------------------------------------------------------------ # - def setGoalVelocity(self, speeds): - """Set the goal velocity + def _write1ByteAll(self, addr_fn, value: int): + """ + Write a single byte to all motors, using each motor's own address. Args: - speeds (list of numbers): unit depends on motor type + addr_fn: callable(MotorConfig) -> int, returns the register address for that motor. + value: the byte value to write. """ - self.__writeSyncMotorsData(self.groupWriters["goal_velocity"] , speeds) + if not self.isConnected: + raise DisconnectedException() + for cfg in self.motorsConfig: + addr = addr_fn(cfg) + dxl_comm_result, dxl_error = self.packetHandler.write1ByteTxRx( + self.portHandler, cfg.id, addr, value + ) + if dxl_comm_result != COMM_SUCCESS: + raise Exception(f"Failed to write byte to motor {cfg.id} at addr {addr}: " + f"{self.packetHandler.getTxRxResult(dxl_comm_result)}") + if dxl_error != 0: + raise Exception(f"Error on motor {cfg.id} at addr {addr}: " + f"{self.packetHandler.getRxPacketError(dxl_error)}") + logger.debug(f"Motor {cfg.id}: addr {addr} set to {value}") - def setGoalPosition(self, positions): - """Set the goal position + def _readSyncMotorsData(self, reader_name: str) -> list: + """ + Read data from all motors using GroupSyncRead, per model, and return + results in the original motor_configs order. Args: - positions (list of numbers): unit = 1 pulse + reader_name: key into self.groupReaders[model]. + + Returns: + List of values in motor_configs order. """ - self.__writeSyncMotorsData(self.groupWriters["goal_position"], positions) + if not self.isConnected: + raise DisconnectedException() + # Collect results keyed by motor ID across all models + results_by_id = {} + for model_name, readers in self.groupReaders.items(): + group = readers[reader_name] + dxl_comm_result = group.txRxPacket() + if dxl_comm_result != COMM_SUCCESS: + raise Exception( + f"Failed to read '{reader_name}' for model '{model_name}': " + f"{self.packetHandler.getTxRxResult(dxl_comm_result)}" + ) + for cfg in self._models_groups[model_name]: + if not group.isAvailable(cfg.id, group.start_address, group.data_length): + raise Exception( + f"Data not available for motor {cfg.id} (model '{model_name}', " + f"reader '{reader_name}')" + ) + raw = group.getData(cfg.id, group.start_address, group.data_length) + results_by_id[cfg.id] = ctypes.c_int(raw).value - def setVelocityProfile(self, max_vel): - """Set the maximum velocities in position mode + # Return in original motor_configs order + return [results_by_id[cfg.id] for cfg in self.motorsConfig] + - Args: - positions (list of numbers): unit depends on the motor type + def __writeSyncMotorsData(self, writer_name: str, values: list): """ - self.__writeSyncMotorsData(self.groupWriters["velocity_profile"], max_vel) - - - def setPositionPGain(self, p_gains): - """Set the position P gains + Write data to all motors using GroupSyncWrite, per models. Args: - p_gains (list of numbers): unit depends on the motor type + writer_name: key into self.groupWriters[model]. + values: list of values in motor_configs order. """ - self.__writeSyncMotorsData(self.groupWriters["position_p_gain"], p_gains) + if not self.isConnected: + raise DisconnectedException() + # Map motor ID -> value from the ordered values list + values_by_id = {cfg.id: values[i] for i, cfg in enumerate(self.motorsConfig)} + + for model_name, writers in self.groupWriters.items(): # iterate through motor models in groupwriters + group = writers[writer_name] + group.clearParam() + for cfg in self._models_groups[model_name]: # get the MotorConfigs for model model_name + val = values_by_id[cfg.id] + if group.data_length == 2: + data = _valTo2Bytes(val) + elif group.data_length == 4: + data = _valToArray(val) + else: + raise Exception(f"Unsupported data length: {group.data_length}") + group.addParam(cfg.id, data) + group.txPacket() - def setPositionIGain(self, i_gains): - """Set the position I gains - Args: - i_gains (list of numbers): unit depends on the motor type - """ - self.__writeSyncMotorsData(self.groupWriters["position_i_gain"], i_gains) + # ------------------------------------------------------------------ # + # Public read / write API # + # ------------------------------------------------------------------ # + def setGoalPosition(self, positions: list): + """Set the goal position (pulses) for each motor.""" + self.__writeSyncMotorsData("goal_position", positions) - def setPositionDGain(self, d_gains): - """Set the position D gains + def setGoalVelocity(self, speeds: list): + """Set the goal velocity for each motor.""" + self.__writeSyncMotorsData("goal_velocity", speeds) - Args: - d_gains (list of numbers): unit depends on the motor type - """ - self.__writeSyncMotorsData(self.groupWriters["position_d_gain"], d_gains) + def setVelocityProfile(self, max_vel: list): + """Set the maximum velocity profile (position mode) for each motor.""" + self.__writeSyncMotorsData("velocity_profile", max_vel) + def setPositionPGain(self, p_gains: list): + """Set the position P gain for each motor.""" + self.__writeSyncMotorsData("position_p_gain", p_gains) - def getCurrentPosition(self) -> list: - """Get the current position of the motors - Returns: - list of numbers: unit = 1 pulse - """ - return self._readSyncMotorsData(self.groupReaders["position"]) + def setPositionIGain(self, i_gains: list): + """Set the position I gain for each motor.""" + self.__writeSyncMotorsData("position_i_gain", i_gains) + + def setPositionDGain(self, d_gains: list): + """Set the position D gain for each motor.""" + self.__writeSyncMotorsData("position_d_gain", d_gains) + def getCurrentPosition(self) -> list: + """Get the current position (pulses) for each motor.""" + return self._readSyncMotorsData("position") def getGoalPosition(self) -> list: - """Get the goal position of the motors - Returns: - list of numbers: unit = 1 pulse - """ - return self._readSyncMotorsData(self.groupReaders["goal_position"]) + """Get the goal position (pulses) for each motor.""" + return self._readSyncMotorsData("goal_position") def getGoalVelocity(self) -> list: - """Get the goal velocity of the motors - Returns: - list of velocities: unit is rev/min - """ - return self._readSyncMotorsData(self.groupReaders["goal_velocity"]) - + """Get the goal velocity for each motor.""" + return self._readSyncMotorsData("goal_velocity") def getCurrentVelocity(self) -> list: - """Get the current velocity of the motors - Returns: - list of velocities: unit is rev/min - """ - return self._readSyncMotorsData(self.groupReaders["velocity"]) - + """Get the current velocity for each motor.""" + return self._readSyncMotorsData("velocity") def isMoving(self) -> list: - """Check if the motors are moving - Returns: - list of booleans: True if the motor is moving, False otherwise - """ - return self._readSyncMotorsData(self.groupReaders["moving"]) - + """Return True for each motor that is currently moving.""" + return self._readSyncMotorsData("moving") def getMovingStatus(self) -> list: - """Get the moving status of the motors - Returns: - list of booleans: True if the motor is moving, False otherwise - """ - return self._readSyncMotorsData(self.groupReaders["moving_status"]) - + """Get the moving status byte for each motor.""" + return self._readSyncMotorsData("moving_status") def getVelocityTrajectory(self) -> list: - """Get the velocity trajectory of the motors - Returns: - list of velocities: unit is rev/min - """ - return self._readSyncMotorsData(self.groupReaders["velocity_trajectory"]) - + """Get the velocity trajectory for each motor.""" + return self._readSyncMotorsData("velocity_trajectory") def getPositionTrajectory(self) -> list: - """Get the position trajectory of the motors - Returns: - list of positions: unit = 1 pulse - """ - return self._readSyncMotorsData(self.groupReaders["position_trajectory"]) - + """Get the position trajectory for each motor.""" + return self._readSyncMotorsData("position_trajectory") def getPositionPGain(self) -> list: - """Get the position P gains of the motors - Returns: - list of P gains: unit depends on the motor type - """ - return self._readSyncMotorsData(self.groupReaders["position_p_gain"]) - + """Get the position P gain for each motor.""" + return self._readSyncMotorsData("position_p_gain") def getPositionIGain(self) -> list: - """Get the position I gains of the motors - Returns: - list of I gains: unit depends on the motor type - """ - return self._readSyncMotorsData(self.groupReaders["position_i_gain"]) - + """Get the position I gain for each motor.""" + return self._readSyncMotorsData("position_i_gain") def getPositionDGain(self) -> list: - """Get the position D gains of the motors - Returns: - list of D gains: unit depends on the motor type - """ - return self._readSyncMotorsData(self.groupReaders["position_d_gain"]) - - - def open(self) -> None: - """Open the port and set the baud rate. - Raises: - Exception: If the port cannot be opened or the baud rate cannot be set. - """ - try: - self.portHandler.openPort() - self.portHandler.setBaudRate(self.parameters.BAUDRATE) - except Exception as e: - raise Exception(f"Failed to open port: {e}") - - - def enableTorque(self): - """Enable the torque of the motors.""" - self.__write1Byte(self.parameters.ADDR_TORQUE_ENABLE, self.parameters.TORQUE_ENABLE) - - - def disableTorque(self): - """Disable the torque of the motors.""" - self.__write1Byte(self.parameters.ADDR_TORQUE_ENABLE, self.parameters.TORQUE_DISABLE) - - - def isTorqueEnable(self): - torques = [] - for DXL_ID in self.parameters.DXL_IDs: - torque, dxl_comm_result, dxl_error = self.packetHandler.read1ByteTxRx(self.portHandler, DXL_ID, self.parameters.ADDR_TORQUE_ENABLE) - if dxl_comm_result != COMM_SUCCESS: - raise Exception(f"Failed to read torque: {self.packetHandler.getTxRxResult(dxl_comm_result)}") - elif dxl_error != 0: - raise Exception(f"Failed to read torque: {self.packetHandler.getTxRxResult(dxl_error)}") - torques.append(torque) - return torques - - - def close(self) -> None: - """Close the port and disable the torque of the motors.""" - try: - for DXL_ID in self.parameters.DXL_IDs: - self.packetHandler.write1ByteTxRx(self.portHandler, DXL_ID, self.parameters.ADDR_TORQUE_ENABLE, - self.parameters.TORQUE_DISABLE) - self.portHandler.closePort() - self.deviceName = None - except Exception as e: - raise Exception(f"Failed to close port: {e}") - - def clearPort(self) -> None: - """Clear the port.""" - if not self.isConnected: - raise DisconnectedException() - - if self.portHandler: - self.portHandler.clearPort() + """Get the position D gain for each motor.""" + return self._readSyncMotorsData("position_d_gain") \ No newline at end of file diff --git a/dynamixelmotorsapi/dynamixelmotors.py b/dynamixelmotorsapi/dynamixelmotors.py index 4028e85..10712db 100644 --- a/dynamixelmotorsapi/dynamixelmotors.py +++ b/dynamixelmotorsapi/dynamixelmotors.py @@ -1,65 +1,65 @@ -from abc import ABC, abstractmethod -from dataclasses import field from threading import Lock from math import pi +from typing import List +import json import dynamixelmotorsapi._motorgroup as motorgroup -import dynamixelmotorsapi._dynamixelmotorsparameters as robotparameters +from dynamixelmotorsapi._dynamixelmotorsparameters import MotorConfig from dynamixelmotorsapi._logging_config import logger -class DynamixelMotors(ABC): - """ - Abstract class to control Dynamixel motors. - The class is designed to be used with the Dynamixel motors plugged into a FTDI USB hub. - The motors are controlled in position mode. The class is thread-safe and can be used in a multi-threaded environment. +from dynamixelmotorsapi._dynamixelmotorsparameters import register_model_from_json, MODELS_CONFIGS +loaded_models = register_model_from_json("./dynamixelmotorsapi/dynamixel_configs.json", overwrite=True) +if len(loaded_models): + print("Loaded ", len(MODELS_CONFIGS), " motor configs") - Example: - ```python - from robotsmotorsapi import DynamixelMotors - from robotsmotorsapi._dynamixelmotorsparameters import DXL_IDs - from robotsmotorsapi._logging_config import logger +class DynamixelMotors: + """ + Abstract class to control Dynamixel motors, supporting heterogeneous motor groups + where each motor can be a different series with different conversion parameters. - class MyDynamixelMotors(DynamixelMotors): - _length_to_rad = 1.0 / 20.0 # 1/radius of the pulley - _rad_to_pulse = 4096 / (2 * pi) # the resolution of the Dynamixel xm430 w210 - _pulse_center= 2048 - _max_vel = 1000 # *0.01 rev/min + The motor group is configured via a list of MotorConfig objects, one per motor, + which can be loaded from a dict or JSON file. - def __init__(self): - super().__init__() # Check if all parameters have been set + Example: + ```python + from dynamixelmotorsapi import DynamixelMotors + motors = DynamixelMotors.from_json("my_motors.json") - # Open connection to the motors (optionally specify device name, or it will take the first FTDI device) if motors.open(): - # Print current angles in radians print("Current angles (rad):", motors.angles) - - # Set new goal angles (example values) motors.angles = [0.5, 1.0, -0.5, 1.0] - - # Print status motors.printStatus() - - # Close connection when done motors.close() else: print("Failed to connect to motors.") ``` + JSON format: + ```json + [ + { + "id": 0, + "model": "XM430-W210", + "length_to_rad": 0.05, + "pulse_center": 2048, + "max_vel": 1000 + }, + { + "id": 1, + "model": "P_SERIES", + "length_to_rad": 0.03, + "pulse_center": 0, + "max_vel": 500 + } + ] + ``` """ - _FTDI_list = {} # Dict of all FTDI devices connected to the computer _initialized: bool = False - # To be defined by child class - _length_to_rad: float = None - _rad_to_pulse: int = None - _pulse_center: int = None - _max_vel: float = None - - _length_to_pulse: int = None - + _motor_configs: List[MotorConfig] = None _goal_velocity: list = None _goal_position: list = None _mg: motorgroup.MotorGroup = None @@ -71,80 +71,123 @@ def __init__(self): ##################### - @abstractmethod - def __init__(self): + def __init__(self, motor_configs: List[MotorConfig]): + """ + Args: + motor_configs: list of MotorConfig, one per motor, ordered by motor index. + """ self._lock = Lock() - self._goal_velocity = field(default_factory=lambda: [0] * len(robotparameters.DXL_IDs)) - self._goal_position = field(default_factory=lambda: [0] * len(robotparameters.DXL_IDs)) + self._motor_configs = motor_configs + n = len(motor_configs) + self._goal_velocity = [0] * n + self._goal_position = [0] * n if not self._initialized: - self._mg = motorgroup.MotorGroup(robotparameters) + self._mg = motorgroup.MotorGroup(motor_configs) self._initialized = True - - message = "A child class of DynamixelMotors must initialize this parameter" - assert self._length_to_rad is not None, message - assert self._rad_to_pulse is not None, message - assert self._pulse_center is not None, message - assert self._max_vel is not None, message - self._length_to_pulse = self._length_to_rad * self._rad_to_pulse + @classmethod + def from_dict(cls, data: list) -> "DynamixelMotors": + """ + Instantiate from a list of per-motor config dicts. - def lengthToPulse(self, displacement: list): + Args: + data: list of dicts, each containing the fields for one MotorConfig. + + Returns: + A configured DynamixelMotors instance (not yet connected). + """ + motor_configs = [MotorConfig.from_dict(m) for m in data] + return cls(motor_configs) + + + @classmethod + def from_json(cls, path: str) -> "DynamixelMotors": + """ + Instantiate from a JSON file containing a list of per-motor config dicts. + + Args: + path: path to the JSON file. + + Returns: + A configured DynamixelMotors instance (not yet connected). + """ + with open(path) as f: + return cls.from_dict(json.load(f)) + + + def _config(self, index: int) -> MotorConfig: + """Convenience accessor for the MotorConfig of motor at position `index`.""" + return self._motor_configs[index] + + + def lengthToPulse(self, displacement: list) -> list: """ - Convert length (mm) to pulse using the conversion factor `lengthToPulse`. + Convert length (mm) to pulse, per motor. Args: - displacement: list: list of length values in mm for each motor. + displacement: list of length values in mm, one per motor. Returns: A list of pulse values for each motor. """ - return [self._pulse_center - int(item * self._length_to_pulse) for item in displacement] + return [ + cfg.pulse_center - int(d * cfg.length_to_pulse) + for d, cfg in zip(displacement, self._motor_configs) + ] - def pulseToLength(self, pulse: list): + def pulseToLength(self, pulse: list) -> list: """ - Convert pulse to length (mm) using the conversion factor `lengthToPulse`. + Convert pulse to length (mm), per motor. Args: - pulse: list of pulse integer values for each motor. + pulse: list of pulse integer values, one per motor. Returns: A list of length values in mm for each motor. """ - return [(self._pulse_center - float(item)) / self._length_to_pulse for item in pulse] + return [ + (cfg.pulse_center - float(p)) / cfg.length_to_pulse + for p, cfg in zip(pulse, self._motor_configs) + ] - def pulseToRad(self, pulse: list): + def pulseToRad(self, pulse: list) -> list: """ - Convert pulse to radians using the conversion factor `radToPulse`. + Convert pulse to radians, per motor. Args: - pulse: list: list of pulse integer values for each motor. + pulse: list of pulse integer values, one per motor. Returns: A list of angles in radians for each motor. - """ - return [(self._pulse_center - float(item)) / self._rad_to_pulse for item in pulse] + return [ + (cfg.pulse_center - float(p)) / cfg.rad_to_pulse + for p, cfg in zip(pulse, self._motor_configs) + ] - def pulseToDeg(self, pulse: list): + def pulseToDeg(self, pulse: list) -> list: """ - Convert pulse to degrees using the conversion factor `radToPulse`. + Convert pulse to degrees, per motor. Args: - pulse: list: list of pulse values for each motor. + pulse: list of pulse values, one per motor. Returns: A list of angles in degrees for each motor. """ - return [(self._pulse_center - float(item)) / self._rad_to_pulse * 180.0 / pi for item in pulse] + return [ + (cfg.pulse_center - float(p)) / cfg.rad_to_pulse * 180.0 / pi + for p, cfg in zip(pulse, self._motor_configs) + ] - def _openAndConfig(self, device_name: str=None, multi_turn:bool = False) -> bool: - """Open the connection to the motors, configure it for position mode in multi-turn or not and enable torque sensing.""" + def _openAndConfig(self, device_name: str = None, multi_turn: bool = False) -> bool: + """Open the connection to the motors, configure position mode and enable torque.""" with self._lock: try: self._mg.updateDeviceName(device_name) @@ -162,20 +205,23 @@ def _openAndConfig(self, device_name: str=None, multi_turn:bool = False) -> bool self.enablePositionMode() self._mg.enableTorque() - logger.debug(f"Motor group opened and configured. Device name: {self._mg.deviceName}, Multi turn activated: {multi_turn}") + logger.debug( + f"Motor group opened and configured. " + f"Device name: {self._mg.deviceName}, Multi turn: {multi_turn}" + ) return True except Exception as e: logger.error(f"Failed to open and configure the motor group: {e}") return False - def open(self, device_name: str=None, multi_turn: bool=False) -> bool: + def open(self, device_name: str = None, multi_turn: bool = False) -> bool: """ Open the connection to the motors. Args: - device_name: str: if set, it will connect to the device with the given name, If not set, the first device will be used. - multi_turn: bool: Whether to enable the multi-turn mode of the motors. In multi-turn mode on, the angles interval is [-256*2π, 256*2π] + device_name: if set, connect to this specific port; otherwise use the first available. + multi_turn: enable multi-turn mode. Angle interval becomes [-256*2π, 256*2π]. """ if self._openAndConfig(device_name, multi_turn): self._device_index = motorgroup.listMotors().index(self._mg.deviceName) @@ -184,40 +230,37 @@ def open(self, device_name: str=None, multi_turn: bool=False) -> bool: return False - def findAndOpen(self, device_name: str=None, multi_turn: bool=False) -> int: + def findAndOpen(self, device_name: str = None, multi_turn: bool = False) -> int: """ - Iterate over the serial ports and try to conenct to the first available FTDI device. + Iterate over serial ports and connect to the first available FTDI device. Args: - device_name: str: If set, It will try to connected to the given device name (port name) - multi_turn: bool: Whether to enable the multi-turn mode of the motors. In multi-turn mode on, the angles interval is [-256*2π, 256*2π] + device_name: if set, try only this port. + multi_turn: enable multi-turn mode. Returns: - the index in the list of port to which it connected. If no connection was possible, returns -1. + Index of the connected port, or -1 if no connection was possible. """ if device_name is not None: try: index = motorgroup.listMotors().index(device_name) logger.info(f"Trying given device number {index} on port: {device_name}.") - return index if len(motorgroup.listMotors())>0 and self.open(device_name, multi_turn) else -1 - except: + return index if len(motorgroup.listMotors()) > 0 and self.open(device_name, multi_turn) else -1 + except Exception: return -1 index = 0 - connected = False try: - - while not connected and index list: @@ -285,34 +315,40 @@ def angles(self, angles: list): """Set the goal angles of the motors in radians.""" with self._lock: self._goal_position = angles - self._mg.setGoalPosition([int(self._pulse_center - self._rad_to_pulse * a) for a in angles]) + self._mg.setGoalPosition([ + int(cfg.pulse_center - cfg.rad_to_pulse * a) + for a, cfg in zip(angles, self._motor_configs) + ]) @property def goal_velocity(self) -> list: - """Get the current velocity (rev/min) of the motors.""" + """Get the last commanded velocity (rev/min) for each motor.""" return self._goal_velocity @goal_velocity.setter def goal_velocity(self, velocities: list): - """Set the goal velocity (rev/min) of the motors.""" + """Set the goal velocity (rev/min) for each motor.""" self._goal_velocity = velocities with self._lock: self._mg.setGoalVelocity(velocities) @property - def max_velocity(self)-> list: - """Get the current velocity (rev/min) profile of the motors.""" - return self._max_vel + def max_velocity(self) -> list: + """Get the maximum velocity profile (rev/min) for each motor.""" + return [cfg.max_vel for cfg in self._motor_configs] @max_velocity.setter def max_velocity(self, max_vel: list): - """Set the maximum velocities (rev/min) in position mode. - Arguments: + """ + Set the maximum velocity profile (rev/min) in position mode, per motor. + + Args: max_vel: list of maximum velocities for each motor in rev/min. """ - self._max_vel = max_vel + for cfg, v in zip(self._motor_configs, max_vel): + cfg.max_vel = v with self._lock: self._mg.setVelocityProfile(max_vel) @@ -325,10 +361,7 @@ def position_p_gain(self) -> list: @position_p_gain.setter def position_p_gain(self, p_gains: list): - """Set the position P gains of the motors. - Arguments: - p_gains: list of position P gains for each motor. - """ + """Set the position P gains of the motors.""" with self._lock: self._mg.setPositionPGain(p_gains) @@ -341,10 +374,7 @@ def position_i_gain(self) -> list: @position_i_gain.setter def position_i_gain(self, i_gains: list): - """Set the position I gains of the motors. - Arguments: - i_gains: list of position I gains for each motor. - """ + """Set the position I gains of the motors.""" with self._lock: self._mg.setPositionIGain(i_gains) @@ -357,69 +387,64 @@ def position_d_gain(self) -> list: @position_d_gain.setter def position_d_gain(self, d_gains: list): - """Set the position D gains of the motors. - Arguments: - d_gains: list of position D gains for each motor. - """ + """Set the position D gains of the motors.""" with self._lock: self._mg.setPositionDGain(d_gains) #### Read-only properties #### + + @property + def motor_configs(self) -> List[MotorConfig]: + """Get the list of per-motor configurations.""" + return self._motor_configs + @property def is_connected(self) -> bool: """Check if the motors are connected.""" with self._lock: return self._mg.isConnected - @property def device_name(self) -> str: - """Get the name of the device.""" + """Get the name of the connected device port.""" with self._lock: return self._mg.deviceName - @property def device_index(self) -> int: - """Get the index of the device in the list of Robot Motors Devices from Robot MotorsAPI""" + """Get the index of the device in the list of available motor devices.""" return self._device_index - @property def moving(self) -> list: """Check if the motors are moving.""" with self._lock: return self._mg.isMoving() - @property def moving_status(self) -> list: - """Get the moving status of the motors. - Returns: - A Byte encoding different informations on the moving status like whether the desired position has been reached or not, if the profile is in progress or not, the kind of Profile used. + """Get the moving status byte of the motors. - See [here](https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/#moving-status) for more details.""" + See https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/#moving-status for details. + """ with self._lock: return self._mg.getMovingStatus() - @property def velocity(self) -> list: """Get the current velocity (rev/min) of the motors.""" with self._lock: return self._mg.getCurrentVelocity() - @property - def velocity_trajectory(self)-> list: + def velocity_trajectory(self) -> list: """Get the velocity (rev/min) trajectory of the motors.""" with self._lock: return self._mg.getVelocityTrajectory() - @property - def position_trajectory(self)-> list: + def position_trajectory(self) -> list: """Get the position (pulse) trajectory of the motors.""" with self._lock: - return self._mg.getPositionTrajectory() + return self._mg.getPositionTrajectory() \ No newline at end of file diff --git a/examples/motors_example.py b/examples/motors_example.py index a4535b6..241250c 100644 --- a/examples/motors_example.py +++ b/examples/motors_example.py @@ -8,24 +8,13 @@ sys.path.append(os.path.dirname(os.path.realpath(__file__))+'/..') from dynamixelmotorsapi import DynamixelMotors -from dynamixelmotorsapi._dynamixelmotorsparameters import DXL_IDs from dynamixelmotorsapi._logging_config import logger -class MyDynamixelMotors(DynamixelMotors): - _length_to_rad = 1.0 / 20.0 # 1/radius of the pulley - _rad_to_pulse = 4096 / (2 * pi) # the resolution of the Dynamixel xm430 w210 - _pulse_center= 2048 - _max_vel = 1000 # *0.01 rev/min - - def __init__(self): - super().__init__() # Check if all parameters have been set - - def main(robot_motors: DynamixelMotors, loops=1): - - initial_pos_pulse = [0] * len(DXL_IDs) - robot_motors.max_velocity = [1000] * len(DXL_IDs) + motors_count = robot_motors._motor_configs + initial_pos_pulse = [0] * len(motors_count) + robot_motors.max_velocity = [1000] * len(motors_count) logger.info(f"Initial position in rad: {initial_pos_pulse}") robot_motors.angles = initial_pos_pulse time.sleep(1) @@ -33,7 +22,7 @@ def main(robot_motors: DynamixelMotors, loops=1): for i in range(loops): - new_pos = [((2*3.14)*((i+1)%8)/8)] * len(DXL_IDs) + new_pos = [((2*3.14)*((i+1)%8)/8)] * len(motors_count) print("-"*20) logger.info(f"new_pos {new_pos}") try: @@ -54,8 +43,17 @@ def main(robot_motors: DynamixelMotors, loops=1): try: logger.info("Starting DynamixelMotors API test...") logger.info("Opening and configuring Robot Motors API...") + + motors_description = [{ + "id": 0, + "model": "XM430-W210", + "length_to_rad": 0.05, + "pulse_center": 2048, + "max_vel": 1000 + } + ] - robot_motors = MyDynamixelMotors() + robot_motors = DynamixelMotors.from_dict(motors_description) if robot_motors.open(): diff --git a/pyproject.toml b/pyproject.toml index 373a27f..8f276f6 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -9,8 +9,10 @@ requires-python = ">=3.10" readme = "README.md" dependencies = [ "pyserial", - "dynamixel_sdk", - "numpy==1.26.4", + "dynamixel_sdk", + "numpy==1.26.4", + "requests", + "beautifulsoup4>=4.7.0", ] description = "An API for controlling the motors of a group of Dynamixel motors." keywords = ["robotics", "api", "dynamixel"] diff --git a/uv.lock b/uv.lock index a6bb56b..518186b 100644 --- a/uv.lock +++ b/uv.lock @@ -2,6 +2,117 @@ version = 1 revision = 2 requires-python = ">=3.10" +[[package]] +name = "beautifulsoup4" +version = "4.14.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "soupsieve" }, + { name = "typing-extensions" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/c3/b0/1c6a16426d389813b48d95e26898aff79abbde42ad353958ad95cc8c9b21/beautifulsoup4-4.14.3.tar.gz", hash = "sha256:6292b1c5186d356bba669ef9f7f051757099565ad9ada5dd630bd9de5fa7fb86", size = 627737, upload-time = "2025-11-30T15:08:26.084Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1a/39/47f9197bdd44df24d67ac8893641e16f386c984a0619ef2ee4c51fbbc019/beautifulsoup4-4.14.3-py3-none-any.whl", hash = "sha256:0918bfe44902e6ad8d57732ba310582e98da931428d231a5ecb9e7c703a735bb", size = 107721, upload-time = "2025-11-30T15:08:24.087Z" }, +] + +[[package]] +name = "certifi" +version = "2026.2.25" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/af/2d/7bf41579a8986e348fa033a31cdd0e4121114f6bce2457e8876010b092dd/certifi-2026.2.25.tar.gz", hash = "sha256:e887ab5cee78ea814d3472169153c2d12cd43b14bd03329a39a9c6e2e80bfba7", size = 155029, upload-time = "2026-02-25T02:54:17.342Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/9a/3c/c17fb3ca2d9c3acff52e30b309f538586f9f5b9c9cf454f3845fc9af4881/certifi-2026.2.25-py3-none-any.whl", hash = "sha256:027692e4402ad994f1c42e52a4997a9763c646b73e4096e4d5d6db8af1d6f0fa", size = 153684, upload-time = "2026-02-25T02:54:15.766Z" }, +] + +[[package]] +name = "charset-normalizer" +version = "3.4.5" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/1d/35/02daf95b9cd686320bb622eb148792655c9412dbb9b67abb5694e5910a24/charset_normalizer-3.4.5.tar.gz", hash = "sha256:95adae7b6c42a6c5b5b559b1a99149f090a57128155daeea91732c8d970d8644", size = 134804, upload-time = "2026-03-06T06:03:19.46Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a7/21/a2b1505639008ba2e6ef03733a81fc6cfd6a07ea6139a2b76421230b8dad/charset_normalizer-3.4.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:4167a621a9a1a986c73777dbc15d4b5eac8ac5c10393374109a343d4013ec765", size = 283319, upload-time = "2026-03-06T06:00:26.433Z" }, + { url = "https://files.pythonhosted.org/packages/70/67/df234c29b68f4e1e095885c9db1cb4b69b8aba49cf94fac041db4aaf1267/charset_normalizer-3.4.5-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3f64c6bf8f32f9133b668c7f7a7cbdbc453412bc95ecdbd157f3b1e377a92990", size = 189974, upload-time = "2026-03-06T06:00:28.222Z" }, + { url = "https://files.pythonhosted.org/packages/df/7f/fc66af802961c6be42e2c7b69c58f95cbd1f39b0e81b3365d8efe2a02a04/charset_normalizer-3.4.5-cp310-cp310-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:568e3c34b58422075a1b49575a6abc616d9751b4d61b23f712e12ebb78fe47b2", size = 207866, upload-time = "2026-03-06T06:00:29.769Z" }, + { url = "https://files.pythonhosted.org/packages/c9/23/404eb36fac4e95b833c50e305bba9a241086d427bb2167a42eac7c4f7da4/charset_normalizer-3.4.5-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:036c079aa08a6a592b82487f97c60b439428320ed1b2ea0b3912e99d30c77765", size = 203239, upload-time = "2026-03-06T06:00:31.086Z" }, + { url = "https://files.pythonhosted.org/packages/4b/2f/8a1d989bfadd120c90114ab33e0d2a0cbde05278c1fc15e83e62d570f50a/charset_normalizer-3.4.5-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:340810d34ef83af92148e96e3e44cb2d3f910d2bf95e5618a5c467d9f102231d", size = 196529, upload-time = "2026-03-06T06:00:32.608Z" }, + { url = "https://files.pythonhosted.org/packages/a5/0c/c75f85ff7ca1f051958bb518cd43922d86f576c03947a050fbedfdfb4f15/charset_normalizer-3.4.5-cp310-cp310-manylinux_2_31_armv7l.whl", hash = "sha256:cd2d0f0ec9aa977a27731a3209ebbcacebebaf41f902bd453a928bfd281cf7f8", size = 184152, upload-time = "2026-03-06T06:00:33.93Z" }, + { url = "https://files.pythonhosted.org/packages/f9/20/4ed37f6199af5dde94d4aeaf577f3813a5ec6635834cda1d957013a09c76/charset_normalizer-3.4.5-cp310-cp310-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:0b362bcd27819f9c07cbf23db4e0e8cd4b44c5ecd900c2ff907b2b92274a7412", size = 195226, upload-time = "2026-03-06T06:00:35.469Z" }, + { url = "https://files.pythonhosted.org/packages/28/31/7ba1102178cba7c34dcc050f43d427172f389729e356038f0726253dd914/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:77be992288f720306ab4108fe5c74797de327f3248368dfc7e1a916d6ed9e5a2", size = 192933, upload-time = "2026-03-06T06:00:36.83Z" }, + { url = "https://files.pythonhosted.org/packages/4b/23/f86443ab3921e6a60b33b93f4a1161222231f6c69bc24fb18f3bee7b8518/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_armv7l.whl", hash = "sha256:8b78d8a609a4b82c273257ee9d631ded7fac0d875bdcdccc109f3ee8328cfcb1", size = 185647, upload-time = "2026-03-06T06:00:38.367Z" }, + { url = "https://files.pythonhosted.org/packages/82/44/08b8be891760f1f5a6d23ce11d6d50c92981603e6eb740b4f72eea9424e2/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:ba20bdf69bd127f66d0174d6f2a93e69045e0b4036dc1ca78e091bcc765830c4", size = 209533, upload-time = "2026-03-06T06:00:41.931Z" }, + { url = "https://files.pythonhosted.org/packages/3b/5f/df114f23406199f8af711ddccfbf409ffbc5b7cdc18fa19644997ff0c9bb/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_riscv64.whl", hash = "sha256:76a9d0de4d0eab387822e7b35d8f89367dd237c72e82ab42b9f7bf5e15ada00f", size = 195901, upload-time = "2026-03-06T06:00:43.978Z" }, + { url = "https://files.pythonhosted.org/packages/07/83/71ef34a76fe8aa05ff8f840244bda2d61e043c2ef6f30d200450b9f6a1be/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:8fff79bf5978c693c9b1a4d71e4a94fddfb5fe744eb062a318e15f4a2f63a550", size = 204950, upload-time = "2026-03-06T06:00:45.202Z" }, + { url = "https://files.pythonhosted.org/packages/58/40/0253be623995365137d7dc68e45245036207ab2227251e69a3d93ce43183/charset_normalizer-3.4.5-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:c7e84e0c0005e3bdc1a9211cd4e62c78ba80bc37b2365ef4410cd2007a9047f2", size = 198546, upload-time = "2026-03-06T06:00:46.481Z" }, + { url = "https://files.pythonhosted.org/packages/ed/5c/5f3cb5b259a130895ef5ae16b38eaf141430fa3f7af50cd06c5d67e4f7b2/charset_normalizer-3.4.5-cp310-cp310-win32.whl", hash = "sha256:58ad8270cfa5d4bef1bc85bd387217e14ff154d6630e976c6f56f9a040757475", size = 132516, upload-time = "2026-03-06T06:00:47.924Z" }, + { url = "https://files.pythonhosted.org/packages/a5/c3/84fb174e7770f2df2e1a2115090771bfbc2227fb39a765c6d00568d1aab4/charset_normalizer-3.4.5-cp310-cp310-win_amd64.whl", hash = "sha256:02a9d1b01c1e12c27883b0c9349e0bcd9ae92e727ff1a277207e1a262b1cbf05", size = 142906, upload-time = "2026-03-06T06:00:49.389Z" }, + { url = "https://files.pythonhosted.org/packages/d7/b2/6f852f8b969f2cbd0d4092d2e60139ab1af95af9bb651337cae89ec0f684/charset_normalizer-3.4.5-cp310-cp310-win_arm64.whl", hash = "sha256:039215608ac7b358c4da0191d10fc76868567fbf276d54c14721bdedeb6de064", size = 133258, upload-time = "2026-03-06T06:00:51.051Z" }, + { url = "https://files.pythonhosted.org/packages/8f/9e/bcec3b22c64ecec47d39bf5167c2613efd41898c019dccd4183f6aa5d6a7/charset_normalizer-3.4.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:610f72c0ee565dfb8ae1241b666119582fdbfe7c0975c175be719f940e110694", size = 279531, upload-time = "2026-03-06T06:00:52.252Z" }, + { url = "https://files.pythonhosted.org/packages/58/12/81fd25f7e7078ab5d1eedbb0fac44be4904ae3370a3bf4533c8f2d159acd/charset_normalizer-3.4.5-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:60d68e820af339df4ae8358c7a2e7596badeb61e544438e489035f9fbf3246a5", size = 188006, upload-time = "2026-03-06T06:00:53.8Z" }, + { url = "https://files.pythonhosted.org/packages/ae/6e/f2d30e8c27c1b0736a6520311982cf5286cfc7f6cac77d7bc1325e3a23f2/charset_normalizer-3.4.5-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:10b473fc8dca1c3ad8559985794815f06ca3fc71942c969129070f2c3cdf7281", size = 205085, upload-time = "2026-03-06T06:00:55.311Z" }, + { url = "https://files.pythonhosted.org/packages/d0/90/d12cefcb53b5931e2cf792a33718d7126efb116a320eaa0742c7059a95e4/charset_normalizer-3.4.5-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:d4eb8ac7469b2a5d64b5b8c04f84d8bf3ad340f4514b98523805cbf46e3b3923", size = 200545, upload-time = "2026-03-06T06:00:56.532Z" }, + { url = "https://files.pythonhosted.org/packages/03/f4/44d3b830a20e89ff82a3134912d9a1cf6084d64f3b95dcad40f74449a654/charset_normalizer-3.4.5-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:5bcb3227c3d9aaf73eaaab1db7ccd80a8995c509ee9941e2aae060ca6e4e5d81", size = 193863, upload-time = "2026-03-06T06:00:57.823Z" }, + { url = "https://files.pythonhosted.org/packages/25/4b/f212119c18a6320a9d4a730d1b4057875cdeabf21b3614f76549042ef8a8/charset_normalizer-3.4.5-cp311-cp311-manylinux_2_31_armv7l.whl", hash = "sha256:75ee9c1cce2911581a70a3c0919d8bccf5b1cbc9b0e5171400ec736b4b569497", size = 181827, upload-time = "2026-03-06T06:00:59.323Z" }, + { url = "https://files.pythonhosted.org/packages/74/00/b26158e48b425a202a92965f8069e8a63d9af1481dfa206825d7f74d2a3c/charset_normalizer-3.4.5-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:1d1401945cb77787dbd3af2446ff2d75912327c4c3a1526ab7955ecf8600687c", size = 191085, upload-time = "2026-03-06T06:01:00.546Z" }, + { url = "https://files.pythonhosted.org/packages/c4/c2/1c1737bf6fd40335fe53d28fe49afd99ee4143cc57a845e99635ce0b9b6d/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0a45e504f5e1be0bd385935a8e1507c442349ca36f511a47057a71c9d1d6ea9e", size = 190688, upload-time = "2026-03-06T06:01:02.479Z" }, + { url = "https://files.pythonhosted.org/packages/5a/3d/abb5c22dc2ef493cd56522f811246a63c5427c08f3e3e50ab663de27fcf4/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:e09f671a54ce70b79a1fc1dc6da3072b7ef7251fadb894ed92d9aa8218465a5f", size = 183077, upload-time = "2026-03-06T06:01:04.231Z" }, + { url = "https://files.pythonhosted.org/packages/44/33/5298ad4d419a58e25b3508e87f2758d1442ff00c2471f8e0403dab8edad5/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:d01de5e768328646e6a3fa9e562706f8f6641708c115c62588aef2b941a4f88e", size = 206706, upload-time = "2026-03-06T06:01:05.773Z" }, + { url = "https://files.pythonhosted.org/packages/7b/17/51e7895ac0f87c3b91d276a449ef09f5532a7529818f59646d7a55089432/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:131716d6786ad5e3dc542f5cc6f397ba3339dc0fb87f87ac30e550e8987756af", size = 191665, upload-time = "2026-03-06T06:01:07.473Z" }, + { url = "https://files.pythonhosted.org/packages/90/8f/cce9adf1883e98906dbae380d769b4852bb0fa0004bc7d7a2243418d3ea8/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:1a374cc0b88aa710e8865dc1bd6edb3743c59f27830f0293ab101e4cf3ce9f85", size = 201950, upload-time = "2026-03-06T06:01:08.973Z" }, + { url = "https://files.pythonhosted.org/packages/08/ca/bce99cd5c397a52919e2769d126723f27a4c037130374c051c00470bcd38/charset_normalizer-3.4.5-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d31f0d1671e1534e395f9eb84a68e0fb670e1edb1fe819a9d7f564ae3bc4e53f", size = 195830, upload-time = "2026-03-06T06:01:10.155Z" }, + { url = "https://files.pythonhosted.org/packages/87/4f/2e3d023a06911f1281f97b8f036edc9872167036ca6f55cc874a0be6c12c/charset_normalizer-3.4.5-cp311-cp311-win32.whl", hash = "sha256:cace89841c0599d736d3d74a27bc5821288bb47c5441923277afc6059d7fbcb4", size = 132029, upload-time = "2026-03-06T06:01:11.706Z" }, + { url = "https://files.pythonhosted.org/packages/fe/1f/a853b73d386521fd44b7f67ded6b17b7b2367067d9106a5c4b44f9a34274/charset_normalizer-3.4.5-cp311-cp311-win_amd64.whl", hash = "sha256:f8102ae93c0bc863b1d41ea0f4499c20a83229f52ed870850892df555187154a", size = 142404, upload-time = "2026-03-06T06:01:12.865Z" }, + { url = "https://files.pythonhosted.org/packages/b4/10/dba36f76b71c38e9d391abe0fd8a5b818790e053c431adecfc98c35cd2a9/charset_normalizer-3.4.5-cp311-cp311-win_arm64.whl", hash = "sha256:ed98364e1c262cf5f9363c3eca8c2df37024f52a8fa1180a3610014f26eac51c", size = 132796, upload-time = "2026-03-06T06:01:14.106Z" }, + { url = "https://files.pythonhosted.org/packages/9c/b6/9ee9c1a608916ca5feae81a344dffbaa53b26b90be58cc2159e3332d44ec/charset_normalizer-3.4.5-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:ed97c282ee4f994ef814042423a529df9497e3c666dca19be1d4cd1129dc7ade", size = 280976, upload-time = "2026-03-06T06:01:15.276Z" }, + { url = "https://files.pythonhosted.org/packages/f8/d8/a54f7c0b96f1df3563e9190f04daf981e365a9b397eedfdfb5dbef7e5c6c/charset_normalizer-3.4.5-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0294916d6ccf2d069727d65973c3a1ca477d68708db25fd758dd28b0827cff54", size = 189356, upload-time = "2026-03-06T06:01:16.511Z" }, + { url = "https://files.pythonhosted.org/packages/42/69/2bf7f76ce1446759a5787cb87d38f6a61eb47dbbdf035cfebf6347292a65/charset_normalizer-3.4.5-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:dc57a0baa3eeedd99fafaef7511b5a6ef4581494e8168ee086031744e2679467", size = 206369, upload-time = "2026-03-06T06:01:17.853Z" }, + { url = "https://files.pythonhosted.org/packages/10/9c/949d1a46dab56b959d9a87272482195f1840b515a3380e39986989a893ae/charset_normalizer-3.4.5-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:ed1a9a204f317ef879b32f9af507d47e49cd5e7f8e8d5d96358c98373314fc60", size = 203285, upload-time = "2026-03-06T06:01:19.473Z" }, + { url = "https://files.pythonhosted.org/packages/67/5c/ae30362a88b4da237d71ea214a8c7eb915db3eec941adda511729ac25fa2/charset_normalizer-3.4.5-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7ad83b8f9379176c841f8865884f3514d905bcd2a9a3b210eaa446e7d2223e4d", size = 196274, upload-time = "2026-03-06T06:01:20.728Z" }, + { url = "https://files.pythonhosted.org/packages/b2/07/c9f2cb0e46cb6d64fdcc4f95953747b843bb2181bda678dc4e699b8f0f9a/charset_normalizer-3.4.5-cp312-cp312-manylinux_2_31_armv7l.whl", hash = "sha256:a118e2e0b5ae6b0120d5efa5f866e58f2bb826067a646431da4d6a2bdae7950e", size = 184715, upload-time = "2026-03-06T06:01:22.194Z" }, + { url = "https://files.pythonhosted.org/packages/36/64/6b0ca95c44fddf692cd06d642b28f63009d0ce325fad6e9b2b4d0ef86a52/charset_normalizer-3.4.5-cp312-cp312-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:754f96058e61a5e22e91483f823e07df16416ce76afa4ebf306f8e1d1296d43f", size = 193426, upload-time = "2026-03-06T06:01:23.795Z" }, + { url = "https://files.pythonhosted.org/packages/50/bc/a730690d726403743795ca3f5bb2baf67838c5fea78236098f324b965e40/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0c300cefd9b0970381a46394902cd18eaf2aa00163f999590ace991989dcd0fc", size = 191780, upload-time = "2026-03-06T06:01:25.053Z" }, + { url = "https://files.pythonhosted.org/packages/97/4f/6c0bc9af68222b22951552d73df4532b5be6447cee32d58e7e8c74ecbb7b/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:c108f8619e504140569ee7de3f97d234f0fbae338a7f9f360455071ef9855a95", size = 185805, upload-time = "2026-03-06T06:01:26.294Z" }, + { url = "https://files.pythonhosted.org/packages/dd/b9/a523fb9b0ee90814b503452b2600e4cbc118cd68714d57041564886e7325/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:d1028de43596a315e2720a9849ee79007ab742c06ad8b45a50db8cdb7ed4a82a", size = 208342, upload-time = "2026-03-06T06:01:27.55Z" }, + { url = "https://files.pythonhosted.org/packages/4d/61/c59e761dee4464050713e50e27b58266cc8e209e518c0b378c1580c959ba/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:19092dde50335accf365cce21998a1c6dd8eafd42c7b226eb54b2747cdce2fac", size = 193661, upload-time = "2026-03-06T06:01:29.051Z" }, + { url = "https://files.pythonhosted.org/packages/1c/43/729fa30aad69783f755c5ad8649da17ee095311ca42024742701e202dc59/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:4354e401eb6dab9aed3c7b4030514328a6c748d05e1c3e19175008ca7de84fb1", size = 204819, upload-time = "2026-03-06T06:01:30.298Z" }, + { url = "https://files.pythonhosted.org/packages/87/33/d9b442ce5a91b96fc0840455a9e49a611bbadae6122778d0a6a79683dd31/charset_normalizer-3.4.5-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a68766a3c58fde7f9aaa22b3786276f62ab2f594efb02d0a1421b6282e852e98", size = 198080, upload-time = "2026-03-06T06:01:31.478Z" }, + { url = "https://files.pythonhosted.org/packages/56/5a/b8b5a23134978ee9885cee2d6995f4c27cc41f9baded0a9685eabc5338f0/charset_normalizer-3.4.5-cp312-cp312-win32.whl", hash = "sha256:1827734a5b308b65ac54e86a618de66f935a4f63a8a462ff1e19a6788d6c2262", size = 132630, upload-time = "2026-03-06T06:01:33.056Z" }, + { url = "https://files.pythonhosted.org/packages/70/53/e44a4c07e8904500aec95865dc3f6464dc3586a039ef0df606eb3ac38e35/charset_normalizer-3.4.5-cp312-cp312-win_amd64.whl", hash = "sha256:728c6a963dfab66ef865f49286e45239384249672cd598576765acc2a640a636", size = 142856, upload-time = "2026-03-06T06:01:34.489Z" }, + { url = "https://files.pythonhosted.org/packages/ea/aa/c5628f7cad591b1cf45790b7a61483c3e36cf41349c98af7813c483fd6e8/charset_normalizer-3.4.5-cp312-cp312-win_arm64.whl", hash = "sha256:75dfd1afe0b1647449e852f4fb428195a7ed0588947218f7ba929f6538487f02", size = 132982, upload-time = "2026-03-06T06:01:35.641Z" }, + { url = "https://files.pythonhosted.org/packages/f5/48/9f34ec4bb24aa3fdba1890c1bddb97c8a4be1bd84ef5c42ac2352563ad05/charset_normalizer-3.4.5-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:ac59c15e3f1465f722607800c68713f9fbc2f672b9eb649fe831da4019ae9b23", size = 280788, upload-time = "2026-03-06T06:01:37.126Z" }, + { url = "https://files.pythonhosted.org/packages/0e/09/6003e7ffeb90cc0560da893e3208396a44c210c5ee42efff539639def59b/charset_normalizer-3.4.5-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:165c7b21d19365464e8f70e5ce5e12524c58b48c78c1f5a57524603c1ab003f8", size = 188890, upload-time = "2026-03-06T06:01:38.73Z" }, + { url = "https://files.pythonhosted.org/packages/42/1e/02706edf19e390680daa694d17e2b8eab4b5f7ac285e2a51168b4b22ee6b/charset_normalizer-3.4.5-cp313-cp313-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:28269983f25a4da0425743d0d257a2d6921ea7d9b83599d4039486ec5b9f911d", size = 206136, upload-time = "2026-03-06T06:01:40.016Z" }, + { url = "https://files.pythonhosted.org/packages/c7/87/942c3def1b37baf3cf786bad01249190f3ca3d5e63a84f831e704977de1f/charset_normalizer-3.4.5-cp313-cp313-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:d27ce22ec453564770d29d03a9506d449efbb9fa13c00842262b2f6801c48cce", size = 202551, upload-time = "2026-03-06T06:01:41.522Z" }, + { url = "https://files.pythonhosted.org/packages/94/0a/af49691938dfe175d71b8a929bd7e4ace2809c0c5134e28bc535660d5262/charset_normalizer-3.4.5-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0625665e4ebdddb553ab185de5db7054393af8879fb0c87bd5690d14379d6819", size = 195572, upload-time = "2026-03-06T06:01:43.208Z" }, + { url = "https://files.pythonhosted.org/packages/20/ea/dfb1792a8050a8e694cfbde1570ff97ff74e48afd874152d38163d1df9ae/charset_normalizer-3.4.5-cp313-cp313-manylinux_2_31_armv7l.whl", hash = "sha256:c23eb3263356d94858655b3e63f85ac5d50970c6e8febcdde7830209139cc37d", size = 184438, upload-time = "2026-03-06T06:01:44.755Z" }, + { url = "https://files.pythonhosted.org/packages/72/12/c281e2067466e3ddd0595bfaea58a6946765ace5c72dfa3edc2f5f118026/charset_normalizer-3.4.5-cp313-cp313-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:e6302ca4ae283deb0af68d2fbf467474b8b6aedcd3dab4db187e07f94c109763", size = 193035, upload-time = "2026-03-06T06:01:46.051Z" }, + { url = "https://files.pythonhosted.org/packages/ba/4f/3792c056e7708e10464bad0438a44708886fb8f92e3c3d29ec5e2d964d42/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:e51ae7d81c825761d941962450f50d041db028b7278e7b08930b4541b3e45cb9", size = 191340, upload-time = "2026-03-06T06:01:47.547Z" }, + { url = "https://files.pythonhosted.org/packages/e7/86/80ddba897127b5c7a9bccc481b0cd36c8fefa485d113262f0fe4332f0bf4/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_armv7l.whl", hash = "sha256:597d10dec876923e5c59e48dbd366e852eacb2b806029491d307daea6b917d7c", size = 185464, upload-time = "2026-03-06T06:01:48.764Z" }, + { url = "https://files.pythonhosted.org/packages/4d/00/b5eff85ba198faacab83e0e4b6f0648155f072278e3b392a82478f8b988b/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:5cffde4032a197bd3b42fd0b9509ec60fb70918d6970e4cc773f20fc9180ca67", size = 208014, upload-time = "2026-03-06T06:01:50.371Z" }, + { url = "https://files.pythonhosted.org/packages/c8/11/d36f70be01597fd30850dde8a1269ebc8efadd23ba5785808454f2389bde/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_riscv64.whl", hash = "sha256:2da4eedcb6338e2321e831a0165759c0c620e37f8cd044a263ff67493be8ffb3", size = 193297, upload-time = "2026-03-06T06:01:51.933Z" }, + { url = "https://files.pythonhosted.org/packages/1a/1d/259eb0a53d4910536c7c2abb9cb25f4153548efb42800c6a9456764649c0/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:65a126fb4b070d05340a84fc709dd9e7c75d9b063b610ece8a60197a291d0adf", size = 204321, upload-time = "2026-03-06T06:01:53.887Z" }, + { url = "https://files.pythonhosted.org/packages/84/31/faa6c5b9d3688715e1ed1bb9d124c384fe2fc1633a409e503ffe1c6398c1/charset_normalizer-3.4.5-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:c7a80a9242963416bd81f99349d5f3fce1843c303bd404f204918b6d75a75fd6", size = 197509, upload-time = "2026-03-06T06:01:56.439Z" }, + { url = "https://files.pythonhosted.org/packages/fd/a5/c7d9dd1503ffc08950b3260f5d39ec2366dd08254f0900ecbcf3a6197c7c/charset_normalizer-3.4.5-cp313-cp313-win32.whl", hash = "sha256:f1d725b754e967e648046f00c4facc42d414840f5ccc670c5670f59f83693e4f", size = 132284, upload-time = "2026-03-06T06:01:57.812Z" }, + { url = "https://files.pythonhosted.org/packages/b9/0f/57072b253af40c8aa6636e6de7d75985624c1eb392815b2f934199340a89/charset_normalizer-3.4.5-cp313-cp313-win_amd64.whl", hash = "sha256:e37bd100d2c5d3ba35db9c7c5ba5a9228cbcffe5c4778dc824b164e5257813d7", size = 142630, upload-time = "2026-03-06T06:01:59.062Z" }, + { url = "https://files.pythonhosted.org/packages/31/41/1c4b7cc9f13bd9d369ce3bc993e13d374ce25fa38a2663644283ecf422c1/charset_normalizer-3.4.5-cp313-cp313-win_arm64.whl", hash = "sha256:93b3b2cc5cf1b8743660ce77a4f45f3f6d1172068207c1defc779a36eea6bb36", size = 133254, upload-time = "2026-03-06T06:02:00.281Z" }, + { url = "https://files.pythonhosted.org/packages/43/be/0f0fd9bb4a7fa4fb5067fb7d9ac693d4e928d306f80a0d02bde43a7c4aee/charset_normalizer-3.4.5-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:8197abe5ca1ffb7d91e78360f915eef5addff270f8a71c1fc5be24a56f3e4873", size = 280232, upload-time = "2026-03-06T06:02:01.508Z" }, + { url = "https://files.pythonhosted.org/packages/28/02/983b5445e4bef49cd8c9da73a8e029f0825f39b74a06d201bfaa2e55142a/charset_normalizer-3.4.5-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a2aecdb364b8a1802afdc7f9327d55dad5366bc97d8502d0f5854e50712dbc5f", size = 189688, upload-time = "2026-03-06T06:02:02.857Z" }, + { url = "https://files.pythonhosted.org/packages/d0/88/152745c5166437687028027dc080e2daed6fe11cfa95a22f4602591c42db/charset_normalizer-3.4.5-cp314-cp314-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:a66aa5022bf81ab4b1bebfb009db4fd68e0c6d4307a1ce5ef6a26e5878dfc9e4", size = 206833, upload-time = "2026-03-06T06:02:05.127Z" }, + { url = "https://files.pythonhosted.org/packages/cb/0f/ebc15c8b02af2f19be9678d6eed115feeeccc45ce1f4b098d986c13e8769/charset_normalizer-3.4.5-cp314-cp314-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:d77f97e515688bd615c1d1f795d540f32542d514242067adcb8ef532504cb9ee", size = 202879, upload-time = "2026-03-06T06:02:06.446Z" }, + { url = "https://files.pythonhosted.org/packages/38/9c/71336bff6934418dc8d1e8a1644176ac9088068bc571da612767619c97b3/charset_normalizer-3.4.5-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:01a1ed54b953303ca7e310fafe0fe347aab348bd81834a0bcd602eb538f89d66", size = 195764, upload-time = "2026-03-06T06:02:08.763Z" }, + { url = "https://files.pythonhosted.org/packages/b7/95/ce92fde4f98615661871bc282a856cf9b8a15f686ba0af012984660d480b/charset_normalizer-3.4.5-cp314-cp314-manylinux_2_31_armv7l.whl", hash = "sha256:b2d37d78297b39a9eb9eb92c0f6df98c706467282055419df141389b23f93362", size = 183728, upload-time = "2026-03-06T06:02:10.137Z" }, + { url = "https://files.pythonhosted.org/packages/1c/e7/f5b4588d94e747ce45ae680f0f242bc2d98dbd4eccfab73e6160b6893893/charset_normalizer-3.4.5-cp314-cp314-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:e71bbb595973622b817c042bd943c3f3667e9c9983ce3d205f973f486fec98a7", size = 192937, upload-time = "2026-03-06T06:02:11.663Z" }, + { url = "https://files.pythonhosted.org/packages/f9/29/9d94ed6b929bf9f48bf6ede6e7474576499f07c4c5e878fb186083622716/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:4cd966c2559f501c6fd69294d082c2934c8dd4719deb32c22961a5ac6db0df1d", size = 192040, upload-time = "2026-03-06T06:02:13.489Z" }, + { url = "https://files.pythonhosted.org/packages/15/d2/1a093a1cf827957f9445f2fe7298bcc16f8fc5e05c1ed2ad1af0b239035e/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_armv7l.whl", hash = "sha256:d5e52d127045d6ae01a1e821acfad2f3a1866c54d0e837828538fabe8d9d1bd6", size = 184107, upload-time = "2026-03-06T06:02:14.83Z" }, + { url = "https://files.pythonhosted.org/packages/0f/7d/82068ce16bd36135df7b97f6333c5d808b94e01d4599a682e2337ed5fd14/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_ppc64le.whl", hash = "sha256:30a2b1a48478c3428d047ed9690d57c23038dac838a87ad624c85c0a78ebeb39", size = 208310, upload-time = "2026-03-06T06:02:16.165Z" }, + { url = "https://files.pythonhosted.org/packages/84/4e/4dfb52307bb6af4a5c9e73e482d171b81d36f522b21ccd28a49656baa680/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_riscv64.whl", hash = "sha256:d8ed79b8f6372ca4254955005830fd61c1ccdd8c0fac6603e2c145c61dd95db6", size = 192918, upload-time = "2026-03-06T06:02:18.144Z" }, + { url = "https://files.pythonhosted.org/packages/08/a4/159ff7da662cf7201502ca89980b8f06acf3e887b278956646a8aeb178ab/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_s390x.whl", hash = "sha256:c5af897b45fa606b12464ccbe0014bbf8c09191e0a66aab6aa9d5cf6e77e0c94", size = 204615, upload-time = "2026-03-06T06:02:19.821Z" }, + { url = "https://files.pythonhosted.org/packages/d6/62/0dd6172203cb6b429ffffc9935001fde42e5250d57f07b0c28c6046deb6b/charset_normalizer-3.4.5-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:1088345bcc93c58d8d8f3d783eca4a6e7a7752bbff26c3eee7e73c597c191c2e", size = 197784, upload-time = "2026-03-06T06:02:21.86Z" }, + { url = "https://files.pythonhosted.org/packages/c7/5e/1aab5cb737039b9c59e63627dc8bbc0d02562a14f831cc450e5f91d84ce1/charset_normalizer-3.4.5-cp314-cp314-win32.whl", hash = "sha256:ee57b926940ba00bca7ba7041e665cc956e55ef482f851b9b65acb20d867e7a2", size = 133009, upload-time = "2026-03-06T06:02:23.289Z" }, + { url = "https://files.pythonhosted.org/packages/40/65/e7c6c77d7aaa4c0d7974f2e403e17f0ed2cb0fc135f77d686b916bf1eead/charset_normalizer-3.4.5-cp314-cp314-win_amd64.whl", hash = "sha256:4481e6da1830c8a1cc0b746b47f603b653dadb690bcd851d039ffaefe70533aa", size = 143511, upload-time = "2026-03-06T06:02:26.195Z" }, + { url = "https://files.pythonhosted.org/packages/ba/91/52b0841c71f152f563b8e072896c14e3d83b195c188b338d3cc2e582d1d4/charset_normalizer-3.4.5-cp314-cp314-win_arm64.whl", hash = "sha256:97ab7787092eb9b50fb47fa04f24c75b768a606af1bcba1957f07f128a7219e4", size = 133775, upload-time = "2026-03-06T06:02:27.473Z" }, + { url = "https://files.pythonhosted.org/packages/c5/60/3a621758945513adfd4db86827a5bafcc615f913dbd0b4c2ed64a65731be/charset_normalizer-3.4.5-py3-none-any.whl", hash = "sha256:9db5e3fcdcee89a78c04dffb3fe33c79f77bd741a624946db2591c81b2fc85b0", size = 55455, upload-time = "2026-03-06T06:03:17.827Z" }, +] + [[package]] name = "dynamixel-sdk" version = "4.0.3" @@ -14,6 +125,36 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/18/5b/50e4acc3cfccb4a502b6bc3b82eeb24b271740d97ef6ddb91746acebc095/dynamixel_sdk-4.0.3-py3-none-any.whl", hash = "sha256:fc243f0a72ab6827a09908b93c83d894fab83ab4dd76c6c6a07057c0f9686b5f", size = 103497, upload-time = "2025-12-18T05:57:40.47Z" }, ] +[[package]] +name = "dynamixelmotorsapi" +version = "0.2.0" +source = { editable = "." } +dependencies = [ + { name = "beautifulsoup4" }, + { name = "dynamixel-sdk" }, + { name = "numpy" }, + { name = "pyserial" }, + { name = "requests" }, +] + +[package.metadata] +requires-dist = [ + { name = "beautifulsoup4", specifier = ">=4.7.0" }, + { name = "dynamixel-sdk" }, + { name = "numpy", specifier = "==1.26.4" }, + { name = "pyserial" }, + { name = "requests" }, +] + +[[package]] +name = "idna" +version = "3.11" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/6f/6d/0703ccc57f3a7233505399edb88de3cbd678da106337b9fcde432b65ed60/idna-3.11.tar.gz", hash = "sha256:795dafcc9c04ed0c1fb032c2aa73654d8e8c5023a7df64a53f39190ada629902", size = 194582, upload-time = "2025-10-12T14:55:20.501Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/0e/61/66938bbb5fc52dbdf84594873d5b51fb1f7c7794e9c0f5bd885f30bc507b/idna-3.11-py3-none-any.whl", hash = "sha256:771a87f49d9defaf64091e6e6fe9c18d4833f140bd19464795bc32d966ca37ea", size = 71008, upload-time = "2025-10-12T14:55:18.883Z" }, +] + [[package]] name = "numpy" version = "1.26.4" @@ -56,18 +197,43 @@ wheels = [ ] [[package]] -name = "robotsmotorsapi" -version = "0.2.0" -source = { editable = "." } +name = "requests" +version = "2.32.5" +source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "dynamixel-sdk" }, - { name = "numpy" }, - { name = "pyserial" }, + { name = "certifi" }, + { name = "charset-normalizer" }, + { name = "idna" }, + { name = "urllib3" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/c9/74/b3ff8e6c8446842c3f5c837e9c3dfcfe2018ea6ecef224c710c85ef728f4/requests-2.32.5.tar.gz", hash = "sha256:dbba0bac56e100853db0ea71b82b4dfd5fe2bf6d3754a8893c3af500cec7d7cf", size = 134517, upload-time = "2025-08-18T20:46:02.573Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1e/db/4254e3eabe8020b458f1a747140d32277ec7a271daf1d235b70dc0b4e6e3/requests-2.32.5-py3-none-any.whl", hash = "sha256:2462f94637a34fd532264295e186976db0f5d453d1cdd31473c85a6a161affb6", size = 64738, upload-time = "2025-08-18T20:46:00.542Z" }, ] -[package.metadata] -requires-dist = [ - { name = "dynamixel-sdk" }, - { name = "numpy", specifier = "==1.26.4" }, - { name = "pyserial" }, +[[package]] +name = "soupsieve" +version = "2.8.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/7b/ae/2d9c981590ed9999a0d91755b47fc74f74de286b0f5cee14c9269041e6c4/soupsieve-2.8.3.tar.gz", hash = "sha256:3267f1eeea4251fb42728b6dfb746edc9acaffc4a45b27e19450b676586e8349", size = 118627, upload-time = "2026-01-20T04:27:02.457Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/46/2c/1462b1d0a634697ae9e55b3cecdcb64788e8b7d63f54d923fcd0bb140aed/soupsieve-2.8.3-py3-none-any.whl", hash = "sha256:ed64f2ba4eebeab06cc4962affce381647455978ffc1e36bb79a545b91f45a95", size = 37016, upload-time = "2026-01-20T04:27:01.012Z" }, +] + +[[package]] +name = "typing-extensions" +version = "4.15.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/72/94/1a15dd82efb362ac84269196e94cf00f187f7ed21c242792a923cdb1c61f/typing_extensions-4.15.0.tar.gz", hash = "sha256:0cea48d173cc12fa28ecabc3b837ea3cf6f38c6d1136f85cbaaf598984861466", size = 109391, upload-time = "2025-08-25T13:49:26.313Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/18/67/36e9267722cc04a6b9f15c7f3441c2363321a3ea07da7ae0c0707beb2a9c/typing_extensions-4.15.0-py3-none-any.whl", hash = "sha256:f0fa19c6845758ab08074a0cfa8b7aecb71c999ca73d62883bc25cc018c4e548", size = 44614, upload-time = "2025-08-25T13:49:24.86Z" }, +] + +[[package]] +name = "urllib3" +version = "2.6.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/c7/24/5f1b3bdffd70275f6661c76461e25f024d5a38a46f04aaca912426a2b1d3/urllib3-2.6.3.tar.gz", hash = "sha256:1b62b6884944a57dbe321509ab94fd4d3b307075e0c2eae991ac71ee15ad38ed", size = 435556, upload-time = "2026-01-07T16:24:43.925Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/39/08/aaaad47bc4e9dc8c725e68f9d04865dbcb2052843ff09c97b08904852d84/urllib3-2.6.3-py3-none-any.whl", hash = "sha256:bf272323e553dfb2e87d9bfd225ca7b0f467b919d7bbd355436d3fd37cb0acd4", size = 131584, upload-time = "2026-01-07T16:24:42.685Z" }, ] From ed00b192bbe71b3bf1c9bb8e08ceabc067fd2fba Mon Sep 17 00:00:00 2001 From: HanaeRateau Date: Mon, 16 Mar 2026 15:09:01 +0100 Subject: [PATCH 02/27] Renaming and adds scraper and dynamixel_configs --- ...rameters.py => _dynamixelmotorsconfigs.py} | 0 dynamixelmotorsapi/dynamixel_configs.json | 2818 +++++++++++++++++ scraper.py | 351 ++ 3 files changed, 3169 insertions(+) rename dynamixelmotorsapi/{_dynamixelmotorsparameters.py => _dynamixelmotorsconfigs.py} (100%) create mode 100644 dynamixelmotorsapi/dynamixel_configs.json create mode 100644 scraper.py diff --git a/dynamixelmotorsapi/_dynamixelmotorsparameters.py b/dynamixelmotorsapi/_dynamixelmotorsconfigs.py similarity index 100% rename from dynamixelmotorsapi/_dynamixelmotorsparameters.py rename to dynamixelmotorsapi/_dynamixelmotorsconfigs.py diff --git a/dynamixelmotorsapi/dynamixel_configs.json b/dynamixelmotorsapi/dynamixel_configs.json new file mode 100644 index 0000000..6074ef8 --- /dev/null +++ b/dynamixelmotorsapi/dynamixel_configs.json @@ -0,0 +1,2818 @@ +[ + { + "model": "YM070-210-M001-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-m001-rh/", + "resolution": 524288, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM070-210-B001-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-b001-rh/", + "resolution": 524288, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM070-210-R051-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-r051-rh/", + "resolution": 26738688, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM070-210-R099-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-r099-rh/", + "resolution": 51904512, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM070-210-A051-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-a051-rh/", + "resolution": 26738688, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM070-210-A099-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym070-210-a099-rh/", + "resolution": 51904512, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-M001-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-m001-rh/", + "resolution": 524288, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-B001-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-b001-rh/", + "resolution": 524288, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-R051-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-r051-rh/", + "resolution": 26738688, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-R099-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-r099-rh/", + "resolution": 51904512, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-A051-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-a051-rh/", + "resolution": 26738688, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "YM080-230-A099-RH", + "series": "Y_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/y/ym080-230-a099-rh/", + "resolution": 51904512, + "addr_torque_enable": 512, + "addr_operating_mode": 33, + "addr_goal_position": 532, + "len_goal_position": 4, + "addr_goal_velocity": 528, + "len_goal_velocity": 4, + "addr_present_position": 552, + "len_present_position": 4, + "addr_present_velocity": 132, + "len_present_velocity": 2, + "addr_velocity_profile": 244, + "addr_moving": 48, + "addr_moving_status": 541, + "addr_velocity_trajectory": 564, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 560, + "len_position_trajectory": 4, + "addr_position_p_gain": 232, + "len_position_p_gain": 4, + "addr_position_i_gain": 228, + "len_position_i_gain": 4, + "addr_position_d_gain": 224, + "len_position_d_gain": 4, + "min_position_value": -262144, + "max_position_value": 262144, + "errors": [] + }, + { + "model": "PH54-200-S500-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/ph54-200-s500-r/", + "resolution": 1003846, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -501433, + "max_position_value": 501433, + "errors": [] + }, + { + "model": "PH54-100-S500-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/ph54-100-s500-r/", + "resolution": 1003846, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -501433, + "max_position_value": 501433, + "errors": [] + }, + { + "model": "PH42-020-S300-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/ph42-020-s300-r/", + "resolution": 607500, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -303454, + "max_position_value": 303454, + "errors": [] + }, + { + "model": "PM54-060-S250-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/pm54-060-s250-r/", + "resolution": 502834, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -251173, + "max_position_value": 251173, + "errors": [] + }, + { + "model": "PM54-040-S250-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/pm54-040-s250-r/", + "resolution": 502834, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -251173, + "max_position_value": 251173, + "errors": [] + }, + { + "model": "PM42-010-S260-R", + "series": "P_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/p/pm42-010-s260-r/", + "resolution": 526374, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -262931, + "max_position_value": 262931, + "errors": [] + }, + { + "model": "XL320", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xl320/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 37, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "XW540-T140", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xw540-t140/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XW540-T260", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xw540-t260/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XW430-T200", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xw430-t200/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XW430-T333", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xw430-t333/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XD540-T270", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xd540-t270/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XD540-T150", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xd540-t150/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XD430-T350", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xd430-t350/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XD430-T210", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xd430-t210/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH540-W150", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh540-w150/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH540-W270", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh540-w270/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH540-V150", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh540-v150/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH540-V270", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh540-v270/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH430-W210", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh430-w210/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH430-W350", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh430-w350/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH430-V210", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh430-v210/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XH430-V350", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xh430-v350/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XM540-W150", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xm540-w150/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XM540-W270", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xm540-w270/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XM430-W210", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xm430-w210/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XM430-W350", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xm430-w350/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XM335-T323", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xm335-t323/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 1024, + "max_position_value": 3072, + "errors": [] + }, + { + "model": "2XC430-W250", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/2xc430-w250/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC430-W150", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc430-w150/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC430-W240", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc430-w240/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC430-T150BB", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc430-t150bb/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC430-T240BB", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc430-t240bb/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC330-T288", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC330-T181", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc330-t181/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC330-M288", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc330-m288/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XC330-M181", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xc330-m181/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "2XL430-W250", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/2xl430-w250/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XL430-W250", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xl430-w250/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XL330-M288", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xl330-m288/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "XL330-M077", + "series": "X_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/x/xl330-m077/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "MX-12W", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-12w/", + "resolution": 4096, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": 73, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "MX-106T/R", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-106/", + "resolution": 4096, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": 73, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "MX-64T/R/AT/AR", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-64/", + "resolution": 4096, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": 73, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "MX-28T/R/AT/AR", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-28/", + "resolution": 4096, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": 73, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "MX-106T/R(2.0)", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-106-2/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "MX-64T/R/AT/AR(2.0)", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-64-2/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "MX-28T/R/AT/AR(2.0)", + "series": "MX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/mx/mx-28-2/", + "resolution": 4096, + "addr_torque_enable": 64, + "addr_operating_mode": 11, + "addr_goal_position": 116, + "len_goal_position": 4, + "addr_goal_velocity": 104, + "len_goal_velocity": 4, + "addr_present_position": 132, + "len_present_position": 4, + "addr_present_velocity": 128, + "len_present_velocity": 4, + "addr_velocity_profile": 112, + "addr_moving": 24, + "addr_moving_status": 123, + "addr_velocity_trajectory": 136, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 140, + "len_position_trajectory": 4, + "addr_position_p_gain": 84, + "len_position_p_gain": 2, + "addr_position_i_gain": 82, + "len_position_i_gain": 2, + "addr_position_d_gain": 80, + "len_position_d_gain": 2, + "min_position_value": 0, + "max_position_value": 4095, + "errors": [] + }, + { + "model": "AX-18A", + "series": "AX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/ax/ax-18a/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "AX-12A", + "series": "AX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/ax/ax-12a/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "AX-12W", + "series": "AX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/ax/ax-12w/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "EX-106+", + "series": "EX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/ex/ex-106+/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "DX-113", + "series": "DX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/dx/dx-113/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "DX-116", + "series": "DX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/dx/dx-116/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "DX-117", + "series": "DX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/dx/dx-117/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "RX-10", + "series": "RX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/rx/rx-10/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "RX-24F", + "series": "RX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/rx/rx-24f/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "RX-28", + "series": "RX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/rx/rx-28/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "RX-64", + "series": "RX_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/rx/rx-64/", + "resolution": null, + "addr_torque_enable": 24, + "addr_operating_mode": null, + "addr_goal_position": 30, + "len_goal_position": 2, + "addr_goal_velocity": null, + "len_goal_velocity": null, + "addr_present_position": 36, + "len_present_position": 2, + "addr_present_velocity": null, + "len_present_velocity": null, + "addr_velocity_profile": null, + "addr_moving": 32, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": null, + "len_position_p_gain": null, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": null, + "max_position_value": null, + "errors": [] + }, + { + "model": "L54-30-S400-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/l54-30-s400-r/", + "resolution": 288395, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -144197, + "max_position_value": 144197, + "errors": [] + }, + { + "model": "L54-30-S500-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/l54-30-s500-r/", + "resolution": 361384, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -180692, + "max_position_value": 180692, + "errors": [] + }, + { + "model": "L54-50-S290-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/l54-50-s290-r/", + "resolution": 207692, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -103846, + "max_position_value": 103846, + "errors": [] + }, + { + "model": "L54-50-S500-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/l54-50-s500-r/", + "resolution": 361384, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -180692, + "max_position_value": 180692, + "errors": [] + }, + { + "model": "L42-10-S300-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/l42-10-s300-r/", + "resolution": 4096, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -2047, + "max_position_value": 2048, + "errors": [] + }, + { + "model": "M54-40-S250-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m54-40-s250-r/", + "resolution": 251417, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -125708, + "max_position_value": 125708, + "errors": [] + }, + { + "model": "M54-60-S250-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m54-60-s250-r/", + "resolution": 251417, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -125708, + "max_position_value": 125708, + "errors": [] + }, + { + "model": "M42-10-S260-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m42-10-s260-r/", + "resolution": 263187, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -131593, + "max_position_value": 131593, + "errors": [] + }, + { + "model": "M54-40-S250-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m54-40-s250-ra/", + "resolution": 502834, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -251173, + "max_position_value": 251173, + "errors": [] + }, + { + "model": "M54-60-S250-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m54-60-s250-ra/", + "resolution": 502834, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -251173, + "max_position_value": 251173, + "errors": [] + }, + { + "model": "M42-10-S260-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/m42-10-s260-ra/", + "resolution": 526375, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -262931, + "max_position_value": 262931, + "errors": [] + }, + { + "model": "H54-100-S500-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h54-100-s500-r/", + "resolution": 501923, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -250961, + "max_position_value": 250961, + "errors": [] + }, + { + "model": "H54-200-S500-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h54-200-s500-r/", + "resolution": 501923, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -250961, + "max_position_value": 250961, + "errors": [] + }, + { + "model": "H42-20-S300-R", + "series": "PRO_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h42-20-s300-r/", + "resolution": 303750, + "addr_torque_enable": 562, + "addr_operating_mode": 11, + "addr_goal_position": 596, + "len_goal_position": 4, + "addr_goal_velocity": 600, + "len_goal_velocity": 4, + "addr_present_position": 611, + "len_present_position": 4, + "addr_present_velocity": 615, + "len_present_velocity": 4, + "addr_velocity_profile": 606, + "addr_moving": 17, + "addr_moving_status": null, + "addr_velocity_trajectory": null, + "len_velocity_trajectory": null, + "addr_position_trajectory": null, + "len_position_trajectory": null, + "addr_position_p_gain": 594, + "len_position_p_gain": 2, + "addr_position_i_gain": null, + "len_position_i_gain": null, + "addr_position_d_gain": null, + "len_position_d_gain": null, + "min_position_value": -151875, + "max_position_value": 151875, + "errors": [] + }, + { + "model": "H54-100-S500-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h54-100-s500-ra/", + "resolution": 1003846, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -501433, + "max_position_value": 501433, + "errors": [] + }, + { + "model": "H54-200-S500-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h54-200-s500-ra/", + "resolution": 1003846, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -501433, + "max_position_value": 501433, + "errors": [] + }, + { + "model": "H42-20-S300-R(A)", + "series": "PRO_A_SERIES", + "url": "https://emanual.robotis.com/docs/en/dxl/pro/h42-20-s300-ra/", + "resolution": 607500, + "addr_torque_enable": 512, + "addr_operating_mode": 11, + "addr_goal_position": 564, + "len_goal_position": 4, + "addr_goal_velocity": 552, + "len_goal_velocity": 4, + "addr_present_position": 580, + "len_present_position": 4, + "addr_present_velocity": 576, + "len_present_velocity": 4, + "addr_velocity_profile": 560, + "addr_moving": 24, + "addr_moving_status": 571, + "addr_velocity_trajectory": 584, + "len_velocity_trajectory": 4, + "addr_position_trajectory": 588, + "len_position_trajectory": 4, + "addr_position_p_gain": 532, + "len_position_p_gain": 2, + "addr_position_i_gain": 530, + "len_position_i_gain": 2, + "addr_position_d_gain": 528, + "len_position_d_gain": 2, + "min_position_value": -303454, + "max_position_value": 303454, + "errors": [] + } +] \ No newline at end of file diff --git a/scraper.py b/scraper.py new file mode 100644 index 0000000..3bf47a1 --- /dev/null +++ b/scraper.py @@ -0,0 +1,351 @@ +""" +scrape_dynamixel.py +------------------- +Scrapes all Dynamixel motor pages from emanual.robotis.com and outputs +a JSON file with register addresses, sizes, and specs for each model. + +Usage: + pip install requests beautifulsoup4 + python scrape_dynamixel.py + +Output: + dynamixel_configs.json +""" + +import re +import json +import time +import logging +from dataclasses import dataclass, asdict, field, make_dataclass, fields +from typing import Optional + +import requests +from bs4 import BeautifulSoup + +logging.basicConfig( + level=logging.INFO, + format="%(asctime)s %(levelname)-7s %(message)s", + datefmt="%H:%M:%S", +) +log = logging.getLogger(__name__) + +BASE_URL = "https://emanual.robotis.com" +INDEX_URL = f"{BASE_URL}/docs/en/dxl/" + +SESSION = requests.Session() +SESSION.headers.update({ + "User-Agent": "Mozilla/5.0 (compatible; DynamixelScraper/1.0)" +}) + + +# ── Data model ───────────────────────────────────────────────────────────────── +from dynamixelmotorsapi._dynamixelmotorsparameters import ModelConfig +# We extend the base SeriesConfig with an 'errors' field to capture any issues during scraping. +MotorConfig = make_dataclass( + "SeriesConfig", + [(f.name, Optional[f.type], field(default=None)) for f in fields(ModelConfig)] + + [("errors", list, field(default_factory=list))] +) + +# ── Register name → field mapping ───────────────────────────────────────────── +# +# Each entry: (fragment_to_match, addr_field, len_field_or_None) +# Matching is case-insensitive, first-match wins. +# More specific entries must come before more generic ones. + +REGISTER_MAP = [ + # Torque / mode + ("torque enable", "addr_torque_enable", "len_torque_enable", "initial_torque_enable"), + ("operating mode", "addr_operating_mode", "len_operating_mode", "initial_operating_mode"), + + # Position + ("goal position", "addr_goal_position", "len_goal_position", "initial_goal_position"), + ("present position", "addr_present_position", "len_present_position", "initial_present_position"), + ("position trajectory", "addr_position_trajectory", "len_position_trajectory", "initial_position_trajectory"), + ("position p gain", "addr_position_p_gain", "len_position_p_gain", "initial_position_p_gain"), + ("position i gain", "addr_position_i_gain", "len_position_i_gain", "initial_position_i_gain"), + ("position d gain", "addr_position_d_gain", "len_position_d_gain", "initial_position_d_gain"), + ("min position limit", "addr_min_position", "len_min_position", "min_position_value"), + ("max position limit", "addr_max_position", "len_max_position", "max_position_value"), + + # Velocity + ("goal velocity", "addr_goal_velocity", "len_goal_velocity", "initial_goal_velocity"), + ("present velocity", "addr_present_velocity", "len_present_velocity", "initial_present_velocity"), + ("velocity trajectory", "addr_velocity_trajectory", "len_velocity_trajectory", "initial_velocity_trajectory"), + ("profile velocity", "addr_velocity_profile", "len_velocity_profile", "initial_velocity_profile"), + ("goal acceleration", "addr_velocity_profile", "len_velocity_profile", "initial_velocity_profile"), # PRO series uses same field for acceleration + + # Moving + ("moving status", "addr_moving_status", "len_moving_status", "initial_moving_status"), + ("moving", "addr_moving", "len_moving", "initial_moving"), +] + + +# ── Series detection ─────────────────────────────────────────────────────────── + +def detect_series(url: str) -> str: + u = url.lower() + if "/dxl/y/" in u: return "Y_SERIES" + if "/dxl/p/" in u: return "P_SERIES" + if "/dxl/x/" in u: return "X_SERIES" + if "/dxl/mx/" in u: return "MX_SERIES" + if "/dxl/ax/" in u: return "AX_SERIES" + if "/dxl/rx/" in u: return "RX_SERIES" + if "/dxl/ex/" in u: return "EX_SERIES" + if "/dxl/dx/" in u: return "DX_SERIES" + if "/dxl/pro/" in u: + # URLs ending in 'a/' or 'ra/' are the (A) advanced firmware + return "PRO_A_SERIES" if re.search(r"[/-]r?a/?$", u) else "PRO_SERIES" + return "UNKNOWN" + + +# ── Page fetching ────────────────────────────────────────────────────────────── + +def fetch(url: str, retries: int = 3) -> Optional[BeautifulSoup]: + for attempt in range(retries): + try: + resp = SESSION.get(url, timeout=15) + resp.raise_for_status() + return BeautifulSoup(resp.text, "html.parser") + except requests.RequestException as e: + wait = 2 ** attempt + log.warning(f" Fetch error ({e}), retrying in {wait}s…") + time.sleep(wait) + return None + + +# ── Index scraping ───────────────────────────────────────────────────────────── + +# URL path segments that are NOT individual motor pages +_SKIP_PATHS = { + "/docs/en/dxl/", + "/docs/en/dxl/protocol1/", + "/docs/en/dxl/protocol2/", + "/docs/en/dxl/dxl-quick-start-guide/", + "/docs/en/dxl/x/", + "/docs/en/dxl/mx/", + "/docs/en/dxl/p/", + "/docs/en/dxl/pro/", + "/docs/en/dxl/y/", +} + +def get_motor_urls() -> list[tuple[str, str]]: + """ + Return a list of (model_name, absolute_url) for every motor listed + in the sidebar of the DYNAMIXEL index page, restricted to /docs/en/dxl/. + """ + soup = fetch(INDEX_URL) + if not soup: + raise RuntimeError("Could not fetch index page") + + seen = set() + motors = [] + + # The sidebar