From 724d6caec4e71019c81f328d0526c442f5dbd006 Mon Sep 17 00:00:00 2001 From: Alexandre Kruszewski Date: Wed, 25 Mar 2026 16:59:52 +0100 Subject: [PATCH 1/3] Communication Timing improvement + PWM mode + example + Changed pid example --- emioapi/_emiomotorsparameters.py | 3 + emioapi/_motorgroup.py | 31 ++++++++-- emioapi/emiomotors.py | 15 +++++ examples/motors_pid_position.py | 14 +++-- examples/motors_pwm.py | 102 +++++++++++++++++++++++++++++++ 5 files changed, 153 insertions(+), 12 deletions(-) create mode 100644 examples/motors_pwm.py diff --git a/emioapi/_emiomotorsparameters.py b/emioapi/_emiomotorsparameters.py index f381fa0..60eeca8 100644 --- a/emioapi/_emiomotorsparameters.py +++ b/emioapi/_emiomotorsparameters.py @@ -34,12 +34,15 @@ VELOCITY_MODE = 1 POSITION_MODE = 3 EXT_POSITION_MODE = 4 +PWM_MODE = 16 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_GOAL_PWM = 100 + LEN_GOAL_PWM = 2 ADDR_PRESENT_POSITION = 132 LEN_PRESENT_POSITION = 4 # Data Byte Length ADDR_PRESENT_VELOCITY = 128 diff --git a/emioapi/_motorgroup.py b/emioapi/_motorgroup.py index 9c5ddd3..3546d75 100644 --- a/emioapi/_motorgroup.py +++ b/emioapi/_motorgroup.py @@ -145,6 +145,9 @@ def __init__(self, parameters: MotorsParametersTemplate) -> None: self.groupWriters["goal_velocity"] = GroupSyncWrite(self.portHandler, self.packetHandler, self.parameters.ADDR_GOAL_VELOCITY, self.parameters.LEN_GOAL_POSITION) + self.groupWriters["goal_pwm"] = GroupSyncWrite(self.portHandler, self.packetHandler, + self.parameters.ADDR_GOAL_PWM, + self.parameters.LEN_GOAL_PWM) self.groupWriters["velocity_profile"] = GroupSyncWrite(self.portHandler, self.packetHandler, self.parameters.ADDR_VELOCITY_PROFILE, self.parameters.LEN_GOAL_POSITION) @@ -221,9 +224,9 @@ def _readSyncMotorsData(self, groupSyncRead:GroupSyncRead): Raises: Exception: If the motor group is not connected or if the read operation fails. - """ - if not self.isConnected: - raise DisconnectedException() + # """ + # if not self.isConnected: + # raise DisconnectedException() dxl_comm_result = groupSyncRead.txRxPacket() if dxl_comm_result != COMM_SUCCESS: @@ -246,9 +249,9 @@ def __writeSyncMotorsData(self, group: GroupSyncWrite, values): group (GroupSyncWrite): The group sync write object. values (list of numbers): The values to write to the motors. """ - if not self.isConnected: - raise DisconnectedException() - + # if not self.isConnected: + # raise DisconnectedException() + group.clearParam() for index, DXL_ID in enumerate(self.parameters.DXL_IDs): if group.data_length == 2: @@ -314,6 +317,15 @@ def enableExtendedPositionMode(self): if any(t==1 for t in torques): self.enableTorque() + def enablePWMMode(self): + torques = self.isTorqueEnable() + + if any(t==1 for t in torques): + self.disableTorque() + self.__setOperatingMode(self.parameters.PWM_MODE) + if any(t==1 for t in torques): + self.enableTorque() + def enablePositionMode(self): torques = self.isTorqueEnable() @@ -342,6 +354,13 @@ def setGoalPosition(self, positions): """ self.__writeSyncMotorsData(self.groupWriters["goal_position"], positions) + def setGoalPWM(self, pwms): + """Set the goal velocity + + Args: + speeds (list of numbers): unit depends on motor type + """ + self.__writeSyncMotorsData(self.groupWriters["goal_pwm"] , pwms) def setVelocityProfile(self, max_vel): """Set the maximum velocities in position mode diff --git a/emioapi/emiomotors.py b/emioapi/emiomotors.py index d6c3b52..451eea6 100644 --- a/emioapi/emiomotors.py +++ b/emioapi/emiomotors.py @@ -46,6 +46,7 @@ class EmioMotors: _max_vel: float = 1000 # *0.01 rev/min _goal_velocity: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) _goal_position: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) + _goal_pwm: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) _mg: motorgroup.MotorGroup = None _device_index: int = None @@ -222,6 +223,8 @@ def enablePositionMode(self): def enableExtendedPositionMode(self): self._mg.enableExtendedPositionMode() + def enablePWMMode(self): + self._mg.enablePWMMode() #################### #### PROPERTIES #### @@ -275,6 +278,18 @@ def goal_velocity(self, velocities: list): self._mg.setGoalVelocity(velocities) + @property + def goal_pwm(self) -> list: + """Get the current velocity (rev/min) of the motors.""" + return self._goal_pwm + + @goal_pwm.setter + def goal_pwm(self, pwms: list): + """Set the goal velocity (rev/min) of the motors.""" + self._goal_pwm = pwms + with self._lock: + self._mg.setGoalPWM(pwms) + @property def max_velocity(self)-> list: """Get the current velocity (rev/min) profile of the motors.""" diff --git a/examples/motors_pid_position.py b/examples/motors_pid_position.py index cb6cb3d..87a7462 100644 --- a/examples/motors_pid_position.py +++ b/examples/motors_pid_position.py @@ -1,7 +1,11 @@ import numpy as np +import matplotlib +matplotlib.use("TkAgg") import matplotlib.pyplot as plt import time - +import sys +import os +sys.path.append(os.path.dirname(os.path.realpath(__file__))+'/..') from emioapi import EmioMotors @@ -15,8 +19,8 @@ def main(): print("Motors opened successfully.") # initial and target angles - init_angles = np.array([0.5, 0, 0.5, 0]) - target_angles = init_angles + np.array([0.4, 0, 0, 0]) + init_angles = np.array([0.0, 0, 0.0, 0]) + target_angles = init_angles + np.array([0.1, 0, 0, 0]) motors.angles = init_angles time.sleep(1) @@ -42,7 +46,6 @@ def main(): while time.time() - t0 < 0.3: measures.append(motors.angles) times.append(time.time()) - time.sleep(0.01) time.sleep(1) nb_steps1 = len(measures) @@ -51,7 +54,7 @@ def main(): motors.position_p_gain = [15800, 800, 15800, 800] motors.position_i_gain = [0, 0, 0, 0] - motors.position_d_gain = [600, 0, 600, 0] + motors.position_d_gain = [0, 0, 0, 0] print("Set second PID gains.") time.sleep(1) @@ -70,7 +73,6 @@ def main(): while time.time() - t0 < 0.3: measures.append(motors.angles) times.append(time.time()) - time.sleep(0.01) time.sleep(1) motors.close() diff --git a/examples/motors_pwm.py b/examples/motors_pwm.py new file mode 100644 index 0000000..f37a7e0 --- /dev/null +++ b/examples/motors_pwm.py @@ -0,0 +1,102 @@ +#!/usr/bin/env -S uv run --script + +import time +import logging +import os +import sys +import matplotlib +matplotlib.use("TkAgg") +import matplotlib.pyplot as plt +import numpy as np +sys.path.append(os.path.dirname(os.path.realpath(__file__))+'/..') +from emioapi import EmioMotors +from emioapi._logging_config import logger + +''' +This example demonstrates how to use the EMIO API to control DYNAMIXEL motors in PWM mode. +''' + +def main(emio: EmioMotors, loops=500, motor_id=1): + ''' + Main function to run the PWM test. + Parameters: + - emio: An instance of the EmioMotors class. + - loops: Number of iterations to run the test. + - motor_id: ID of the motor to test (0-3). + ''' + # Enable PWM mode + emio._mg.enablePWMMode() + time.sleep(1) + emio.printStatus() + + # Intialize lists to store data for plotting + start = time.perf_counter() + last = start + dt = [] + speed = [] + pwm = [] + t = [] + pwm_value = [0]*4 + + # Loop to set PWM values and read velocity + for i in range(loops): + # Record loop time and elapsed time + new = time.perf_counter() + dt.append(new-last) + t.append(new-start) + last = new + + # Alternate PWM values for the first half and second half of the loops + if i Date: Wed, 25 Mar 2026 17:50:43 +0100 Subject: [PATCH 2/3] Uses dynamixelMotorsAPI --- emioapi/__init__.py | 2 +- emioapi/emioapi.py | 2 +- emioapi/emiomotors.py | 371 +++---------------------------------- examples/motors_example.py | 4 +- pyproject.toml | 16 +- uv.lock | 204 ++++++++++++++++++++ 6 files changed, 240 insertions(+), 359 deletions(-) diff --git a/emioapi/__init__.py b/emioapi/__init__.py index a4aff1e..5d2f82e 100644 --- a/emioapi/__init__.py +++ b/emioapi/__init__.py @@ -1,4 +1,4 @@ from .emiocamera import EmioCamera, CalibrationStatusEnum -from .emiomotors import EmioMotors, motorgroup +from .emiomotors import EmioMotors from .multiprocessemiocamera import MultiprocessEmioCamera from .emioapi import EmioAPI \ No newline at end of file diff --git a/emioapi/emioapi.py b/emioapi/emioapi.py index f2bb29c..55c5ff3 100644 --- a/emioapi/emioapi.py +++ b/emioapi/emioapi.py @@ -23,7 +23,7 @@ from threading import Lock -from emioapi import EmioMotors, motorgroup +from emioapi import EmioMotors from emioapi import MultiprocessEmioCamera from emioapi import EmioCamera, emiocamera from emioapi._logging_config import logger diff --git a/emioapi/emiomotors.py b/emioapi/emiomotors.py index d6c3b52..c866f29 100644 --- a/emioapi/emiomotors.py +++ b/emioapi/emiomotors.py @@ -2,11 +2,13 @@ from threading import Lock from math import pi +from dynamixelmotorsapi import DynamixelMotors + import emioapi._motorgroup as motorgroup import emioapi._emiomotorsparameters as emioparameters from emioapi._logging_config import logger -class EmioMotors: +class EmioMotors(DynamixelMotors): """ Class to control emio motors. The class is designed to be used with the emio device. @@ -38,16 +40,16 @@ class EmioMotors: """ - _initialized: bool = False - _length_to_rad: float = 1.0 / 20.0 # 1/radius of the pulley - _rad_to_pulse: int = 4096 / (2 * pi) # the resolution of the Dynamixel xm430 w210 - _length_to_pulse: int = _length_to_rad * _rad_to_pulse - _pulse_center: int = 2048 - _max_vel: float = 1000 # *0.01 rev/min - _goal_velocity: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) - _goal_position: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) - _mg: motorgroup.MotorGroup = None - _device_index: int = None + # _initialized: bool = False + # _length_to_rad: float = 1.0 / 20.0 # 1/radius of the pulley + # _rad_to_pulse: int = 4096 / (2 * pi) # the resolution of the Dynamixel xm430 w210 + # _length_to_pulse: int = _length_to_rad * _rad_to_pulse + # _pulse_center: int = 2048 + # _max_vel: float = 1000 # *0.01 rev/min + # _goal_velocity: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) + # _goal_position: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) + # _mg: motorgroup.MotorGroup = None + # _device_index: int = None @@ -58,342 +60,11 @@ class EmioMotors: def __init__(self): - self._lock = Lock() - if not self._initialized: - self._mg = motorgroup.MotorGroup(emioparameters) - self._initialized = True - - - def lengthToPulse(self, displacement: list): - """ - Convert length (mm) to pulse using the conversion factor `lengthToPulse`. - - Args: - displacement: list: list of length values in mm for each motor. - - Returns: - A list of pulse values for each motor. - """ - return [self._pulse_center - int(item * self._length_to_pulse) for item in displacement] - - - def pulseToLength(self, pulse: list): - """ - Convert pulse to length (mm) using the conversion factor `lengthToPulse`. - - Args: - pulse: list of pulse integer values for each 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] - - - def pulseToRad(self, pulse: list): - """ - Convert pulse to radians using the conversion factor `radToPulse`. - - Args: - pulse: list: list of pulse integer values for each 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] - - - def pulseToDeg(self, pulse: list): - """ - Convert pulse to degrees using the conversion factor `radToPulse`. - - Args: - pulse: list: list of pulse values for each 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] - - - 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.""" - with self._lock: - try: - self._mg.updateDeviceName(device_name) - - if self._mg.deviceName is None: - logger.error("Device name is None. Please check the connection.") - return False - - self._mg.open() - self._mg.disableTorque() - self._mg.clearPort() - if multi_turn: - self.enableExtendedPositionMode() - else: - self.enablePositionMode() - self._mg.enableTorque() - - logger.debug(f"Motor group opened and configured. Device name: {self._mg.deviceName}, Multi turn activated: {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: - """ - 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 emio 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π] - """ - if self._openAndConfig(device_name, multi_turn): - self._device_index = motorgroup.listMotors().index(self._mg.deviceName) - logger.info(f"Connected to emio device: {self._mg.deviceName}") - return True - return False - - - 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 emio motors. - - 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π] - - Returns: - the index in the list of port to which it connected. If no connection was possible, returns -1. - """ - if device_name is not None: - try: - index = motorgroup.listMotors().index(device_name) - logger.info(f"Trying given emio number {index} on port: {device_name}.") - return index if len(motorgroup.listMotors())>0 and self.open(device_name, multi_turn) else -1 - except: - return -1 - - index = 0 - - connected = False - try: - - while not connected and index list: - """Get the current angles of the motors in radians.""" - with self._lock: - return self.pulseToRad(self._mg.getCurrentPosition()) - - @angles.setter - 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]) - - - @property - def goal_velocity(self) -> list: - """Get the current velocity (rev/min) of the motors.""" - return self._goal_velocity - - @goal_velocity.setter - def goal_velocity(self, velocities: list): - """Set the goal velocity (rev/min) of the motors.""" - 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 - - @max_velocity.setter - def max_velocity(self, max_vel: list): - """Set the maximum velocities (rev/min) in position mode. - Arguments: - max_vel: list of maximum velocities for each motor in rev/min. - """ - self._max_vel = max_vel - with self._lock: - self._mg.setVelocityProfile(max_vel) - - - @property - def position_p_gain(self) -> list: - """Get the current position P gains of the motors.""" - with self._lock: - return self._mg.getPositionPGain() - - @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. - """ - with self._lock: - self._mg.setPositionPGain(p_gains) - - - @property - def position_i_gain(self) -> list: - """Get the current position I gains of the motors.""" - with self._lock: - return self._mg.getPositionIGain() - - @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. - """ - with self._lock: - self._mg.setPositionIGain(i_gains) - - - @property - def position_d_gain(self) -> list: - """Get the current position D gains of the motors.""" - with self._lock: - return self._mg.getPositionDGain() - - @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. - """ - with self._lock: - self._mg.setPositionDGain(d_gains) - - - #### Read-only properties #### - @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.""" - with self._lock: - return self._mg.deviceName - - - @property - def device_index(self) -> int: - """Get the index of the device in the list of Emio Devices from EmioAPI""" - 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. - - See [here](https://emanual.robotis.com/docs/en/dxl/x/xc330-t288/#moving-status) for more 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: - """Get the velocity (rev/min) trajectory of the motors.""" - with self._lock: - return self._mg.getVelocityTrajectory() - - - @property - def position_trajectory(self)-> list: - """Get the position (pulse) trajectory of the motors.""" - with self._lock: - return self._mg.getPositionTrajectory() + super().__init__([{ + "id": [0, 1, 2, 3], + "model": "XM430-W210", + "pulley_radius": 20, + "pulse_center": 2048, + "max_vel": 1000, + "baud_rate": 1000000 + }]) diff --git a/examples/motors_example.py b/examples/motors_example.py index 2247961..afa0ede 100644 --- a/examples/motors_example.py +++ b/examples/motors_example.py @@ -37,6 +37,7 @@ def main(emio: EmioMotors, loops=1): if __name__ == "__main__": + emio_motors = None try: logger.info("Starting EMIO API test...") logger.info("Opening and configuring EMIO API...") @@ -58,4 +59,5 @@ def main(emio: EmioMotors, loops=1): logger.info("Emio connection closed.") except Exception as e: logger.exception(f"An error occurred: {e}") - emio_motors.close() \ No newline at end of file + if emio_motors: + emio_motors.close() \ No newline at end of file diff --git a/pyproject.toml b/pyproject.toml index d17660f..38788cc 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -9,12 +9,13 @@ requires-python = ">=3.10" readme = "README.md" dependencies = [ "pyserial", - "dynamixel_sdk", - "pyrealsense2; platform_system != 'Darwin'", - "pyrealsense2-macosx; platform_system == 'Darwin'", - "opencv-python", - "numpy==1.26.4", - "pillow", + "dynamixel_sdk", + "pyrealsense2; platform_system != 'Darwin'", + "pyrealsense2-macosx; platform_system == 'Darwin'", + "opencv-python", + "numpy==1.26.4", + "pillow", + "dynamixelmotorsapi", ] description = "An API for controlling the motors of the EMIO robot." keywords = ["roboticsc", "emio", "api"] @@ -72,3 +73,6 @@ Class = 2 Method = 3 Function = 3 Data = 3 + +[tool.uv.sources] +dynamixelmotorsapi = { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" } diff --git a/uv.lock b/uv.lock index e3cc42b..a1d59a9 100644 --- a/uv.lock +++ b/uv.lock @@ -13,6 +13,133 @@ resolution-markers = [ "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux')", ] +[[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.6" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/7b/60/e3bec1881450851b087e301bedc3daa9377a4d45f1c26aa90b0b235e38aa/charset_normalizer-3.4.6.tar.gz", hash = "sha256:1ae6b62897110aa7c79ea2f5dd38d1abca6db663687c0b1ad9aed6f6bae3d9d6", size = 143363, upload-time = "2026-03-15T18:53:25.478Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e6/8c/2c56124c6dc53a774d435f985b5973bc592f42d437be58c0c92d65ae7296/charset_normalizer-3.4.6-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:2e1d8ca8611099001949d1cdfaefc510cf0f212484fe7c565f735b68c78c3c95", size = 298751, upload-time = "2026-03-15T18:50:00.003Z" }, + { url = "https://files.pythonhosted.org/packages/86/2a/2a7db6b314b966a3bcad8c731c0719c60b931b931de7ae9f34b2839289ee/charset_normalizer-3.4.6-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e25369dc110d58ddf29b949377a93e0716d72a24f62bad72b2b39f155949c1fd", size = 200027, upload-time = "2026-03-15T18:50:01.702Z" }, + { url = "https://files.pythonhosted.org/packages/68/f2/0fe775c74ae25e2a3b07b01538fc162737b3e3f795bada3bc26f4d4d495c/charset_normalizer-3.4.6-cp310-cp310-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:259695e2ccc253feb2a016303543d691825e920917e31f894ca1a687982b1de4", size = 220741, upload-time = "2026-03-15T18:50:03.194Z" }, + { url = "https://files.pythonhosted.org/packages/10/98/8085596e41f00b27dd6aa1e68413d1ddda7e605f34dd546833c61fddd709/charset_normalizer-3.4.6-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:dda86aba335c902b6149a02a55b38e96287157e609200811837678214ba2b1db", size = 215802, upload-time = "2026-03-15T18:50:05.859Z" }, + { url = "https://files.pythonhosted.org/packages/fd/ce/865e4e09b041bad659d682bbd98b47fb490b8e124f9398c9448065f64fee/charset_normalizer-3.4.6-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:51fb3c322c81d20567019778cb5a4a6f2dc1c200b886bc0d636238e364848c89", size = 207908, upload-time = "2026-03-15T18:50:07.676Z" }, + { url = "https://files.pythonhosted.org/packages/a8/54/8c757f1f7349262898c2f169e0d562b39dcb977503f18fdf0814e923db78/charset_normalizer-3.4.6-cp310-cp310-manylinux_2_31_armv7l.whl", hash = "sha256:4482481cb0572180b6fd976a4d5c72a30263e98564da68b86ec91f0fe35e8565", size = 194357, upload-time = "2026-03-15T18:50:09.327Z" }, + { url = "https://files.pythonhosted.org/packages/6f/29/e88f2fac9218907fc7a70722b393d1bbe8334c61fe9c46640dba349b6e66/charset_normalizer-3.4.6-cp310-cp310-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:39f5068d35621da2881271e5c3205125cc456f54e9030d3f723288c873a71bf9", size = 205610, upload-time = "2026-03-15T18:50:10.732Z" }, + { url = "https://files.pythonhosted.org/packages/4c/c5/21d7bb0cb415287178450171d130bed9d664211fdd59731ed2c34267b07d/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:8bea55c4eef25b0b19a0337dc4e3f9a15b00d569c77211fa8cde38684f234fb7", size = 203512, upload-time = "2026-03-15T18:50:12.535Z" }, + { url = "https://files.pythonhosted.org/packages/a4/be/ce52f3c7fdb35cc987ad38a53ebcef52eec498f4fb6c66ecfe62cfe57ba2/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_armv7l.whl", hash = "sha256:f0cdaecd4c953bfae0b6bb64910aaaca5a424ad9c72d85cb88417bb9814f7550", size = 195398, upload-time = "2026-03-15T18:50:14.236Z" }, + { url = "https://files.pythonhosted.org/packages/81/a0/3ab5dd39d4859a3555e5dadfc8a9fa7f8352f8c183d1a65c90264517da0e/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:150b8ce8e830eb7ccb029ec9ca36022f756986aaaa7956aad6d9ec90089338c0", size = 221772, upload-time = "2026-03-15T18:50:15.581Z" }, + { url = "https://files.pythonhosted.org/packages/04/6e/6a4e41a97ba6b2fa87f849c41e4d229449a586be85053c4d90135fe82d26/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_riscv64.whl", hash = "sha256:e68c14b04827dd76dcbd1aeea9e604e3e4b78322d8faf2f8132c7138efa340a8", size = 205759, upload-time = "2026-03-15T18:50:17.047Z" }, + { url = "https://files.pythonhosted.org/packages/db/3b/34a712a5ee64a6957bf355b01dc17b12de457638d436fdb05d01e463cd1c/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:3778fd7d7cd04ae8f54651f4a7a0bd6e39a0cf20f801720a4c21d80e9b7ad6b0", size = 216938, upload-time = "2026-03-15T18:50:18.44Z" }, + { url = "https://files.pythonhosted.org/packages/cb/05/5bd1e12da9ab18790af05c61aafd01a60f489778179b621ac2a305243c62/charset_normalizer-3.4.6-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:dad6e0f2e481fffdcf776d10ebee25e0ef89f16d691f1e5dee4b586375fdc64b", size = 210138, upload-time = "2026-03-15T18:50:19.852Z" }, + { url = "https://files.pythonhosted.org/packages/bd/8e/3cb9e2d998ff6b21c0a1860343cb7b83eba9cdb66b91410e18fc4969d6ab/charset_normalizer-3.4.6-cp310-cp310-win32.whl", hash = "sha256:74a2e659c7ecbc73562e2a15e05039f1e22c75b7c7618b4b574a3ea9118d1557", size = 144137, upload-time = "2026-03-15T18:50:21.505Z" }, + { url = "https://files.pythonhosted.org/packages/d8/8f/78f5489ffadb0db3eb7aff53d31c24531d33eb545f0c6f6567c25f49a5ff/charset_normalizer-3.4.6-cp310-cp310-win_amd64.whl", hash = "sha256:aa9cccf4a44b9b62d8ba8b4dd06c649ba683e4bf04eea606d2e94cfc2d6ff4d6", size = 154244, upload-time = "2026-03-15T18:50:22.81Z" }, + { url = "https://files.pythonhosted.org/packages/e4/74/e472659dffb0cadb2f411282d2d76c60da1fc94076d7fffed4ae8a93ec01/charset_normalizer-3.4.6-cp310-cp310-win_arm64.whl", hash = "sha256:e985a16ff513596f217cee86c21371b8cd011c0f6f056d0920aa2d926c544058", size = 143312, upload-time = "2026-03-15T18:50:24.074Z" }, + { url = "https://files.pythonhosted.org/packages/62/28/ff6f234e628a2de61c458be2779cb182bc03f6eec12200d4a525bbfc9741/charset_normalizer-3.4.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:82060f995ab5003a2d6e0f4ad29065b7672b6593c8c63559beefe5b443242c3e", size = 293582, upload-time = "2026-03-15T18:50:25.454Z" }, + { url = "https://files.pythonhosted.org/packages/1c/b7/b1a117e5385cbdb3205f6055403c2a2a220c5ea80b8716c324eaf75c5c95/charset_normalizer-3.4.6-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:60c74963d8350241a79cb8feea80e54d518f72c26db618862a8f53e5023deaf9", size = 197240, upload-time = "2026-03-15T18:50:27.196Z" }, + { url = "https://files.pythonhosted.org/packages/a1/5f/2574f0f09f3c3bc1b2f992e20bce6546cb1f17e111c5be07308dc5427956/charset_normalizer-3.4.6-cp311-cp311-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:f6e4333fb15c83f7d1482a76d45a0818897b3d33f00efd215528ff7c51b8e35d", size = 217363, upload-time = "2026-03-15T18:50:28.601Z" }, + { url = "https://files.pythonhosted.org/packages/4a/d1/0ae20ad77bc949ddd39b51bf383b6ca932f2916074c95cad34ae465ab71f/charset_normalizer-3.4.6-cp311-cp311-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:bc72863f4d9aba2e8fd9085e63548a324ba706d2ea2c83b260da08a59b9482de", size = 212994, upload-time = "2026-03-15T18:50:30.102Z" }, + { url = "https://files.pythonhosted.org/packages/60/ac/3233d262a310c1b12633536a07cde5ddd16985e6e7e238e9f3f9423d8eb9/charset_normalizer-3.4.6-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9cc4fc6c196d6a8b76629a70ddfcd4635a6898756e2d9cac5565cf0654605d73", size = 204697, upload-time = "2026-03-15T18:50:31.654Z" }, + { url = "https://files.pythonhosted.org/packages/25/3c/8a18fc411f085b82303cfb7154eed5bd49c77035eb7608d049468b53f87c/charset_normalizer-3.4.6-cp311-cp311-manylinux_2_31_armv7l.whl", hash = "sha256:0c173ce3a681f309f31b87125fecec7a5d1347261ea11ebbb856fa6006b23c8c", size = 191673, upload-time = "2026-03-15T18:50:33.433Z" }, + { url = "https://files.pythonhosted.org/packages/ff/a7/11cfe61d6c5c5c7438d6ba40919d0306ed83c9ab957f3d4da2277ff67836/charset_normalizer-3.4.6-cp311-cp311-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:c907cdc8109f6c619e6254212e794d6548373cc40e1ec75e6e3823d9135d29cc", size = 201120, upload-time = "2026-03-15T18:50:35.105Z" }, + { url = "https://files.pythonhosted.org/packages/b5/10/cf491fa1abd47c02f69687046b896c950b92b6cd7337a27e6548adbec8e4/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:404a1e552cf5b675a87f0651f8b79f5f1e6fd100ee88dc612f89aa16abd4486f", size = 200911, upload-time = "2026-03-15T18:50:36.819Z" }, + { url = "https://files.pythonhosted.org/packages/28/70/039796160b48b18ed466fde0af84c1b090c4e288fae26cd674ad04a2d703/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_armv7l.whl", hash = "sha256:e3c701e954abf6fc03a49f7c579cc80c2c6cc52525340ca3186c41d3f33482ef", size = 192516, upload-time = "2026-03-15T18:50:38.228Z" }, + { url = "https://files.pythonhosted.org/packages/ff/34/c56f3223393d6ff3124b9e78f7de738047c2d6bc40a4f16ac0c9d7a1cb3c/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:7a6967aaf043bceabab5412ed6bd6bd26603dae84d5cb75bf8d9a74a4959d398", size = 218795, upload-time = "2026-03-15T18:50:39.664Z" }, + { url = "https://files.pythonhosted.org/packages/e8/3b/ce2d4f86c5282191a041fdc5a4ce18f1c6bd40a5bd1f74cf8625f08d51c1/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_riscv64.whl", hash = "sha256:5feb91325bbceade6afab43eb3b508c63ee53579fe896c77137ded51c6b6958e", size = 201833, upload-time = "2026-03-15T18:50:41.552Z" }, + { url = "https://files.pythonhosted.org/packages/3b/9b/b6a9f76b0fd7c5b5ec58b228ff7e85095370282150f0bd50b3126f5506d6/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:f820f24b09e3e779fe84c3c456cb4108a7aa639b0d1f02c28046e11bfcd088ed", size = 213920, upload-time = "2026-03-15T18:50:43.33Z" }, + { url = "https://files.pythonhosted.org/packages/ae/98/7bc23513a33d8172365ed30ee3a3b3fe1ece14a395e5fc94129541fc6003/charset_normalizer-3.4.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b35b200d6a71b9839a46b9b7fff66b6638bb52fc9658aa58796b0326595d3021", size = 206951, upload-time = "2026-03-15T18:50:44.789Z" }, + { url = "https://files.pythonhosted.org/packages/32/73/c0b86f3d1458468e11aec870e6b3feac931facbe105a894b552b0e518e79/charset_normalizer-3.4.6-cp311-cp311-win32.whl", hash = "sha256:9ca4c0b502ab399ef89248a2c84c54954f77a070f28e546a85e91da627d1301e", size = 143703, upload-time = "2026-03-15T18:50:46.103Z" }, + { url = "https://files.pythonhosted.org/packages/c6/e3/76f2facfe8eddee0bbd38d2594e709033338eae44ebf1738bcefe0a06185/charset_normalizer-3.4.6-cp311-cp311-win_amd64.whl", hash = "sha256:a9e68c9d88823b274cf1e72f28cb5dc89c990edf430b0bfd3e2fb0785bfeabf4", size = 153857, upload-time = "2026-03-15T18:50:47.563Z" }, + { url = "https://files.pythonhosted.org/packages/e2/dc/9abe19c9b27e6cd3636036b9d1b387b78c40dedbf0b47f9366737684b4b0/charset_normalizer-3.4.6-cp311-cp311-win_arm64.whl", hash = "sha256:97d0235baafca5f2b09cf332cc275f021e694e8362c6bb9c96fc9a0eb74fc316", size = 142751, upload-time = "2026-03-15T18:50:49.234Z" }, + { url = "https://files.pythonhosted.org/packages/e5/62/c0815c992c9545347aeea7859b50dc9044d147e2e7278329c6e02ac9a616/charset_normalizer-3.4.6-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:2ef7fedc7a6ecbe99969cd09632516738a97eeb8bd7258bf8a0f23114c057dab", size = 295154, upload-time = "2026-03-15T18:50:50.88Z" }, + { url = "https://files.pythonhosted.org/packages/a8/37/bdca6613c2e3c58c7421891d80cc3efa1d32e882f7c4a7ee6039c3fc951a/charset_normalizer-3.4.6-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a4ea868bc28109052790eb2b52a9ab33f3aa7adc02f96673526ff47419490e21", size = 199191, upload-time = "2026-03-15T18:50:52.658Z" }, + { url = "https://files.pythonhosted.org/packages/6c/92/9934d1bbd69f7f398b38c5dae1cbf9cc672e7c34a4adf7b17c0a9c17d15d/charset_normalizer-3.4.6-cp312-cp312-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:836ab36280f21fc1a03c99cd05c6b7af70d2697e374c7af0b61ed271401a72a2", size = 218674, upload-time = "2026-03-15T18:50:54.102Z" }, + { url = "https://files.pythonhosted.org/packages/af/90/25f6ab406659286be929fd89ab0e78e38aa183fc374e03aa3c12d730af8a/charset_normalizer-3.4.6-cp312-cp312-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:f1ce721c8a7dfec21fcbdfe04e8f68174183cf4e8188e0645e92aa23985c57ff", size = 215259, upload-time = "2026-03-15T18:50:55.616Z" }, + { url = "https://files.pythonhosted.org/packages/4e/ef/79a463eb0fff7f96afa04c1d4c51f8fc85426f918db467854bfb6a569ce3/charset_normalizer-3.4.6-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:0e28d62a8fc7a1fa411c43bd65e346f3bce9716dc51b897fbe930c5987b402d5", size = 207276, upload-time = "2026-03-15T18:50:57.054Z" }, + { url = "https://files.pythonhosted.org/packages/f7/72/d0426afec4b71dc159fa6b4e68f868cd5a3ecd918fec5813a15d292a7d10/charset_normalizer-3.4.6-cp312-cp312-manylinux_2_31_armv7l.whl", hash = "sha256:530d548084c4a9f7a16ed4a294d459b4f229db50df689bfe92027452452943a0", size = 195161, upload-time = "2026-03-15T18:50:58.686Z" }, + { url = "https://files.pythonhosted.org/packages/bf/18/c82b06a68bfcb6ce55e508225d210c7e6a4ea122bfc0748892f3dc4e8e11/charset_normalizer-3.4.6-cp312-cp312-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:30f445ae60aad5e1f8bdbb3108e39f6fbc09f4ea16c815c66578878325f8f15a", size = 203452, upload-time = "2026-03-15T18:51:00.196Z" }, + { url = "https://files.pythonhosted.org/packages/44/d6/0c25979b92f8adafdbb946160348d8d44aa60ce99afdc27df524379875cb/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:ac2393c73378fea4e52aa56285a3d64be50f1a12395afef9cce47772f60334c2", size = 202272, upload-time = "2026-03-15T18:51:01.703Z" }, + { url = "https://files.pythonhosted.org/packages/2e/3d/7fea3e8fe84136bebbac715dd1221cc25c173c57a699c030ab9b8900cbb7/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_armv7l.whl", hash = "sha256:90ca27cd8da8118b18a52d5f547859cc1f8354a00cd1e8e5120df3e30d6279e5", size = 195622, upload-time = "2026-03-15T18:51:03.526Z" }, + { url = "https://files.pythonhosted.org/packages/57/8a/d6f7fd5cb96c58ef2f681424fbca01264461336d2a7fc875e4446b1f1346/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:8e5a94886bedca0f9b78fecd6afb6629142fd2605aa70a125d49f4edc6037ee6", size = 220056, upload-time = "2026-03-15T18:51:05.269Z" }, + { url = "https://files.pythonhosted.org/packages/16/50/478cdda782c8c9c3fb5da3cc72dd7f331f031e7f1363a893cdd6ca0f8de0/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_riscv64.whl", hash = "sha256:695f5c2823691a25f17bc5d5ffe79fa90972cc34b002ac6c843bb8a1720e950d", size = 203751, upload-time = "2026-03-15T18:51:06.858Z" }, + { url = "https://files.pythonhosted.org/packages/75/fc/cc2fcac943939c8e4d8791abfa139f685e5150cae9f94b60f12520feaa9b/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:231d4da14bcd9301310faf492051bee27df11f2bc7549bc0bb41fef11b82daa2", size = 216563, upload-time = "2026-03-15T18:51:08.564Z" }, + { url = "https://files.pythonhosted.org/packages/a8/b7/a4add1d9a5f68f3d037261aecca83abdb0ab15960a3591d340e829b37298/charset_normalizer-3.4.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:a056d1ad2633548ca18ffa2f85c202cfb48b68615129143915b8dc72a806a923", size = 209265, upload-time = "2026-03-15T18:51:10.312Z" }, + { url = "https://files.pythonhosted.org/packages/6c/18/c094561b5d64a24277707698e54b7f67bd17a4f857bbfbb1072bba07c8bf/charset_normalizer-3.4.6-cp312-cp312-win32.whl", hash = "sha256:c2274ca724536f173122f36c98ce188fd24ce3dad886ec2b7af859518ce008a4", size = 144229, upload-time = "2026-03-15T18:51:11.694Z" }, + { url = "https://files.pythonhosted.org/packages/ab/20/0567efb3a8fd481b8f34f739ebddc098ed062a59fed41a8d193a61939e8f/charset_normalizer-3.4.6-cp312-cp312-win_amd64.whl", hash = "sha256:c8ae56368f8cc97c7e40a7ee18e1cedaf8e780cd8bc5ed5ac8b81f238614facb", size = 154277, upload-time = "2026-03-15T18:51:13.004Z" }, + { url = "https://files.pythonhosted.org/packages/15/57/28d79b44b51933119e21f65479d0864a8d5893e494cf5daab15df0247c17/charset_normalizer-3.4.6-cp312-cp312-win_arm64.whl", hash = "sha256:899d28f422116b08be5118ef350c292b36fc15ec2daeb9ea987c89281c7bb5c4", size = 142817, upload-time = "2026-03-15T18:51:14.408Z" }, + { url = "https://files.pythonhosted.org/packages/1e/1d/4fdabeef4e231153b6ed7567602f3b68265ec4e5b76d6024cf647d43d981/charset_normalizer-3.4.6-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:11afb56037cbc4b1555a34dd69151e8e069bee82e613a73bef6e714ce733585f", size = 294823, upload-time = "2026-03-15T18:51:15.755Z" }, + { url = "https://files.pythonhosted.org/packages/47/7b/20e809b89c69d37be748d98e84dce6820bf663cf19cf6b942c951a3e8f41/charset_normalizer-3.4.6-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:423fb7e748a08f854a08a222b983f4df1912b1daedce51a72bd24fe8f26a1843", size = 198527, upload-time = "2026-03-15T18:51:17.177Z" }, + { url = "https://files.pythonhosted.org/packages/37/a6/4f8d27527d59c039dce6f7622593cdcd3d70a8504d87d09eb11e9fdc6062/charset_normalizer-3.4.6-cp313-cp313-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:d73beaac5e90173ac3deb9928a74763a6d230f494e4bfb422c217a0ad8e629bf", size = 218388, upload-time = "2026-03-15T18:51:18.934Z" }, + { url = "https://files.pythonhosted.org/packages/f6/9b/4770ccb3e491a9bacf1c46cc8b812214fe367c86a96353ccc6daf87b01ec/charset_normalizer-3.4.6-cp313-cp313-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:d60377dce4511655582e300dc1e5a5f24ba0cb229005a1d5c8d0cb72bb758ab8", size = 214563, upload-time = "2026-03-15T18:51:20.374Z" }, + { url = "https://files.pythonhosted.org/packages/2b/58/a199d245894b12db0b957d627516c78e055adc3a0d978bc7f65ddaf7c399/charset_normalizer-3.4.6-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:530e8cebeea0d76bdcf93357aa5e41336f48c3dc709ac52da2bb167c5b8271d9", size = 206587, upload-time = "2026-03-15T18:51:21.807Z" }, + { url = "https://files.pythonhosted.org/packages/7e/70/3def227f1ec56f5c69dfc8392b8bd63b11a18ca8178d9211d7cc5e5e4f27/charset_normalizer-3.4.6-cp313-cp313-manylinux_2_31_armv7l.whl", hash = "sha256:a26611d9987b230566f24a0a125f17fe0de6a6aff9f25c9f564aaa2721a5fb88", size = 194724, upload-time = "2026-03-15T18:51:23.508Z" }, + { url = "https://files.pythonhosted.org/packages/58/ab/9318352e220c05efd31c2779a23b50969dc94b985a2efa643ed9077bfca5/charset_normalizer-3.4.6-cp313-cp313-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:34315ff4fc374b285ad7f4a0bf7dcbfe769e1b104230d40f49f700d4ab6bbd84", size = 202956, upload-time = "2026-03-15T18:51:25.239Z" }, + { url = "https://files.pythonhosted.org/packages/75/13/f3550a3ac25b70f87ac98c40d3199a8503676c2f1620efbf8d42095cfc40/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:5f8ddd609f9e1af8c7bd6e2aca279c931aefecd148a14402d4e368f3171769fd", size = 201923, upload-time = "2026-03-15T18:51:26.682Z" }, + { url = "https://files.pythonhosted.org/packages/1b/db/c5c643b912740b45e8eec21de1bbab8e7fc085944d37e1e709d3dcd9d72f/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_armv7l.whl", hash = "sha256:80d0a5615143c0b3225e5e3ef22c8d5d51f3f72ce0ea6fb84c943546c7b25b6c", size = 195366, upload-time = "2026-03-15T18:51:28.129Z" }, + { url = "https://files.pythonhosted.org/packages/5a/67/3b1c62744f9b2448443e0eb160d8b001c849ec3fef591e012eda6484787c/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:92734d4d8d187a354a556626c221cd1a892a4e0802ccb2af432a1d85ec012194", size = 219752, upload-time = "2026-03-15T18:51:29.556Z" }, + { url = "https://files.pythonhosted.org/packages/f6/98/32ffbaf7f0366ffb0445930b87d103f6b406bc2c271563644bde8a2b1093/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_riscv64.whl", hash = "sha256:613f19aa6e082cf96e17e3ffd89383343d0d589abda756b7764cf78361fd41dc", size = 203296, upload-time = "2026-03-15T18:51:30.921Z" }, + { url = "https://files.pythonhosted.org/packages/41/12/5d308c1bbe60cabb0c5ef511574a647067e2a1f631bc8634fcafaccd8293/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:2b1a63e8224e401cafe7739f77efd3f9e7f5f2026bda4aead8e59afab537784f", size = 215956, upload-time = "2026-03-15T18:51:32.399Z" }, + { url = "https://files.pythonhosted.org/packages/53/e9/5f85f6c5e20669dbe56b165c67b0260547dea97dba7e187938833d791687/charset_normalizer-3.4.6-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6cceb5473417d28edd20c6c984ab6fee6c6267d38d906823ebfe20b03d607dc2", size = 208652, upload-time = "2026-03-15T18:51:34.214Z" }, + { url = "https://files.pythonhosted.org/packages/f1/11/897052ea6af56df3eef3ca94edafee410ca699ca0c7b87960ad19932c55e/charset_normalizer-3.4.6-cp313-cp313-win32.whl", hash = "sha256:d7de2637729c67d67cf87614b566626057e95c303bc0a55ffe391f5205e7003d", size = 143940, upload-time = "2026-03-15T18:51:36.15Z" }, + { url = "https://files.pythonhosted.org/packages/a1/5c/724b6b363603e419829f561c854b87ed7c7e31231a7908708ac086cdf3e2/charset_normalizer-3.4.6-cp313-cp313-win_amd64.whl", hash = "sha256:572d7c822caf521f0525ba1bce1a622a0b85cf47ffbdae6c9c19e3b5ac3c4389", size = 154101, upload-time = "2026-03-15T18:51:37.876Z" }, + { url = "https://files.pythonhosted.org/packages/01/a5/7abf15b4c0968e47020f9ca0935fb3274deb87cb288cd187cad92e8cdffd/charset_normalizer-3.4.6-cp313-cp313-win_arm64.whl", hash = "sha256:a4474d924a47185a06411e0064b803c68be044be2d60e50e8bddcc2649957c1f", size = 143109, upload-time = "2026-03-15T18:51:39.565Z" }, + { url = "https://files.pythonhosted.org/packages/25/6f/ffe1e1259f384594063ea1869bfb6be5cdb8bc81020fc36c3636bc8302a1/charset_normalizer-3.4.6-cp314-cp314-macosx_10_15_universal2.whl", hash = "sha256:9cc6e6d9e571d2f863fa77700701dae73ed5f78881efc8b3f9a4398772ff53e8", size = 294458, upload-time = "2026-03-15T18:51:41.134Z" }, + { url = "https://files.pythonhosted.org/packages/56/60/09bb6c13a8c1016c2ed5c6a6488e4ffef506461aa5161662bd7636936fb1/charset_normalizer-3.4.6-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ef5960d965e67165d75b7c7ffc60a83ec5abfc5c11b764ec13ea54fbef8b4421", size = 199277, upload-time = "2026-03-15T18:51:42.953Z" }, + { url = "https://files.pythonhosted.org/packages/00/50/dcfbb72a5138bbefdc3332e8d81a23494bf67998b4b100703fd15fa52d81/charset_normalizer-3.4.6-cp314-cp314-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:b3694e3f87f8ac7ce279d4355645b3c878d24d1424581b46282f24b92f5a4ae2", size = 218758, upload-time = "2026-03-15T18:51:44.339Z" }, + { url = "https://files.pythonhosted.org/packages/03/b3/d79a9a191bb75f5aa81f3aaaa387ef29ce7cb7a9e5074ba8ea095cc073c2/charset_normalizer-3.4.6-cp314-cp314-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:5d11595abf8dd942a77883a39d81433739b287b6aa71620f15164f8096221b30", size = 215299, upload-time = "2026-03-15T18:51:45.871Z" }, + { url = "https://files.pythonhosted.org/packages/76/7e/bc8911719f7084f72fd545f647601ea3532363927f807d296a8c88a62c0d/charset_normalizer-3.4.6-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7bda6eebafd42133efdca535b04ccb338ab29467b3f7bf79569883676fc628db", size = 206811, upload-time = "2026-03-15T18:51:47.308Z" }, + { url = "https://files.pythonhosted.org/packages/e2/40/c430b969d41dda0c465aa36cc7c2c068afb67177bef50905ac371b28ccc7/charset_normalizer-3.4.6-cp314-cp314-manylinux_2_31_armv7l.whl", hash = "sha256:bbc8c8650c6e51041ad1be191742b8b421d05bbd3410f43fa2a00c8db87678e8", size = 193706, upload-time = "2026-03-15T18:51:48.849Z" }, + { url = "https://files.pythonhosted.org/packages/48/15/e35e0590af254f7df984de1323640ef375df5761f615b6225ba8deb9799a/charset_normalizer-3.4.6-cp314-cp314-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:22c6f0c2fbc31e76c3b8a86fba1a56eda6166e238c29cdd3d14befdb4a4e4815", size = 202706, upload-time = "2026-03-15T18:51:50.257Z" }, + { url = "https://files.pythonhosted.org/packages/5e/bd/f736f7b9cc5e93a18b794a50346bb16fbfd6b37f99e8f306f7951d27c17c/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:7edbed096e4a4798710ed6bc75dcaa2a21b68b6c356553ac4823c3658d53743a", size = 202497, upload-time = "2026-03-15T18:51:52.012Z" }, + { url = "https://files.pythonhosted.org/packages/9d/ba/2cc9e3e7dfdf7760a6ed8da7446d22536f3d0ce114ac63dee2a5a3599e62/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_armv7l.whl", hash = "sha256:7f9019c9cb613f084481bd6a100b12e1547cf2efe362d873c2e31e4035a6fa43", size = 193511, upload-time = "2026-03-15T18:51:53.723Z" }, + { url = "https://files.pythonhosted.org/packages/9e/cb/5be49b5f776e5613be07298c80e1b02a2d900f7a7de807230595c85a8b2e/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_ppc64le.whl", hash = "sha256:58c948d0d086229efc484fe2f30c2d382c86720f55cd9bc33591774348ad44e0", size = 220133, upload-time = "2026-03-15T18:51:55.333Z" }, + { url = "https://files.pythonhosted.org/packages/83/43/99f1b5dad345accb322c80c7821071554f791a95ee50c1c90041c157ae99/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_riscv64.whl", hash = "sha256:419a9d91bd238052642a51938af8ac05da5b3343becde08d5cdeab9046df9ee1", size = 203035, upload-time = "2026-03-15T18:51:56.736Z" }, + { url = "https://files.pythonhosted.org/packages/87/9a/62c2cb6a531483b55dddff1a68b3d891a8b498f3ca555fbcf2978e804d9d/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_s390x.whl", hash = "sha256:5273b9f0b5835ff0350c0828faea623c68bfa65b792720c453e22b25cc72930f", size = 216321, upload-time = "2026-03-15T18:51:58.17Z" }, + { url = "https://files.pythonhosted.org/packages/6e/79/94a010ff81e3aec7c293eb82c28f930918e517bc144c9906a060844462eb/charset_normalizer-3.4.6-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:0e901eb1049fdb80f5bd11ed5ea1e498ec423102f7a9b9e4645d5b8204ff2815", size = 208973, upload-time = "2026-03-15T18:51:59.998Z" }, + { url = "https://files.pythonhosted.org/packages/2a/57/4ecff6d4ec8585342f0c71bc03efaa99cb7468f7c91a57b105bcd561cea8/charset_normalizer-3.4.6-cp314-cp314-win32.whl", hash = "sha256:b4ff1d35e8c5bd078be89349b6f3a845128e685e751b6ea1169cf2160b344c4d", size = 144610, upload-time = "2026-03-15T18:52:02.213Z" }, + { url = "https://files.pythonhosted.org/packages/80/94/8434a02d9d7f168c25767c64671fead8d599744a05d6a6c877144c754246/charset_normalizer-3.4.6-cp314-cp314-win_amd64.whl", hash = "sha256:74119174722c4349af9708993118581686f343adc1c8c9c007d59be90d077f3f", size = 154962, upload-time = "2026-03-15T18:52:03.658Z" }, + { url = "https://files.pythonhosted.org/packages/46/4c/48f2cdbfd923026503dfd67ccea45c94fd8fe988d9056b468579c66ed62b/charset_normalizer-3.4.6-cp314-cp314-win_arm64.whl", hash = "sha256:e5bcc1a1ae744e0bb59641171ae53743760130600da8db48cbb6e4918e186e4e", size = 143595, upload-time = "2026-03-15T18:52:05.123Z" }, + { url = "https://files.pythonhosted.org/packages/31/93/8878be7569f87b14f1d52032946131bcb6ebbd8af3e20446bc04053dc3f1/charset_normalizer-3.4.6-cp314-cp314t-macosx_10_15_universal2.whl", hash = "sha256:ad8faf8df23f0378c6d527d8b0b15ea4a2e23c89376877c598c4870d1b2c7866", size = 314828, upload-time = "2026-03-15T18:52:06.831Z" }, + { url = "https://files.pythonhosted.org/packages/06/b6/fae511ca98aac69ecc35cde828b0a3d146325dd03d99655ad38fc2cc3293/charset_normalizer-3.4.6-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f5ea69428fa1b49573eef0cc44a1d43bebd45ad0c611eb7d7eac760c7ae771bc", size = 208138, upload-time = "2026-03-15T18:52:08.239Z" }, + { url = "https://files.pythonhosted.org/packages/54/57/64caf6e1bf07274a1e0b7c160a55ee9e8c9ec32c46846ce59b9c333f7008/charset_normalizer-3.4.6-cp314-cp314t-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:06a7e86163334edfc5d20fe104db92fcd666e5a5df0977cb5680a506fe26cc8e", size = 224679, upload-time = "2026-03-15T18:52:10.043Z" }, + { url = "https://files.pythonhosted.org/packages/aa/cb/9ff5a25b9273ef160861b41f6937f86fae18b0792fe0a8e75e06acb08f1d/charset_normalizer-3.4.6-cp314-cp314t-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:e1f6e2f00a6b8edb562826e4632e26d063ac10307e80f7461f7de3ad8ef3f077", size = 223475, upload-time = "2026-03-15T18:52:11.854Z" }, + { url = "https://files.pythonhosted.org/packages/fc/97/440635fc093b8d7347502a377031f9605a1039c958f3cd18dcacffb37743/charset_normalizer-3.4.6-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:95b52c68d64c1878818687a473a10547b3292e82b6f6fe483808fb1468e2f52f", size = 215230, upload-time = "2026-03-15T18:52:13.325Z" }, + { url = "https://files.pythonhosted.org/packages/cd/24/afff630feb571a13f07c8539fbb502d2ab494019492aaffc78ef41f1d1d0/charset_normalizer-3.4.6-cp314-cp314t-manylinux_2_31_armv7l.whl", hash = "sha256:7504e9b7dc05f99a9bbb4525c67a2c155073b44d720470a148b34166a69c054e", size = 199045, upload-time = "2026-03-15T18:52:14.752Z" }, + { url = "https://files.pythonhosted.org/packages/e5/17/d1399ecdaf7e0498c327433e7eefdd862b41236a7e484355b8e0e5ebd64b/charset_normalizer-3.4.6-cp314-cp314t-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:172985e4ff804a7ad08eebec0a1640ece87ba5041d565fff23c8f99c1f389484", size = 211658, upload-time = "2026-03-15T18:52:16.278Z" }, + { url = "https://files.pythonhosted.org/packages/b5/38/16baa0affb957b3d880e5ac2144caf3f9d7de7bc4a91842e447fbb5e8b67/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:4be9f4830ba8741527693848403e2c457c16e499100963ec711b1c6f2049b7c7", size = 210769, upload-time = "2026-03-15T18:52:17.782Z" }, + { url = "https://files.pythonhosted.org/packages/05/34/c531bc6ac4c21da9ddfddb3107be2287188b3ea4b53b70fc58f2a77ac8d8/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_armv7l.whl", hash = "sha256:79090741d842f564b1b2827c0b82d846405b744d31e84f18d7a7b41c20e473ff", size = 201328, upload-time = "2026-03-15T18:52:19.553Z" }, + { url = "https://files.pythonhosted.org/packages/fa/73/a5a1e9ca5f234519c1953608a03fe109c306b97fdfb25f09182babad51a7/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_ppc64le.whl", hash = "sha256:87725cfb1a4f1f8c2fc9890ae2f42094120f4b44db9360be5d99a4c6b0e03a9e", size = 225302, upload-time = "2026-03-15T18:52:21.043Z" }, + { url = "https://files.pythonhosted.org/packages/ba/f6/cd782923d112d296294dea4bcc7af5a7ae0f86ab79f8fefbda5526b6cfc0/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_riscv64.whl", hash = "sha256:fcce033e4021347d80ed9c66dcf1e7b1546319834b74445f561d2e2221de5659", size = 211127, upload-time = "2026-03-15T18:52:22.491Z" }, + { url = "https://files.pythonhosted.org/packages/0e/c5/0b6898950627af7d6103a449b22320372c24c6feda91aa24e201a478d161/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_s390x.whl", hash = "sha256:ca0276464d148c72defa8bb4390cce01b4a0e425f3b50d1435aa6d7a18107602", size = 222840, upload-time = "2026-03-15T18:52:24.113Z" }, + { url = "https://files.pythonhosted.org/packages/7d/25/c4bba773bef442cbdc06111d40daa3de5050a676fa26e85090fc54dd12f0/charset_normalizer-3.4.6-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:197c1a244a274bb016dd8b79204850144ef77fe81c5b797dc389327adb552407", size = 216890, upload-time = "2026-03-15T18:52:25.541Z" }, + { url = "https://files.pythonhosted.org/packages/35/1a/05dacadb0978da72ee287b0143097db12f2e7e8d3ffc4647da07a383b0b7/charset_normalizer-3.4.6-cp314-cp314t-win32.whl", hash = "sha256:2a24157fa36980478dd1770b585c0f30d19e18f4fb0c47c13aa568f871718579", size = 155379, upload-time = "2026-03-15T18:52:27.05Z" }, + { url = "https://files.pythonhosted.org/packages/5d/7a/d269d834cb3a76291651256f3b9a5945e81d0a49ab9f4a498964e83c0416/charset_normalizer-3.4.6-cp314-cp314t-win_amd64.whl", hash = "sha256:cd5e2801c89992ed8c0a3f0293ae83c159a60d9a5d685005383ef4caca77f2c4", size = 169043, upload-time = "2026-03-15T18:52:28.502Z" }, + { url = "https://files.pythonhosted.org/packages/23/06/28b29fba521a37a8932c6a84192175c34d49f84a6d4773fa63d05f9aff22/charset_normalizer-3.4.6-cp314-cp314t-win_arm64.whl", hash = "sha256:47955475ac79cc504ef2704b192364e51d0d473ad452caedd0002605f780101c", size = 148523, upload-time = "2026-03-15T18:52:29.956Z" }, + { url = "https://files.pythonhosted.org/packages/2a/68/687187c7e26cb24ccbd88e5069f5ef00eba804d36dde11d99aad0838ab45/charset_normalizer-3.4.6-py3-none-any.whl", hash = "sha256:947cf925bc916d90adba35a64c82aace04fa39b46b52d4630ece166655905a69", size = 61455, upload-time = "2026-03-15T18:53:23.833Z" }, +] + [[package]] name = "dynamixel-sdk" version = "3.7.31" @@ -24,12 +151,37 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/03/e8/2c65d11d312fdb1a2308563d32f63f93c39123bcfb4909d947e0b294c794/dynamixel_sdk-3.7.31-py3-none-any.whl", hash = "sha256:74e8c112ca6b0b869b196dd8c6a44ffd5dd5c1a3cb9fe2030e9933922406b466", size = 23664, upload-time = "2020-08-14T20:26:00.354Z" }, ] +[[package]] +name = "dynamixelmotorsapi" +version = "0.2.0" +source = { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" } +dependencies = [ + { name = "beautifulsoup4" }, + { name = "dynamixel-sdk" }, + { name = "numpy" }, + { name = "pyserial" }, + { name = "requests" }, +] +wheels = [ + { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl", hash = "sha256:d276e1a3be39faf20f865c42ea284555ee64137b9997a470bb142375ceeef3e9" }, +] + +[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 = "emioapi" version = "0.2.0" source = { editable = "." } dependencies = [ { name = "dynamixel-sdk" }, + { name = "dynamixelmotorsapi" }, { name = "numpy" }, { name = "opencv-python" }, { name = "pillow" }, @@ -41,6 +193,7 @@ dependencies = [ [package.metadata] requires-dist = [ { name = "dynamixel-sdk" }, + { name = "dynamixelmotorsapi", url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" }, { name = "numpy", specifier = "==1.26.4" }, { name = "opencv-python" }, { name = "pillow" }, @@ -49,6 +202,15 @@ requires-dist = [ { name = "pyserial" }, ] +[[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" @@ -205,3 +367,45 @@ sdist = { url = "https://files.pythonhosted.org/packages/1e/7d/ae3f0a63f41e4d2f6 wheels = [ { url = "https://files.pythonhosted.org/packages/07/bc/587a445451b253b285629263eb51c2d8e9bcea4fc97826266d186f96f558/pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0", size = 90585, upload-time = "2020-11-23T03:59:13.41Z" }, ] + +[[package]] +name = "requests" +version = "2.32.5" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { 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]] +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 dc37274d9bdf305381a138fbfa233b579d90a1ec Mon Sep 17 00:00:00 2001 From: HanaeRateau Date: Wed, 25 Mar 2026 19:03:36 +0100 Subject: [PATCH 3/3] Removes unused files and updates some methods --- emioapi/_emiomotorsparameters.py | 92 ------ emioapi/_motorgroup.py | 520 ------------------------------- emioapi/emioapi.py | 7 +- emioapi/emiomotors.py | 15 - pyproject.toml | 2 +- uv.lock | 22 +- 6 files changed, 10 insertions(+), 648 deletions(-) delete mode 100644 emioapi/_emiomotorsparameters.py delete mode 100644 emioapi/_motorgroup.py diff --git a/emioapi/_emiomotorsparameters.py b/emioapi/_emiomotorsparameters.py deleted file mode 100644 index f381fa0..0000000 --- a/emioapi/_emiomotorsparameters.py +++ /dev/null @@ -1,92 +0,0 @@ -#********* 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 - - - -# DYNAMIXEL Protocol Version (1.0 / 2.0) -# https://emanual.robotis.com/docs/en/dxl/protocol2/ -PROTOCOL_VERSION = 2.0 - -# Make sure that each DYNAMIXEL ID should have unique ID. - - -DXL_IDs = (0, 1, 2, 3) - -import serial.tools.list_ports as list_ports - -# Use the actual port assigned to the U2D2. -# ex) Windows: "COM*", Linux: "/dev/ttyUSB*", Mac: "/dev/tty.usbserial-*" -BAUDRATE = 1000000 - - -# Generic motor parameters - -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 diff --git a/emioapi/_motorgroup.py b/emioapi/_motorgroup.py deleted file mode 100644 index 9c5ddd3..0000000 --- a/emioapi/_motorgroup.py +++ /dev/null @@ -1,520 +0,0 @@ -import ctypes - -from dynamixel_sdk import * - -import emioapi._emiomotorsparameters as MotorsParametersTemplate -from emioapi._logging_config import logger - -def listMotors(): - """ - List all the emio devices connected to the computer. - - Returns: - A list containing the devices name (string) - """ - ports = [] - comports = serial.tools.list_ports.comports() - - for p in comports: - if p.manufacturer is not None and "FTDI" in p.manufacturer: - ports.append(p.device) - elif p.description is not None and "FTDI" in p.description: - ports.append(p.device) - 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: - 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 - - -def _valToArray( val): - """Convert a 32-bit integer to a list of 4 bytes. - Args: - val (int): The 32-bit integer to convert. - Returns: - list of bytes: The list of 4 bytes representing the integer. - """ - return [DXL_LOBYTE(DXL_LOWORD(val)), DXL_HIBYTE(DXL_LOWORD(val)), DXL_LOBYTE(DXL_HIWORD(val)), - DXL_HIBYTE(DXL_HIWORD(val))] - - -def _valTo2Bytes(val): - """Convert a 16-bit integer to a list of 2 bytes.""" - return [DXL_LOBYTE(val), DXL_HIBYTE(val)] - - -class DisconnectedException(Exception): - """Custom exception for disconnected motors.""" - def __init__(self): - message = "MotorGroup is not connected. It is either disconnected or permission denied." - super().__init__(message) - -class MotorGroup: - - def __init__(self, parameters: MotorsParametersTemplate) -> None: - - self.parameters = parameters - self.deviceName = None - - self.packetHandler = PacketHandler(self.parameters.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) - - - @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 - 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 _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. - - Returns: - int: The value read from the motor. - - Raises: - Exception: If the motor group is not connected or if the read operation fails. - """ - if not self.isConnected: - raise DisconnectedException() - - 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() - - 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) - - 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. - """ - 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)) - - - 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. - """ - if not self.isConnected: - raise DisconnectedException() - - self.__write1Byte(self.parameters.ADDR_OPERATING_MODE, mode) - - - - def enableVelocityMode(self): - torques = self.isTorqueEnable() - - 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.enableTorque() - - - def enableExtendedPositionMode(self): - torques = self.isTorqueEnable() - - 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.enableTorque() - - - def enablePositionMode(self): - torques = self.isTorqueEnable() - - 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.enableTorque() - - - def setGoalVelocity(self, speeds): - """Set the goal velocity - - Args: - speeds (list of numbers): unit depends on motor type - """ - self.__writeSyncMotorsData(self.groupWriters["goal_velocity"] , speeds) - - - def setGoalPosition(self, positions): - """Set the goal position - - Args: - positions (list of numbers): unit = 1 pulse - """ - self.__writeSyncMotorsData(self.groupWriters["goal_position"], positions) - - - def setVelocityProfile(self, max_vel): - """Set the maximum velocities in position mode - - Args: - positions (list of numbers): unit depends on the motor type - """ - self.__writeSyncMotorsData(self.groupWriters["velocity_profile"], max_vel) - - - def setPositionPGain(self, p_gains): - """Set the position P gains - - Args: - p_gains (list of numbers): unit depends on the motor type - """ - self.__writeSyncMotorsData(self.groupWriters["position_p_gain"], p_gains) - - - 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) - - - def setPositionDGain(self, d_gains): - """Set the position D gains - - Args: - d_gains (list of numbers): unit depends on the motor type - """ - self.__writeSyncMotorsData(self.groupWriters["position_d_gain"], d_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 getGoalPosition(self) -> list: - """Get the goal position of the motors - Returns: - list of numbers: unit = 1 pulse - """ - return self._readSyncMotorsData(self.groupReaders["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"]) - - - 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"]) - - - 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"]) - - - 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"]) - - - 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"]) - - - 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"]) - - - 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"]) - - - 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"]) - - - 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() diff --git a/emioapi/emioapi.py b/emioapi/emioapi.py index 55c5ff3..5cd5785 100644 --- a/emioapi/emioapi.py +++ b/emioapi/emioapi.py @@ -23,6 +23,7 @@ from threading import Lock +from dynamixelmotorsapi import listFTDIDevices, listUnusedFTDIDevices, listUsedFTDIDevices from emioapi import EmioMotors from emioapi import MultiprocessEmioCamera from emioapi import EmioCamera, emiocamera @@ -138,7 +139,7 @@ def listEmioDevices() -> list: Returns: A list of device names (the ports). """ - return motorgroup.listMotors() + return listFTDIDevices() @staticmethod @@ -149,7 +150,7 @@ def listUnusedEmioDevices() -> list: Returns: A list of device names (the ports). """ - return [device for device in EmioAPI.listEmioDevices() if device not in EmioAPI._emio_list] + return listUnusedFTDIDevices() @staticmethod @@ -160,7 +161,7 @@ def listUsedEmioDevices() -> list: Returns: A list of device names (the ports). """ - return [device for device in EmioAPI._emio_list.keys()] + return listUsedFTDIDevices() @staticmethod def listCameraDevices(): diff --git a/emioapi/emiomotors.py b/emioapi/emiomotors.py index c866f29..ea5882d 100644 --- a/emioapi/emiomotors.py +++ b/emioapi/emiomotors.py @@ -3,9 +3,6 @@ from math import pi from dynamixelmotorsapi import DynamixelMotors - -import emioapi._motorgroup as motorgroup -import emioapi._emiomotorsparameters as emioparameters from emioapi._logging_config import logger class EmioMotors(DynamixelMotors): @@ -40,18 +37,6 @@ class EmioMotors(DynamixelMotors): """ - # _initialized: bool = False - # _length_to_rad: float = 1.0 / 20.0 # 1/radius of the pulley - # _rad_to_pulse: int = 4096 / (2 * pi) # the resolution of the Dynamixel xm430 w210 - # _length_to_pulse: int = _length_to_rad * _rad_to_pulse - # _pulse_center: int = 2048 - # _max_vel: float = 1000 # *0.01 rev/min - # _goal_velocity: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) - # _goal_position: list = field(default_factory=lambda: [0] * len(emioparameters.DXL_IDs)) - # _mg: motorgroup.MotorGroup = None - # _device_index: int = None - - ##################### ###### METHODS ###### diff --git a/pyproject.toml b/pyproject.toml index 38788cc..3d960fd 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -75,4 +75,4 @@ Function = 3 Data = 3 [tool.uv.sources] -dynamixelmotorsapi = { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" } +dynamixelmotorsapi = { git = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI", rev = "release-dev_motorsgeneralization" } diff --git a/uv.lock b/uv.lock index a1d59a9..871b85b 100644 --- a/uv.lock +++ b/uv.lock @@ -154,7 +154,7 @@ wheels = [ [[package]] name = "dynamixelmotorsapi" version = "0.2.0" -source = { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" } +source = { git = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI?rev=release-dev_motorsgeneralization#e91d91ac40b3be9229d56791df803737f851690f" } dependencies = [ { name = "beautifulsoup4" }, { name = "dynamixel-sdk" }, @@ -162,18 +162,6 @@ dependencies = [ { name = "pyserial" }, { name = "requests" }, ] -wheels = [ - { url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl", hash = "sha256:d276e1a3be39faf20f865c42ea284555ee64137b9997a470bb142375ceeef3e9" }, -] - -[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 = "emioapi" @@ -193,7 +181,7 @@ dependencies = [ [package.metadata] requires-dist = [ { name = "dynamixel-sdk" }, - { name = "dynamixelmotorsapi", url = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI/releases/download/release-dev_motorsgeneralization/dynamixelmotorsapi-0.2.0-py3-none-any.whl" }, + { name = "dynamixelmotorsapi", git = "https://github.com/SofaComplianceRobotics/DynamixelMotorsAPI?rev=release-dev_motorsgeneralization" }, { name = "numpy", specifier = "==1.26.4" }, { name = "opencv-python" }, { name = "pillow" }, @@ -370,7 +358,7 @@ wheels = [ [[package]] name = "requests" -version = "2.32.5" +version = "2.33.0" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "certifi" }, @@ -378,9 +366,9 @@ dependencies = [ { 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" } +sdist = { url = "https://files.pythonhosted.org/packages/34/64/8860370b167a9721e8956ae116825caff829224fbca0ca6e7bf8ddef8430/requests-2.33.0.tar.gz", hash = "sha256:c7ebc5e8b0f21837386ad0e1c8fe8b829fa5f544d8df3b2253bff14ef29d7652", size = 134232, upload-time = "2026-03-25T15:10:41.586Z" } 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" }, + { url = "https://files.pythonhosted.org/packages/56/5d/c814546c2333ceea4ba42262d8c4d55763003e767fa169adc693bd524478/requests-2.33.0-py3-none-any.whl", hash = "sha256:3324635456fa185245e24865e810cecec7b4caf933d7eb133dcde67d48cee69b", size = 65017, upload-time = "2026-03-25T15:10:40.382Z" }, ] [[package]]