From f1b46923fe3aeb3015042cdcb3267f82eb03846e Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Wed, 12 Feb 2025 18:22:37 +0800 Subject: [PATCH 01/57] add MyCobot 280 X5PI API --- pymycobot/__init__.py | 4 +- pymycobot/common.py | 5 +- pymycobot/mycobot280x5pi.py | 837 ++++++++++++++++++++++++++++++++++++ 3 files changed, 844 insertions(+), 2 deletions(-) create mode 100644 pymycobot/mycobot280x5pi.py diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index ad9afe50..6369c45c 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -4,6 +4,7 @@ import datetime import sys from pymycobot.mycobot280 import MyCobot280 +from pymycobot.mycobot280x5pi import MyCobot280X5PI from pymycobot.mypalletizer260 import MyPalletizer260 from pymycobot.mecharm270 import MechArm270 from pymycobot.mycobot280socket import MyCobot280Socket @@ -77,7 +78,8 @@ "MyCobot320Socket", "MyArmMControl", "ChassisControl", - "ConveyorAPI" + "ConveyorAPI", + "MyCobot280X5PI" ] if sys.platform == "linux": diff --git a/pymycobot/common.py b/pymycobot/common.py index 3ae52e17..d32b9b7e 100644 --- a/pymycobot/common.py +++ b/pymycobot/common.py @@ -110,7 +110,8 @@ class ProtocolCode(object): GET_ROBOT_ID = 0x03 OVER_LIMIT_RETURN_ZERO = 0x04 SET_ROBOT_ID = 0x04 - + CLEAR_COMMAND_QUEUE = 0x05 + CHECK_ASYNC_OR_SYNC = 0x06 GET_ERROR_INFO = 0x07 CLEAR_ERROR_INFO = 0x08 GET_ATOM_VERSION = 0x09 @@ -147,6 +148,7 @@ class ProtocolCode(object): SET_FREE_MODE = 0x1A IS_FREE_MODE = 0x1B COBOTX_GET_ANGLE = 0x1C + IS_CONTROLLER_BUTTON_PRESSED = 0x1C POWER_ON_ONLY = 0x1D SET_VISION_MODE = 0x1D SET_CONTROL_MODE = 0x1E @@ -172,6 +174,7 @@ class ProtocolCode(object): GET_COORD = 0x2D SEND_ANGLES_AUTO = 0x2E GET_SOLUTION_ANGLES = 0x2E + WRITE_ANGLE_TIME = 0x2E SET_SOLUTION_ANGLES = 0x2F # JOG MODE AND OPERATION diff --git a/pymycobot/mycobot280x5pi.py b/pymycobot/mycobot280x5pi.py new file mode 100644 index 00000000..bb4a331e --- /dev/null +++ b/pymycobot/mycobot280x5pi.py @@ -0,0 +1,837 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +from __future__ import division + +import functools +import time +import math +import threading +import serial + +from pymycobot.generate import CommandGenerator +from pymycobot.common import ProtocolCode, write, read +from pymycobot.error import calibration_parameters + + +def setup_serial_port(port, baudrate, timeout): + serial_api = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) + serial_api.rts = False + if not serial_api.is_open: + serial_api.open() + return serial_api + + +class MyCobot280X5Api(CommandGenerator): + + def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): + super(MyCobot280X5Api, self).__init__(debug) + self._serial_port = setup_serial_port(port, baudrate, timeout) + self.thread_lock = thread_lock + self.lock = threading.Lock() + + self.calibration_parameters = functools.partial(calibration_parameters, class_name="MyCobot280") + self._write = functools.partial(write, self) + self._read = functools.partial(read, self) + + def _mesg(self, genre, *args, **kwargs): + """ + + Args: + genre: command type (Command) + *args: other data. + It is converted to octal by default. + If the data needs to be encapsulated into hexadecimal, + the array is used to include them. (Data cannot be nested) + **kwargs: support `has_reply` + has_reply: Whether there is a return value to accept. + """ + real_command, has_reply, _ = super(MyCobot280X5Api, self)._mesg(genre, *args, **kwargs) + if self.thread_lock: + with self.lock: + return self._res(real_command, has_reply, genre) + else: + return self._res(real_command, has_reply, genre) + + def _res(self, real_command, has_reply, genre): + if genre == ProtocolCode.SET_SSID_PWD or genre == ProtocolCode.GET_SSID_PWD: + self._write(self._flatten(real_command)) + data = self._read(genre) + else: + try_count = 0 + while try_count < 3: + self._write(self._flatten(real_command)) + data = self._read(genre) + if data is not None and data != b'': + break + try_count += 1 + else: + return -1 + if genre == ProtocolCode.SET_SSID_PWD: + return 1 + + if genre == ProtocolCode.GET_QUICK_INFO: + res = [] + valid_data = data[4:-1] + for header_i in range(0, len(valid_data), 2): + if header_i < 26: + one = valid_data[header_i: header_i + 2] + res.append(self._decode_int16(one)) + res.extend(valid_data[25:]) + else: + res = self._process_received(data, genre) + + if res is None: + return None + if genre in [ProtocolCode.SET_BASIC_OUTPUT]: + return 1 + if res is not None and isinstance(res, list) and len(res) == 1 and genre not in [ + ProtocolCode.GET_BASIC_VERSION, ProtocolCode.GET_JOINT_MIN_ANGLE, ProtocolCode.GET_JOINT_MAX_ANGLE, + ProtocolCode.SOFTWARE_VERSION, ProtocolCode.GET_ATOM_VERSION + ]: + return res[0] + + if genre in [ + ProtocolCode.IS_POWER_ON, + ProtocolCode.IS_CONTROLLER_CONNECTED, + ProtocolCode.IS_PAUSED, # TODO have bug: return b'' + ProtocolCode.IS_IN_POSITION, + ProtocolCode.IS_MOVING, + ProtocolCode.IS_SERVO_ENABLE, + ProtocolCode.IS_ALL_SERVO_ENABLE, + ProtocolCode.GET_SERVO_DATA, + ProtocolCode.GET_DIGITAL_INPUT, + ProtocolCode.GET_GRIPPER_VALUE, + ProtocolCode.IS_GRIPPER_MOVING, + ProtocolCode.GET_SPEED, + ProtocolCode.GET_ENCODER, + ProtocolCode.GET_BASIC_INPUT, + ProtocolCode.GET_TOF_DISTANCE, + ProtocolCode.GET_END_TYPE, + ProtocolCode.GET_MOVEMENT_TYPE, + ProtocolCode.GET_REFERENCE_FRAME, + ProtocolCode.GET_FRESH_MODE, + ProtocolCode.GET_GRIPPER_MODE, + ProtocolCode.GET_ERROR_INFO, + ProtocolCode.GET_COMMUNICATE_MODE, + ProtocolCode.SET_COMMUNICATE_MODE, + ProtocolCode.SetHTSGripperTorque, + ProtocolCode.GetHTSGripperTorque, + ProtocolCode.GetGripperProtectCurrent, + ProtocolCode.InitGripper, + ProtocolCode.SET_FOUR_PIECES_ZERO + ]: + return self._process_single(res) + elif genre in [ProtocolCode.GET_ANGLES, ProtocolCode.SOLVE_INV_KINEMATICS]: + return [self._int2angle(angle) for angle in res] + elif genre in [ProtocolCode.GET_COORDS, ProtocolCode.GET_TOOL_REFERENCE, ProtocolCode.GET_WORLD_REFERENCE]: + if res: + r = [] + for idx in range(3): + r.append(self._int2coord(res[idx])) + for idx in range(3, 6): + r.append(self._int2angle(res[idx])) + return r + else: + return res + elif genre in [ProtocolCode.GET_SERVO_VOLTAGES]: + return [self._int2coord(angle) for angle in res] + elif genre in [ProtocolCode.GET_JOINT_MAX_ANGLE, ProtocolCode.GET_JOINT_MIN_ANGLE]: + return self._int2coord(res[0]) + elif genre in [ + ProtocolCode.GET_BASIC_VERSION, ProtocolCode.SOFTWARE_VERSION, ProtocolCode.GET_ATOM_VERSION + ]: + return self._int2coord(self._process_single(res)) + elif genre in [ProtocolCode.GET_REBOOT_COUNT]: + return self._process_high_low_bytes(res) + elif genre in (ProtocolCode.GET_ANGLES_COORDS, ProtocolCode.GET_QUICK_INFO): + r = [] + for index, el in enumerate(res): + if index < 6: + r.append(self._int2angle(el)) + elif index < 9: + r.append(self._int2coord(el)) + elif index < 12: + r.append(self._int2angle(el)) + else: + r.append(el) + return r + else: + return res + + def wait(self, t): + time.sleep(t) + return self + + def close(self): + self._serial_port.close() + + def open(self): + self._serial_port.open() + + +class MyCobot280X5PI(MyCobot280X5Api): + + def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): + """ + Args: + port : port string + baudrate : baud rate int, default 100_0000 + timeout : default 0.1 + debug : whether show debug info + """ + super().__init__(port, baudrate, timeout, debug, thread_lock) + + # System Status + def get_modify_version(self): + """get modify version""" + return self._mesg(ProtocolCode.ROBOT_VERSION) + + def get_system_version(self): + """get system version""" + return self._mesg(ProtocolCode.SOFTWARE_VERSION) + + def clear_queue(self): + """Clear the command queue""" + return self._mesg(ProtocolCode.CLEAR_COMMAND_QUEUE) + + def async_or_sync(self): + """Set the command execution mode + Return: + 0: Asynchronous mode + 1: Synchronous mode + """ + return self._mesg(ProtocolCode.CHECK_ASYNC_OR_SYNC) + + def get_error_information(self): + """Obtaining robot error information + + Return: + 0: No error message. + 1 ~ 6: The corresponding joint exceeds the limit position. + 16 ~ 19: Collision protection. + 32: Kinematics inverse solution has no solution. + 33 ~ 34: Linear motion has no adjacent solution. + """ + return self._mesg(ProtocolCode.GET_ERROR_INFO, has_reply=True) + + def clear_error_information(self): + """Clear robot error message""" + return self._mesg(ProtocolCode.CLEAR_ERROR_INFO, has_reply=True) + + def power_on(self): + """Open communication with Atom.""" + return self._mesg(ProtocolCode.POWER_ON) + + def power_off(self): + """Close communication with Atom.""" + return self._mesg(ProtocolCode.POWER_OFF) + + def is_power_on(self): + """Adjust robot arm status + + Return: + 1 - power on + 0 - power off + -1 - error data + """ + return self._mesg(ProtocolCode.IS_POWER_ON, has_reply=True) + + def release_all_servos(self, data=None): + """Relax all joints + + Args: + data: 1 - Undamping (The default is damping) + """ + if data is None: + return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS) + else: + return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS, data) + + def read_next_error(self): + """Robot Error Detection + + Return: + list len 6. + 0 : No abnormality + 1 : Communication disconnected + 2 : Unstable communication + 3 : Servo abnormality + """ + return self._mesg(ProtocolCode.READ_NEXT_ERROR, has_reply=True) + + def set_fresh_mode(self, mode): + """Set command refresh mode + + Args: + mode: int. + 1 - Always execute the latest command first. + 0 - Execute instructions sequentially in the form of a queue. + """ + self.calibration_parameters(mode=mode) + return self._mesg(ProtocolCode.SET_FRESH_MODE, mode) + + def get_fresh_mode(self): + """Query sports mode""" + return self._mesg(ProtocolCode.GET_FRESH_MODE, has_reply=True) + + def set_vision_mode(self, flag): + """Set the visual tracking mode to limit the posture flipping of send_coords in refresh mode. + (Only for visual tracking function) + + Args: + flag: 0/1; 0 - close; 1 - open + """ + self.calibration_parameters(flag=flag) + return self._mesg(ProtocolCode.SET_VISION_MODE, flag) + + # Overall Status + def set_free_mode(self, flag): + """set to free mode + + Args: + flag: 0/1 + """ + self.calibration_parameters(flag=flag) + return self._mesg(ProtocolCode.SET_FREE_MODE, flag) + + def is_free_mode(self): + """Check if it is free mode + + Return: + 0/1 + """ + return self._mesg(ProtocolCode.IS_FREE_MODE, has_reply=True) + + # MDI mode and operation + def get_radians(self): + """Get the radians of all joints + + Return: + list: A list of float radians [radian1, ...] + """ + angles = self._mesg(ProtocolCode.GET_ANGLES, has_reply=True) + return [round(angle * (math.pi / 180), 3) for angle in angles] + + def send_radians(self, radians, speed): + """Send the radians of all joints to robot arm + + Args: + radians: a list of radian values( List[float]), length 6 + speed: (int )0 ~ 100 + """ + calibration_parameters(len6=radians, speed=speed) + degrees = [self._angle2int(radian * (180 / math.pi)) + for radian in radians] + return self._mesg(ProtocolCode.SEND_ANGLES, degrees, speed) + + def sync_send_angles(self, degrees, speed, timeout=15): + """Send the angle in synchronous state and return when the target point is reached + + Args: + degrees: a list of degree values(List[float]), length 6. + speed: (int) 0 ~ 100 + timeout: default 15s. + """ + t = time.time() + self.send_angles(degrees, speed) + while time.time() - t < timeout: + f = self.is_in_position(degrees, 0) + if f == 1: + break + time.sleep(0.1) + return 1 + + def sync_send_coords(self, coords, speed, mode=0, timeout=15): + """Send the coord in synchronous state and return when the target point is reached + + Args: + coords: a list of coord values(List[float]) + speed: (int) 0 ~ 100 + mode: (int): 0 - angular(default), 1 - linear + timeout: default 15s. + """ + t = time.time() + self.send_coords(coords, speed, mode) + while time.time() - t < timeout: + if self.is_in_position(coords, 1) == 1: + break + time.sleep(0.1) + return 1 + + def get_angles_coords(self): + """Get joint angles and coordinates""" + return self._mesg(ProtocolCode.GET_ANGLES_COORDS, has_reply=True) + + def get_quick_move_message(self): + """Get the quick move message""" + return self._mesg(ProtocolCode.GET_QUICK_INFO, has_reply=True) + + # JOG mode and operation + def write_angles_time_control(self, angles, step_time): + """Write the angle of a joint in time control mode + Args: + angles: Angle value + step_time: Time unit: 30ms, range(1 ~ 255) + """ + if step_time not in range(1, 256): + raise ValueError("step_time must be in range(1 ~ 255)") + angles = [self._angle2int(angle) for angle in angles] + return self._mesg(ProtocolCode.WRITE_ANGLE_TIME, angles, step_time) + + def jog_rpy(self, end_direction, direction, speed): + """Rotate the end around a fixed axis in the base coordinate system + + Args: + end_direction (int): Roll, Pitch, Yaw (1-3) + direction (int): 1 - forward rotation, 0 - reverse rotation + speed (int): 1 ~ 100 + """ + self.calibration_parameters(end_direction=end_direction, speed=speed) + return self._mesg(ProtocolCode.JOG_ABSOLUTE, end_direction, direction, speed) + + def jog_increment_angle(self, joint_id, increment, speed): + """ angle step mode + + Args: + joint_id: int 1-6. + increment: Angle increment value + speed: int (0 - 100) + """ + self.calibration_parameters(id=joint_id, speed=speed) + return self._mesg(ProtocolCode.JOG_INCREMENT, joint_id, [self._angle2int(increment)], speed) + + def jog_increment_coord(self, axis, increment, speed): + """coord step mode + + Args: + axis: axis id 1 - 6. + increment: Coord increment value + speed: int (1 - 100) + """ + self.calibration_parameters(id=axis, speed=speed) + value = self._coord2int(increment) if axis <= 3 else self._angle2int(increment) + return self._mesg(ProtocolCode.JOG_INCREMENT_COORD, axis, [value], speed) + + def set_HTS_gripper_torque(self, torque): + """Set new adaptive gripper torque + + Args: + torque (int): 150 ~ 980 + + Return: + 0: Set failed + 1: Set successful + """ + self.calibration_parameters(torque=torque) + return self._mesg(ProtocolCode.SetHTSGripperTorque, [torque], has_reply=True) + + def get_HTS_gripper_torque(self): + """Get gripper torque + + Returns: + int: 150 ~ 980 + """ + return self._mesg(ProtocolCode.GetHTSGripperTorque, has_reply=True) + + def get_gripper_protect_current(self): + """Get the gripper protection current + + Returns: + int: 1 ~ 500 + """ + return self._mesg(ProtocolCode.GetGripperProtectCurrent, has_reply=True) + + def init_gripper(self): + """Initialize gripper + + Returns: + int: 0 or 1 (1 - success) + """ + return self._mesg(ProtocolCode.InitGripper, has_reply=True) + + def set_gripper_protect_current(self, current): + """Set the gripper protection current + + Args: + current (int): 1 ~ 500 + """ + self.calibration_parameters(current=current) + + return self._mesg(ProtocolCode.SetGripperProtectCurrent, [current]) + + # Atom IO + def set_pin_mode(self, pin_no, pin_mode): + """Set the state mode of the specified pin in atom. + + Args: + pin_no (int): pin. + pin_mode (int): 0 - input, 1 - output, 2 - input pull up + """ + self.calibration_parameters(pin_mode=pin_mode) + return self._mesg(ProtocolCode.SET_PIN_MODE, pin_no, pin_mode) + + def get_gripper_value(self, gripper_type=None): + """Get the value of gripper. + + Args: + gripper_type (int): default 1 + 1: Adaptive gripper + 3: Parallel gripper + 4: Flexible gripper + + Return: + gripper value (int) + """ + if gripper_type is None: + return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, has_reply=True) + else: + self.calibration_parameters(gripper_type=gripper_type) + return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, gripper_type, has_reply=True) + + def is_gripper_moving(self): + """Judge whether the gripper is moving or not + + Returns: + 0 - not moving + 1 - is moving + -1- error data + """ + return self._mesg(ProtocolCode.IS_GRIPPER_MOVING, has_reply=True) + + def get_tool_system_version(self): + """ + Read the terminal primary and minor version numbers + """ + return self._mesg(ProtocolCode.GET_ATOM_VERSION, has_reply=True) + + def get_tool_modified_version(self): + """ + Read the terminal modified version number + """ + return self._mesg(ProtocolCode.OVER_LIMIT_RETURN_ZERO, has_reply=True) + + def is_tool_connected(self): + """Check the end connection status""" + return self._mesg(ProtocolCode.IS_CONTROLLER_CONNECTED, has_reply=True) + + def is_tool_button_click(self): + """Check whether the button on the end is pressed""" + return self._mesg(ProtocolCode.IS_CONTROLLER_BUTTON_PRESSED, has_reply=True) + + def set_pwm_output(self, channel, frequency, pin_val): + """ PWM control + + Args: + channel (int): IO number. + frequency (int): clock frequency + pin_val (int): Duty cycle 0 ~ 256; 128 means 50% + """ + return self._mesg(ProtocolCode.SET_PWM_OUTPUT, channel, [frequency], pin_val) + + # communication mode + def set_transponder_mode(self, mode): + """Set basic communication mode + + Args: + mode: 0 - Turn off transparent transmission,1 - Open transparent transmission + """ + self.calibration_parameters(mode=mode) + return self._mesg(ProtocolCode.SET_COMMUNICATE_MODE, mode, has_reply=True) + + def get_transponder_mode(self): + return self._mesg(ProtocolCode.GET_COMMUNICATE_MODE, has_reply=True) + + # g9 servo + def move_round(self): + """Drive the 9g steering gear clockwise for one revolution + """ + return self._mesg(ProtocolCode.move_round) + + def set_four_pieces_zero(self): + """Set the zero position of the four-piece motor + + Returns: + int: 0 or 1 (1 - success) + """ + return self._mesg(ProtocolCode.SET_FOUR_PIECES_ZERO, has_reply=True) + + # Running Status and Settings + def set_joint_max(self, id, angle): + """Set the joint maximum angle + + Args: + id: int. + Joint id 1 - 6 + for gripper: Joint id 7 + angle: 0 ~ 180 + """ + self.calibration_parameters(id=id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MAX, id, angle) + + def set_joint_min(self, id, angle): + """Set the joint minimum angle + + Args: + id: int. + Joint id 1 - 6 + for gripper: Joint id 7 + angle: 0 ~ 180 + """ + self.calibration_parameters(id=id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MIN, id, angle) + + # servo state value + def get_servo_speeds(self): + """Get joint speed + + Return: + A list unit step/s + """ + return self._mesg(ProtocolCode.GET_SERVO_SPEED, has_reply=True) + + def get_servo_voltages(self): + """Get joint voltages + + Return: + A list volts < 24 V + """ + return self._mesg(ProtocolCode.GET_SERVO_VOLTAGES, has_reply=True) + + def get_servo_status(self): + """Get joint status + + Return: + [voltage, sensor, temperature, current, angle, overload], a value of 0 means no error, a value of 1 indicates an error + """ + return self._mesg(ProtocolCode.GET_SERVO_STATUS, has_reply=True) + + def get_servo_temps(self): + """Get joint temperature + + Return: + A list unit ℃ + """ + return self._mesg(ProtocolCode.GET_SERVO_TEMPS, has_reply=True) + + # Coordinate transformation + def set_tool_reference(self, coords): + """Set tool coordinate system + + Args: + coords: a list of coords value(List[float]) + [x(mm), y, z, rx(angle), ry, rz] + """ + self.calibration_parameters(coords=coords) + coord_list = [] + for idx in range(3): + coord_list.append(self._coord2int(coords[idx])) + for angle in coords[3:]: + coord_list.append(self._angle2int(angle)) + return self._mesg(ProtocolCode.SET_TOOL_REFERENCE, coord_list) + + def get_tool_reference(self): + """Get tool coordinate system """ + return self._mesg(ProtocolCode.GET_TOOL_REFERENCE, has_reply=True) + + def set_world_reference(self, coords): + """Set the world coordinate system + + Args: + coords: a list of coords value(List[float]) + [x(mm), y, z, rx(angle), ry, rz]\n + """ + self.calibration_parameters(coords=coords) + coord_list = [] + for idx in range(3): + coord_list.append(self._coord2int(coords[idx])) + for angle in coords[3:]: + coord_list.append(self._angle2int(angle)) + return self._mesg(ProtocolCode.SET_WORLD_REFERENCE, coord_list) + + def get_world_reference(self): + """Get the world coordinate system""" + return self._mesg(ProtocolCode.GET_WORLD_REFERENCE, has_reply=True) + + def set_reference_frame(self, rftype): + """Set the base coordinate system + + Args: + rftype: 0 - base 1 - tool. + """ + self.calibration_parameters(rftype=rftype) + return self._mesg(ProtocolCode.SET_REFERENCE_FRAME, rftype) + + def get_reference_frame(self): + """Get the base coordinate system + + Return: + 0 - base 1 - tool. + """ + return self._mesg(ProtocolCode.GET_REFERENCE_FRAME, has_reply=True) + + def set_movement_type(self, move_type): + """Set movement type + + Args: + move_type: 1 - movel, 0 - moveJ + """ + self.calibration_parameters(move_type=move_type) + return self._mesg(ProtocolCode.SET_MOVEMENT_TYPE, move_type) + + def get_movement_type(self): + """Get movement type + + Return: + 1 - movel, 0 - moveJ + """ + return self._mesg(ProtocolCode.GET_MOVEMENT_TYPE, has_reply=True) + + def set_end_type(self, end): + """Set end coordinate system + + Args: + end: int + 0 - flange, 1 - tool + """ + self.calibration_parameters(end=end) + return self._mesg(ProtocolCode.SET_END_TYPE, end) + + def get_end_type(self): + """Get end coordinate system + + Return: + 0 - flange, 1 - tool + """ + return self._mesg(ProtocolCode.GET_END_TYPE, has_reply=True) + + def angles_to_coords(self, angles): + """ Convert angles to coordinates + + Args: + angles : A float list of all angle. + + Return: + list: A float list of all coordinates. + """ + angles = [self._angle2int(angle) for angle in angles] + return self._mesg(ProtocolCode.GET_COORDS, angles, has_reply=True) + + def solve_inv_kinematics(self, target_coords, current_angles): + """ Convert target coordinates to angles + + Args: + target_coords: A float list of all coordinates. + current_angles : A float list of all angle. + + Return: + list: A float list of all angle. + """ + angles = [self._angle2int(angle) for angle in current_angles] + coord_list = [] + for idx in range(3): + coord_list.append(self._coord2int(target_coords[idx])) + for angle in target_coords[3:]: + coord_list.append(self._angle2int(angle)) + return self._mesg(ProtocolCode.SOLVE_INV_KINEMATICS, coord_list, angles, has_reply=True) + + def is_torque_gripper(self): + """Whether it is a force-controlled gripper + + Return: + 40 - Force control + 9 - Non-force control + """ + return self.get_servo_data(7, 1) + + def set_gripper_state(self, flag, speed, _type_1=None, is_torque=None): + """Set gripper switch state + + Args: + flag (int): 0 - open, 1 - close, 254 - release + speed (int): 1 ~ 100 + _type_1 (int): default 1 + 1 : Adaptive gripper. default to adaptive gripper + 2 : 5 finger dexterous hand + 3 : Parallel gripper, this parameter can be omitted + 4 : Flexible gripper + is_torque (int): When there is no type parameter, this parameter can be omitted. + 1: Force control + 0: Non-force control + """ + self.calibration_parameters(flag=flag, speed=speed, _type_1=_type_1, is_torque=is_torque) + args = [flag, speed] + if _type_1 is not None: + args.append(_type_1) + if is_torque is not None: + args.append(is_torque) + return self._mesg(ProtocolCode.SET_GRIPPER_STATE, *args) + + def set_gripper_value(self, gripper_value, speed, gripper_type=None, is_torque=None): + """Set gripper value + + Args: + gripper_value (int): 0 ~ 100 + speed (int): 1 ~ 100 + gripper_type (int): default 1 + 1: Adaptive gripper + 3: Parallel gripper, this parameter can be omitted + 4: Flexible gripper + is_torque (int): When there is no type parameter, this parameter can be omitted. + 1: Force control + 0: Non-force control + """ + self.calibration_parameters(gripper_value=gripper_value, speed=speed, + gripper_type=gripper_type, is_torque=is_torque) + args = [gripper_value, speed] + if gripper_type is not None: + args.append(gripper_type) + if is_torque is not None: + args.append(is_torque) + return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, *args, has_reply=True) + + def drag_start_record(self): + """Start track recording + + Return: + Recording queue length + """ + + return self._mesg(ProtocolCode.DRAG_START_RECORD, has_reply=True) + + def drag_end_record(self): + """End track recording + + Return: + Recording queue length + """ + + return self._mesg(ProtocolCode.DRAG_END_RECORD, has_reply=True) + + def drag_get_record_data(self): + """Get the recorded track + + Return: + List of potential values (encoder values) and operating speeds of each joint + eg: [J1_encoder, J1_run_speed,J2_encoder, J2_run_speed,J3_encoder, J3_run_speed,J4_encoder, J4_run_speed,J5_ + encoder, J5_run_speed,J6_encoder, J6_run_speed] + """ + + return self._mesg(ProtocolCode.DRAG_GET_RECORD_DATA, has_reply=True) + + def drag_get_record_len(self): + """Get the total number of recorded points + + Return: + Recording queue length + """ + + return self._mesg(ProtocolCode.DRAG_GET_RECORD_LEN, has_reply=True) + + def drag_clear_record_data(self): + """Clear recording track + + Return: + Recording queue length 0 + """ + + return self._mesg(ProtocolCode.DRAG_CLEAR_RECORD_DATA, has_reply=True) \ No newline at end of file From 1346cd81c4d38249a9a2bd55d6456cd170891915 Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Thu, 13 Feb 2025 17:46:10 +0800 Subject: [PATCH 02/57] add MyCobot 280 X5 PI doc --- docs/MyCobot_280_X5PI_en.md | 492 ++++++++++++++++++++++++++++++++++++ docs/MyCobot_280_X5PI_zh.md | 490 +++++++++++++++++++++++++++++++++++ pymycobot/mycobot280x5pi.py | 51 +--- 3 files changed, 991 insertions(+), 42 deletions(-) create mode 100644 docs/MyCobot_280_X5PI_en.md create mode 100644 docs/MyCobot_280_X5PI_zh.md diff --git a/docs/MyCobot_280_X5PI_en.md b/docs/MyCobot_280_X5PI_en.md new file mode 100644 index 00000000..0ebf4910 --- /dev/null +++ b/docs/MyCobot_280_X5PI_en.md @@ -0,0 +1,492 @@ +# MyCobot 280 X5 PI + +[toc] + +## Python API usage instructions + +API (Application Programming Interface), also known as Application Programming Interface functions, are predefined functions. When using the following function interfaces, please import our API library at the beginning by entering the following code, otherwise it will not run successfully: + +```python +# Example +from pymycobot import MyCobot280X5PI + +mc = MyCobot280X5PI('COM3') + +# Gets the current angle of all joints +angles = mc.get_angles() +print(angles) + +# Set 1 joint to move to 40 and speed to 20 +mc.send_angle(1, 40, 20) +``` + +### 1. System Status + +#### `get_modify_version()` +- **function:** get modify version +#### `get_system_version()` +- **function:** get system version + +### 2. Overall Status + +#### `clear_queue()` +- **function:** Clear the command queue +#### `async_or_sync()` +- **function:** Set the command execution mode +- **Return value:** + - **`0`: Asynchronous mode** + - **`1`: Synchronous mode** +#### `get_error_information()` +- **function:** Obtaining robot error information +- **Return value:** + - **`0`: No error message.** + - **`1 ~ 6`: The corresponding joint exceeds the limit position.** + - **`16 ~ 19`: Collision protection.** + - **`32`: Kinematics inverse solution has no solution.** + - **`33 ~ 34`: Linear motion has no adjacent solution.** +#### `clear_error_information()` +- **function:** Clear robot error message +#### `power_on()` +- **function:** Open communication with Atom. +#### `power_off()` +- **function:** Close communication with Atom. +#### `is_power_on()` +- **function:** Adjust robot arm status +- **Return value:** + - **`1` - power on** + - **`0` - power off** + - **`-1` - error data** +#### `release_all_servos(data)` +- **function:** Relax all joints +- **Parameters:** + - **data: `1` - Undamping (The default is damping)** +#### `read_next_error()` +- **function:** Robot Error Detection +- **Return value:** + - **list len 6.** + - **`0` : No abnormality** + - **`1` : Communication disconnected** + - **`2` : Unstable communication** + - **`3` : Servo abnormality** +#### `set_fresh_mode(mode)` +- **function:** Set command refresh mode +- **Parameters:** + - **mode: int.** + - **`1` - Always execute the latest command first.** + - **`0` - Execute instructions sequentially in the form of a queue.** +#### `get_fresh_mode()` +- **function:** Query sports mode +#### `set_vision_mode(flag)` +- **function:** Set the visual tracking mode to limit the posture flipping of send_coords in refresh mode. + - **(Only for visual tracking function)** +- **Parameters:** + - **flag: 0/1; `0` - close; `1` - open** + +### 3. Motion Control Interface + +#### `get_angles()` +- **function:** Get the angle of all joints. +- **Return value:** + - **list: A float list of all angle.** +#### `send_angle(id, degree, speed)` +- **function:** Send one angle of joint to robot arm. +- **Parameters:** + - **id : Joint id(genre.Angle) int 1-6.** + - **angle : angle value(float).** + - **speed : (int) 1 ~ 100** +#### `send_angles(angles, speed)` +- **function:** Send the angles of all joints to robot arm. +- **Parameters:** + - **angles: a list of angle values(List[float]). len 6.** + - **speed : (int) 1 ~ 100** +#### `get_coords()` +- **function:** Get the coords from robot arm, coordinate system based on base. +- **Return value:** + - **list : A float list of coord .[x, y, z, rx, ry, rz]** +#### `send_coord(id, coord, speed)` +- **function:** Send one coord to robot arm. +- **Parameters:** + - **id(int) : coord id(genre.Coord) int 1-6.** + - **coord(float) : coord value, mm** + - **speed(int) : 1 ~ 100** +#### `send_coords(coords, speed, mode)` +- **function:** Send all coords to robot arm. +- **Parameters:** + - **coords: a list of coords value(List[float]).[x(mm), y, z, rx(angle), ry, rz]** + - **speed : (int) 1 ~ 100** + - **mode : (int) 0 - angluar, 1 - linear** +#### `pause()` +- **function:** Pause movement +#### `is_paused()` +- **function:** Judge whether the manipulator pauses or not. +- **Return value:** + - **`1` - paused** + - **`0` - not paused** + - **`-1` - error** +#### `resume()` +- **function:** Recovery movement +#### `stop()` +- **function:** Stop moving +#### `is_in_position(data, id = 0)` +- **function:** Judge whether in the position. +- **Parameters:** + - **data: A data list, angles or coords.len 6.** + - **id: 1 - coords, 0 - angles** +- **Return value:** + - **`1` - True** + - **`0` - False** + - **`-1` - Error** +#### `is_moving()` +- **function:** Detect if the robot is moving +- **Return value:** + - **`0` - not moving** + - **`1` - is moving** + - **`-1` - error data** +#### `write_angles_time_control(angles, step_time)` +- **function:** Write the angle of a joint in time control mode +- **Parameters:** + - **angles: Angle value** + - **step_time: Time unit: 30ms, range(1 ~ 255)** + +### 4. JOG Mode And Operation + +#### `jog_angle(joint_id, direction, speed)` +- **function:** Jog control angle. +- **Parameters:** + - **joint_id: int 1-6.** + - **direction: `0` - decrease, `1` - increase** + - **speed: int (0 - 100)** +#### `jog_rpy(end_direction, direction, speed)` +- **function:** Rotate the end around a fixed axis in the base coordinate system +- **Parameters:** + - **end_direction (int): Roll, Pitch, Yaw (1-3)** + - **direction (int): `1` - forward rotation, `0` - reverse rotation** + - **speed (int): 1 ~ 100** +#### `jog_coord(coord_id, direction, speed)` +- **function:** Jog control coord. +- **Parameters:** + - **coord_id: int 1-6** + - **direction: `0` - decrease, `1` - increase** + - **speed: int (1 - 100)** +#### `jog_increment_angle(joint_id, increment, speed)` +- **function:** angle step mode +- **Parameters:** + - **joint_id: int 1-6.** + - **increment: Angle increment value** + - **speed: int (0 - 100)** +#### `jog_increment_coord(axis, increment, speed)` +- **function:** coord step mode +- **Parameters:** + - **axis: axis id 1 - 6.** + - **increment: Coord increment value** + - **speed: int (1 - 100)** +#### `set_HTS_gripper_torque(torque)` +- **function:** Set new adaptive gripper torque +- **Parameters:** + - **torque (int): 150 ~ 980** +- **Return value:** + - **0: Set failed** + - **1: Set successful** +#### `get_HTS_gripper_torque()` +- **function:** Get gripper torque +- **Return value:** + - **int: 150 ~ 980** +#### `get_gripper_protect_current()` +- **function:** Get the gripper protection current +- **Return value:** + - **int: 1 ~ 500** +#### `init_gripper()` +- **function:** Initialize gripper +- **Return value:** + - **int: 0 or 1 (1 - success)** +#### `set_gripper_protect_current(current)` +- **function:** Set the gripper protection current +- **Parameters:** + - **current (int): 1 ~ 500** +#### `set_encoder(joint_id, encoder, speed)` +- **function:** Set a single joint rotation to the specified potential value. +- **Parameters:** + - **joint_id: int 1 - 6** + - **for gripper: Joint id 7** + - **encoder: The value of the set encoder.** + - **speed : 1 - 100** +#### `get_encoder(joint_id)` +- **function:** Obtain the specified joint potential value. +- **Parameters:** + - **joint_id: (int) 1 - 6** + - **for gripper: Joint id 7** +#### `set_encoders(encoders, sp)` +- **function:** Set the six joints of the manipulator to execute synchronously to the specified position. +- **Parameters:** + - **encoders: A encoder list. len 6.** + - **sp: speed 1 ~ 100** +#### `get_encoders()` +- **function:** Get the six joints of the manipulator +- **Return value:** + - **The list of encoders** +#### `set_encoders_drag(encoders, speeds)` +- **function:** Send all encoders and speeds +- **Parameters:** + - **encoders: encoders list.** + - **speeds: Obtained by the get_servo_speeds() method** +#### `get_joint_min_angle(joint_id)` +- **function:** Gets the minimum movement angle of the specified joint +- **Parameters:** + - **joint_id: 1 - 6** +- **Return value:** + - **angle value(float)** +#### `get_joint_max_angle(joint_id)` +- **function:** Gets the maximum movement angle of the specified joint +- **Parameters:** + - **joint_id: 1 - 6** +- **Return value:** + - **angle value(float)** +#### `set_joint_min(id, angle)` +- **function:** Set the joint minimum angle +- **Parameters:** + - **id: int.** + - **Joint id 1 - 6** + - **for gripper: Joint id 7** + - **angle: 0 ~ 180** +#### `set_joint_max(id, angle)` +- **function:** Set the joint maximum angle +- **Parameters:** + - **id: int.** + - **Joint id 1 - 6** + - **for gripper: Joint id 7** + - **angle: 0 ~ 180** + +### 5. Servo Control + +#### `is_servo_enable(servo_id)` +- **function:** To detect the connection state of a single joint +- **Parameters:** + - **servo_id: 1 - 6** +- **Return value:** + - **`0` - disable** + - **`1` - enable** + - **`-1` - error** +#### `is_all_servo_enable()` +- **function:** Detect the connection status of all joints +- **Return value:** + - **`0` - disable** + - **`1` - enable** + - **`-1` - error** +#### `set_servo_data(servo_id, data_id, value, mode)` +- **function:** Set the data parameters of the specified address of the steering gear +- **Parameters:** + - **servo_id: Serial number of articulated steering gear. 1 - 7** + - **data_id: Data address.** + - **value: 0 - 4096** + - **mode: 0 - indicates that value is one byte(default), 1 - 1 represents a value of two bytes.** +#### `get_servo_data(servo_id, data_id, mode)` +- **function:** Read the data parameter of the specified address of the steering gear. +- **Parameters:** + - **servo_id: Serial number of articulated steering gear.1 - 7** + - **data_id: Data address.** + - **mode: 0 - indicates that value is one byte(default), 1 - 1 represents a value of two bytes.** +- **Return value:** + - **values 0 - 4096** +#### `set_servo_calibration(servo_id)` +- **function:** The current position of the calibration joint actuator is the angle zero point, + - **and the corresponding potential value is 2048.** +- **Parameters:** + - **servo_id: Serial number of articulated steering gear. 1 - 6** +#### `joint_brake(joint_id)` +- **function:** Make it stop when the joint is in motion, and the buffer distance is positively related to the existing speed +- **Parameters:** + - **joint_id: 1 - 6** +#### `release_servo(servo_id, mode)` +- **function:** Power off designated servo +- **Parameters:** + - **servo_id: int 1 - 6** + - **mode: Default damping, set to 1, cancel damping** +#### `focus_servo(servo_id)` +- **function:** Power on designated servo +- **Parameters:** + - **servo_id: int 1 - 6** + +### 6. Gripper Control + +#### `get_gripper_value(gripper_type)` +- **function:** Get the value of gripper. +- **Parameters:** + - **gripper_type (int): default 1** + - **`1`: Adaptive gripper** + - **`3`: Parallel gripper** + - **`4`: Flexible gripper** +- **Return value:** + - **gripper value (int)** +#### `set_gripper_state(flag, speed, _type_1, is_torque)` +- **function:** Set gripper switch state +- **Parameters:** + - **flag (int): 0 - open, 1 - close, 254 - release** + - **speed (int): 1 ~ 100** + - **_type_1 (int): default 1** + - **`1` : Adaptive gripper. default to adaptive gripper** + - **`2` : 5 finger dexterous hand** + - **`3` : Parallel gripper, this parameter can be omitted** + - **`4` : Flexible gripper** + - **is_torque (int): When there is no type parameter, this parameter can be omitted.** + - **`1`: Force control** + - **`0`: Non-force control** +#### `set_gripper_value(gripper_value, speed, gripper_type, is_torque)` +- **function:** Set gripper value +- **Parameters:** + - **gripper_value (int): 0 ~ 100** + - **speed (int): 1 ~ 100** + - **gripper_type (int): default 1** + - **`1`: Adaptive gripper** + - **`3`: Parallel gripper, this parameter can be omitted** + - **`4`: Flexible gripper** + - **is_torque (int): When there is no type parameter, this parameter can be omitted.** + - **`1`: Force control** + - **`0`: Non-force control** +#### `set_gripper_calibration()` +- **function:** Set the current position to zero, set current position value is `2048`. +#### `is_gripper_moving()` +- **function:** Judge whether the gripper is moving or not +- **Return value:** + - **`0` - not moving** + - **`1` - is moving** + - **`-1` - error data** + +### 7. End ATOM Function + +#### `get_tool_system_version()` +- **function:** Read the terminal primary and minor version numbers +#### `get_tool_modify_version()` +- **function:** Read the terminal modified version number +#### `is_tool_connected()` +- **function:** Check the end connection status +#### `set_color(r = 0, g = 0, b = 0)` +- **function:** Set the light color on the top of the robot arm. +- **Parameters:** + - **r (int): 0 ~ 255** + - **g (int): 0 ~ 255** + - **b (int): 0 ~ 255** +#### `is_tool_button_click()` +- **function:** Check whether the button on the end is pressed +#### `set_digital_output(pin_no, pin_signal)` +- **function:** Set the terminal atom io status +- **Parameters:** + - **pin_no (int):** + - **pin_signal (int): 0 / 1** +#### `get_digital_input(pin_no)` +- **function:** singal value + +### 8. Kinematic Algorithm Interface + +#### `solve_inv_kinematics(target_coords, current_angles)` +- **function:** Convert target coordinates to angles +- **Parameters:** + - **target_coords: A float list of all coordinates.** + - **current_angles : A float list of all angle.** +- **Return value:** + - **list: A float list of all angle.** + +### 9. Coordinate System Interface + +#### `set_tool_reference(coords)` +- **function:** Set tool coordinate system +- **Parameters:** + - **coords: a list of coords value(List[float])** + - **[x(mm), y, z, rx(angle), ry, rz]** +#### `get_tool_reference()` +- **function:** Get tool coordinate system +#### `set_world_reference(coords)` +- **function:** Set the world coordinate system +- **Parameters:** + - **coords: a list of coords value(List[float])** + - **[x(mm), y, z, rx(angle), ry, rz]** +#### `get_world_reference()` +- **function:** Get the world coordinate system +#### `set_reference_frame(rftype)` +- **function:** Set the base coordinate system +- **Parameters:** + - **rftype: 0 - base 1 - tool.** +#### `get_reference_frame()` +- **function:** Get the base coordinate system +- **Return value:** + - **`0` - base `1` - tool.** +#### `set_movement_type(move_type)` +- **function:** Set movement type +- **Parameters:** + - **move_type: `1` - movel, `0` - moveJ** +#### `get_movement_type()` +- **function:** Get movement type +- **Return value:** + - **`1` - movel, `0` - moveJ** +#### `set_end_type(end)` +- **function:** Set end coordinate system +- **Parameters:** + - **end: int** + - **`0` - flange, `1` - tool** +#### `get_end_type()` +- **function:** Get end coordinate system +- **Return value:** + - **`0` - flange, `1` - tool** + +### 10. 9G Servo machine backgammon + +#### `move_round()` +- **function:** Drive the 9g steering gear clockwise for one revolution +#### `set_four_pieces_zero()` +- **function:** Set the zero position of the four-piece motor +- **Return value:** + - **int: `0` or `1` (1 - success)** + +### 11. Stdio Interface + +#### `get_angles_coords()` +- **function:** Get joint angles and coordinates +#### `get_quick_move_message()` +- **function:** Get the quick move message +#### `get_servo_speeds()` +- **function:** Get joint speed +- **Return value:** + - **A list unit step/s** + +### 12. Servo State Value Interface + +#### `get_servo_currents()` +- **function:** Get all joint current +- **Return value:** + - **A list unit mA** +#### `get_servo_voltages()` +- **function:** Get joint voltages +- **Return value:** + - **A list volts < 24 V** +#### `get_servo_status()` +- **function:** Get joint status +- **Return value:** + - **[voltage, sensor, temperature, current, angle, overload], a value of 0 means no error, a value of 1 indicates an error** +#### `get_servo_temps()` +- **function:** Get joint temperature +- **Return value:** + - **A list unit ** + +### 13. Drag Track Interface + +#### `drag_start_record()` +- **function:** Start track recording +- **Return value:** + - **Recording queue length** +#### `drag_end_record()` +- **function:** End track recording +- **Return value:** + - **Recording queue length** +#### `drag_get_record_data()` +- **function:** Get the recorded track +- **Return value:** + - **List of potential values (encoder values) and operating speeds of each joint** + - **eg: [J1_encoder, J1_run_speed,J2_encoder, J2_run_speed,J3_encoder, J3_run_speed,J4_encoder, J4_run_speed,J5_** + - **encoder, J5_run_speed,J6_encoder, J6_run_speed]** +#### `drag_get_record_len()` +- **function:** Get the total number of recorded points +- **Return value:** + - **Recording queue length** +#### `drag_clear_record_data()` +- **function:** Clear recording track +- **Return value:** + - **Recording queue length 0** \ No newline at end of file diff --git a/docs/MyCobot_280_X5PI_zh.md b/docs/MyCobot_280_X5PI_zh.md new file mode 100644 index 00000000..5269951d --- /dev/null +++ b/docs/MyCobot_280_X5PI_zh.md @@ -0,0 +1,490 @@ +# MyCobot 280 X5 PI + +[toc] + +## Python API ʹ˵ + +APIApplication Programming InterfaceӦó̽ӿڣԤȶĺʹºӿʱڿͷǵAPI⣬޷ɹУ + +```python +# ʾ +from pymycobot import MyCobot280X5PI + +mc = MyCobot280X5PI('COM3') + +# ȡйؽڵǰǶ +angles = mc.get_angles() +print(angles) + +# 1Źؽƶ40ȣٶ20 +mc.send_angle(1, 40, 20) +``` + +### 1. ϵͳ״̬ + +#### `get_modify_version()` +- **:** ȡ޸İ汾 +#### `get_system_version()` +- **:** ȡϵͳ汾 + +### 2. ״̬ + +#### `clear_queue()` +- **:** +#### `async_or_sync()` +- **:** ִģʽ +- **ֵ:** + - **`0`: 첽ģʽ** + - **`1`: ͬģʽ** +#### `get_error_information()` +- **:** ȡ˴Ϣ +- **ֵ:** + - **`0`: ޴** + - **`1~6`: Ӧؽڳ** + - **`16~19`: ײ** + - **`32`: ˶ѧ޽** + - **`33~34`: ֱ˶ڽ** +#### `clear_error_information()` +- **:** ˴Ϣ +#### `power_on()` +- **:** Atomͨ +#### `power_off()` +- **:** رAtomͨ +#### `is_power_on()` +- **:** е۵Դ״̬ +- **ֵ:** + - **`1` - ϵ** + - **`0` - Ѷϵ** + - **`-1` - ݴ** +#### `release_all_servos(data)` +- **:** ͷйؽ +- **:** + - **data: `1` - ȡ(Ĭ)** +#### `read_next_error()` +- **:** ˴ +- **ֵ:** + - **6б** + - **`0`: ** + - **`1`: ͨŶϿ** + - **`2`: ͨŲȶ** + - **`3`: 쳣** +#### `set_fresh_mode(mode)` +- **:** ˢģʽ +- **:** + - **mode: int** + - **`1` - ִ** + - **`0` - ˳ִ** +#### `get_fresh_mode()` +- **:** ѯ˶ģʽ +#### `set_vision_mode(flag)` +- **:** Ӿģʽ(ˢģʽsend_coordsλ˷ת) + - **(Ӿٹʹ)** +- **:** + - **flag: 0/1; `0` - ر; `1` - ** + +### 3. ˶ƽӿ + +#### `get_angles()` +- **:** ȡйؽڽǶ +- **ֵ:** + - **list: Ƕȸб** +#### `send_angle(id, degree, speed)` +- **:** ͵ؽڽǶ +- **:** + - **id : ؽID(1-6)** + - **angle : Ƕֵ(float)** + - **speed : (int) 1~100** +#### `send_angles(angles, speed)` +- **:** йؽڽǶ +- **:** + - **angles: Ƕֵб(List[float])6** + - **speed : (int) 1~100** +#### `get_coords()` +- **:** ȡϵ +- **ֵ:** + - **list: 긡б[x, y, z, rx, ry, rz]** +#### `send_coord(id, coord, speed)` +- **:** ͵ֵ +- **:** + - **id(int) : ID(1-6)** + - **coord(float) : ֵ(mm)** + - **speed(int) : 1~100** +#### `send_coords(coords, speed, mode)` +- **:** ֵ +- **:** + - **coords: ֵб(List[float])[x(mm), y, z, rx(Ƕ), ry, rz]** + - **speed : (int) 1~100** + - **mode : (int) 0 - Ƕģʽ, 1 - ֱģʽ** +#### `pause()` +- **:** ͣ˶ +#### `is_paused()` +- **:** жϻеǷͣ +- **ֵ:** + - **`1` - ͣ** + - **`0` - ** + - **`-1` - ** +#### `resume()` +- **:** ָ˶ +#### `stop()` +- **:** ֹͣ˶ +#### `is_in_position(data, id = 0)` +- **:** жǷ񵽴Ŀλ +- **:** + - **data: λб(ǶȻ)6** + - **id: 1 - ģʽ, 0 - Ƕģʽ** +- **ֵ:** + - **`1` - ** + - **`0` - ** + - **`-1` - ** +#### `is_moving()` +- **:** еǷ˶ +- **ֵ:** + - **`0` - ֹ** + - **`1` - ˶** + - **`-1` - ݴ** +#### `write_angles_time_control(angles, step_time)` +- **:** ʱģʽдؽڽǶ +- **:** + - **angles: Ƕֵ** + - **step_time: ʱ䵥λ30msΧ1~255** + +### 4. JOGģʽ + +#### `jog_angle(joint_id, direction, speed)` +- **:** ؽģʽ㶯 +- **:** + - **joint_id: 1-6** + - **direction: `0` - , `1` - ** + - **speed: (0-100)** +#### `jog_rpy(end_direction, direction, speed)` +- **:** ƻϵ̶תĩ +- **:** + - **end_direction (int): ƫ(1-3)** + - **direction (int): `1` - ת, `0` - ת** + - **speed (int): 1~100** +#### `jog_coord(coord_id, direction, speed)` +- **:** ģʽ㶯 +- **:** + - **coord_id: 1-6** + - **direction: `0` - , `1` - ** + - **speed: (1-100)** +#### `jog_increment_angle(joint_id, increment, speed)` +- **:** ǶȲģʽ +- **:** + - **joint_id: 1-6** + - **increment: Ƕֵ** + - **speed: (0-100)** +#### `jog_increment_coord(axis, increment, speed)` +- **:** 경ģʽ +- **:** + - **axis: ID 1-6** + - **increment: ֵ** + - **speed: (1-100)** +#### `set_HTS_gripper_torque(torque)` +- **:** ӦצŤ +- **:** + - **torque (int): 150~980** +- **ֵ:** + - **0: ʧ** + - **1: óɹ** +#### `get_HTS_gripper_torque()` +- **:** ȡצŤ +- **ֵ:** + - **int: 150~980** +#### `get_gripper_protect_current()` +- **:** ȡצ +- **ֵ:** + - **int: 1~500** +#### `init_gripper()` +- **:** ʼצ +- **ֵ:** + - **int: 01(1-ɹ)** +#### `set_gripper_protect_current(current)` +- **:** üצ +- **:** + - **current (int): 1~500** +#### `set_encoder(joint_id, encoder, speed)` +- **:** õؽڵλֵ +- **:** + - **joint_id: 1-6** + - **צӦؽIDΪ7** + - **encoder: Ŀλֵ** + - **speed : 1-100** +#### `get_encoder(joint_id)` +- **:** ȡָؽڵλֵ +- **:** + - **joint_id: (int) 1-6** + - **צӦؽIDΪ7** +#### `set_encoders(encoders, sp)` +- **:** ͬйؽڵλֵ +- **:** + - **encoders: λֵб6** + - **sp: ٶ1~100** +#### `get_encoders()` +- **:** ȡйؽڱֵ +- **ֵ:** + - **ֵб** +#### `set_encoders_drag(encoders, speeds)` +- **:** бֵٶ +- **:** + - **encoders: б** + - **speeds: ͨget_servo_speeds()ȡٶֵ** +#### `get_joint_min_angle(joint_id)` +- **:** ȡָؽСǶ +- **:** + - **joint_id: 1-6** +- **ֵ:** + - **Ƕֵ(float)** +#### `get_joint_max_angle(joint_id)` +- **:** ȡָؽǶ +- **:** + - **joint_id: 1-6** +- **ֵ:** + - **Ƕֵ(float)** +#### `set_joint_min(id, angle)` +- **:** ùؽСǶ +- **:** + - **id: int** + - **ؽID 1-6** + - **צӦؽIDΪ7** + - **angle: 0~180** +#### `set_joint_max(id, angle)` +- **:** ùؽǶ +- **:** + - **id: int** + - **ؽID 1-6** + - **צӦؽIDΪ7** + - **angle: 0~180** + +### 5. + +#### `is_servo_enable(servo_id)` +- **:** ⵥؽ״̬ +- **:** + - **servo_id: 1-6** +- **ֵ:** + - **`0` - δʹ** + - **`1` - ʹ** + - **`-1` - ** +#### `is_all_servo_enable()` +- **:** йؽ״̬ +- **ֵ:** + - **`0` - δʹ** + - **`1` - ʹ** + - **`-1` - ** +#### `set_servo_data(servo_id, data_id, value, mode)` +- **:** öַָ +- **:** + - **servo_id: ؽڶ1-7** + - **data_id: ݵַ** + - **value: 0-4096** + - **mode: 0 - ֵֽ(Ĭ), 1 - ˫ֵֽ** +#### `get_servo_data(servo_id, data_id, mode)` +- **:** ȡַָ +- **:** + - **servo_id: ؽڶ1-7** + - **data_id: ݵַ** + - **mode: 0 - ֵֽ(Ĭ), 1 - ˫ֵֽ** +- **ֵ:** + - **0-4096Χֵ** +#### `set_servo_calibration(servo_id)` +- **:** У׼ؽڵǰλΪ(Ӧλֵ2048) +- **:** + - **servo_id: ؽڶ1-6** +#### `joint_brake(joint_id)` +- **:** ؽ˶мͣ(뵱ǰٶ) +- **:** + - **joint_id: 1-6** +#### `release_servo(servo_id, mode)` +- **:** µָ +- **:** + - **servo_id: 1-6** + - **mode: ĬᣬΪ1ȡ** +#### `focus_servo(servo_id)` +- **:** ϵָ +- **:** + - **servo_id: 1-6** + +### 6. צ + +#### `get_gripper_value(gripper_type)` +- **:** ȡצ״ֵ̬ +- **:** + - **gripper_type (int): Ĭ1** + - **`1`: Ӧצ** + - **`3`: ƽмצ** + - **`4`: Լצ** +- **ֵ:** + - **צ״ֵ̬(int)** +#### `set_gripper_state(flag, speed, _type_1, is_torque)` +- **:** üצ״̬ +- **:** + - **flag (int): 0 - , 1 - ر, 254 - ͷ** + - **speed (int): 1~100** + - **_type_1 (int): Ĭ1** + - **`1` : Ӧצ** + - **`2` : ָ** + - **`3` : ƽмצ(ʡ)** + - **`4` : Լצ** + - **is_torque (int): Ͳʱʡ** + - **`1`: ** + - **`0`: ** +#### `set_gripper_value(gripper_value, speed, gripper_type, is_torque)` +- **:** üצ϶ +- **:** + - **gripper_value (int): 0~100** + - **speed (int): 1~100** + - **gripper_type (int): Ĭ1** + - **`1`: Ӧצ** + - **`3`: ƽмצ(ʡ)** + - **`4`: Լצ** + - **is_torque (int): Ͳʱʡ** + - **`1`: ** + - **`0`: ** +#### `set_gripper_calibration()` +- **:** õǰλΪ(Ӧλֵ2048) +#### `is_gripper_moving()` +- **:** жϼצǷ˶ +- **ֵ:** + - **`0` - ֹ** + - **`1` - ˶** + - **`-1` - ݴ** + +### 7. ĩATOM + +#### `get_tool_system_version()` +- **:** ȡĩΰ汾 +#### `get_tool_modify_version()` +- **:** ȡĩ޸İ汾 +#### `is_tool_connected()` +- **:** ĩ״̬ +#### `set_color(r = 0, g = 0, b = 0)` +- **:** ûе۶ƹɫ +- **:** + - **r (int): 0~255** + - **g (int): 0~255** + - **b (int): 0~255** +#### `is_tool_button_click()` +- **:** ĩ˰ťǷ +#### `set_digital_output(pin_no, pin_signal)` +- **:** ĩAtom IO״̬ +- **:** + - **pin_no (int): ź** + - **pin_signal (int): 0/1** +#### `get_digital_input(pin_no)` +- **:** ȡźֵ + +### 8. ˶ѧ㷨ӿ + +#### `solve_inv_kinematics(target_coords, current_angles)` +- **:** ĿתΪؽڽǶ +- **:** + - **target_coords: Ŀ긡б** + - **current_angles : ǰǶȸб** +- **ֵ:** + - **list: ؽڽǶȸб** + +### 9. ϵӿ + +#### `set_tool_reference(coords)` +- **:** ùϵ +- **:** + - **coords: ֵб(List[float])** + - **[x(mm), y, z, rx(Ƕ), ry, rz]** +#### `get_tool_reference()` +- **:** ȡϵ +#### `set_world_reference(coords)` +- **:** ϵ +- **:** + - **coords: ֵб(List[float])** + - **[x(mm), y, z, rx(Ƕ), ry, rz]** +#### `get_world_reference()` +- **:** ȡϵ +#### `set_reference_frame(rftype)` +- **:** ûϵ +- **:** + - **rftype: 0 - ϵ, 1 - ϵ** +#### `get_reference_frame()` +- **:** ȡϵ +- **ֵ:** + - **`0` - ϵ, `1` - ϵ** +#### `set_movement_type(move_type)` +- **:** ˶ +- **:** + - **move_type: `1` - ֱ˶, `0` - ؽ˶** +#### `get_movement_type()` +- **:** ȡ˶ +- **ֵ:** + - **`1` - ֱ˶, `0` - ؽ˶** +#### `set_end_type(end)` +- **:** ĩϵ +- **:** + - **end: int** + - **`0` - ϵ, `1` - ϵ** +#### `get_end_type()` +- **:** ȡĩϵ +- **ֵ:** + - **`0` - ϵ, `1` - ϵ** + +### 10. 9G + +#### `move_round()` +- **:** 9g˳ʱתһ +#### `set_four_pieces_zero()` +- **:** ļ׵λ +- **ֵ:** + - **int: `0``1`(1-ɹ)** + +### 11. ׼ӿ + +#### `get_angles_coords()` +- **:** ȡؽڽǶȺ +#### `get_quick_move_message()` +- **:** ȡƶϢ +#### `get_servo_speeds()` +- **:** ȡؽٶ +- **ֵ:** + - **ٶб(λ:/)** + +### 12. ״ֵ̬ӿ + +#### `get_servo_currents()` +- **:** ȡйؽڵ +- **ֵ:** + - **б(λmA)** +#### `get_servo_voltages()` +- **:** ȡؽڵѹ +- **ֵ:** + - **ѹб(С24V)** +#### `get_servo_status()` +- **:** ȡؽ״̬ +- **ֵ:** + - **[ѹ, , ¶, , Ƕ, ], 0ʾ1ʾ쳣** +#### `get_servo_temps()` +- **:** ȡؽ¶ +- **ֵ:** + - **¶б(λ)** + +### 13. ϶켣ӿ + +#### `drag_start_record()` +- **:** ʼ켣¼ +- **ֵ:** + - **¼г** +#### `drag_end_record()` +- **:** 켣¼ +- **ֵ:** + - **¼г** +#### `drag_get_record_data()` +- **:** ȡѼ¼켣 +- **ֵ:** + - **ؽڵλֵ(ֵ)ٶȵб** + - **ʾ: [J1ֵ,J1ٶ,J2ֵ,J2ٶ,J3ֵ,J3ٶ,J4ֵ,J4ٶ,J5ֵ,J5ٶ,J6ֵ,J6ٶ]** +#### `drag_get_record_len()` +- **:** ȡѼ¼ +- **ֵ:** + - **¼г** +#### `drag_clear_record_data()` +- **:** Ѽ¼켣 +- **ֵ:** + - **¼гȹ** diff --git a/pymycobot/mycobot280x5pi.py b/pymycobot/mycobot280x5pi.py index bb4a331e..59942327 100644 --- a/pymycobot/mycobot280x5pi.py +++ b/pymycobot/mycobot280x5pi.py @@ -4,7 +4,6 @@ import functools import time -import math import threading import serial @@ -284,46 +283,6 @@ def set_vision_mode(self, flag): self.calibration_parameters(flag=flag) return self._mesg(ProtocolCode.SET_VISION_MODE, flag) - # Overall Status - def set_free_mode(self, flag): - """set to free mode - - Args: - flag: 0/1 - """ - self.calibration_parameters(flag=flag) - return self._mesg(ProtocolCode.SET_FREE_MODE, flag) - - def is_free_mode(self): - """Check if it is free mode - - Return: - 0/1 - """ - return self._mesg(ProtocolCode.IS_FREE_MODE, has_reply=True) - - # MDI mode and operation - def get_radians(self): - """Get the radians of all joints - - Return: - list: A list of float radians [radian1, ...] - """ - angles = self._mesg(ProtocolCode.GET_ANGLES, has_reply=True) - return [round(angle * (math.pi / 180), 3) for angle in angles] - - def send_radians(self, radians, speed): - """Send the radians of all joints to robot arm - - Args: - radians: a list of radian values( List[float]), length 6 - speed: (int )0 ~ 100 - """ - calibration_parameters(len6=radians, speed=speed) - degrees = [self._angle2int(radian * (180 / math.pi)) - for radian in radians] - return self._mesg(ProtocolCode.SEND_ANGLES, degrees, speed) - def sync_send_angles(self, degrees, speed, timeout=15): """Send the angle in synchronous state and return when the target point is reached @@ -504,7 +463,7 @@ def get_tool_system_version(self): """ return self._mesg(ProtocolCode.GET_ATOM_VERSION, has_reply=True) - def get_tool_modified_version(self): + def get_tool_modify_version(self): """ Read the terminal modified version number """ @@ -589,6 +548,14 @@ def get_servo_speeds(self): """ return self._mesg(ProtocolCode.GET_SERVO_SPEED, has_reply=True) + def get_servo_currents(self): + """Get all joint current + + Return: + A list unit mA + """ + return self._mesg(ProtocolCode.GET_SERVO_CURRENTS, has_reply=True) + def get_servo_voltages(self): """Get joint voltages From 6156a5047205b0643115d94ec9cba5d3944be2cc Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Thu, 13 Feb 2025 18:20:33 +0800 Subject: [PATCH 03/57] Fix MyCobot 280 X5 Pi doc errors --- docs/MyCobot_280_X5PI_en.md | 2 +- docs/MyCobot_280_X5PI_zh.md | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/MyCobot_280_X5PI_en.md b/docs/MyCobot_280_X5PI_en.md index 0ebf4910..cf8bf1df 100644 --- a/docs/MyCobot_280_X5PI_en.md +++ b/docs/MyCobot_280_X5PI_en.md @@ -10,7 +10,7 @@ API (Application Programming Interface), also known as Application Programming I # Example from pymycobot import MyCobot280X5PI -mc = MyCobot280X5PI('COM3') +mc = MyCobot280X5PI('/dev/ttyS1') # Gets the current angle of all joints angles = mc.get_angles() diff --git a/docs/MyCobot_280_X5PI_zh.md b/docs/MyCobot_280_X5PI_zh.md index 5269951d..6578ce47 100644 --- a/docs/MyCobot_280_X5PI_zh.md +++ b/docs/MyCobot_280_X5PI_zh.md @@ -10,7 +10,7 @@ API # ʾ from pymycobot import MyCobot280X5PI -mc = MyCobot280X5PI('COM3') +mc = MyCobot280X5PI('/dev/ttyS1') # ȡйؽڵǰǶ angles = mc.get_angles() From 3021fa25949a0e246486683f0fec9f50d6d1f31e Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Fri, 14 Feb 2025 15:57:27 +0800 Subject: [PATCH 04/57] add MyCobot 280 X5 PI sokcet sever&client --- demo/Server_280_X5PI.py | 203 ++++++++++++++++++++++++++++++++++++ pymycobot/__init__.py | 5 +- pymycobot/mycobot280x5pi.py | 144 ++++++++++++++++++++----- 3 files changed, 325 insertions(+), 27 deletions(-) create mode 100644 demo/Server_280_X5PI.py diff --git a/demo/Server_280_X5PI.py b/demo/Server_280_X5PI.py new file mode 100644 index 00000000..03cc6ec1 --- /dev/null +++ b/demo/Server_280_X5PI.py @@ -0,0 +1,203 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import fcntl +import logging +import traceback +import typing as T +import socket +import struct +import serial +import Hobot.GPIO as GPIO + +GPIO.setwarnings(False) + + +class GPIOProtocolCode: + SETUP_GPIO_MODE = 0xAA + SETUP_GPIO_STATE = 0xAB + SET_GPIO_OUTPUT = 0xAC + GET_GPIO_INPUT = 0xAD + + +def to_string(data: bytes) -> str: + return ' '.join(map(lambda x: f'{x:02x}', data)) + + +def get_local_host(name: str) -> T.Optional[str]: + host = None + dgram_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) + try: + pack_res = struct.pack('256s', bytes(name, encoding="utf8")) + host = socket.inet_ntoa(fcntl.ioctl(dgram_socket.fileno(), 0x8915, pack_res)[20:24]) + except Exception as e: + print(e) + finally: + dgram_socket.close() + return host + + +localhost = get_local_host("wlan0") + + +class SocketTransport(object): + def __init__(self, host: str = "0.0.0.0", port: int = 30002): + self.port = port + self.host = host + self.running = True + self.log = logging.getLogger("socket") + self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.socket.bind((host, port)) + self.socket.listen(5) + if host == "0.0.0.0": + host = localhost + self.log.info(f"start listening on {host}:{port}") + + def accept(self): + while self.running is True: + yield self.socket.accept() + + def context(self, conn: socket.socket, buffer_size: int = 1024): + while self.running is True: + try: + data_buffer = conn.recv(buffer_size) + if len(data_buffer) == 0: + break + yield data_buffer + except Exception as e: + self.log.error(f"error while reading socket: {e}") + traceback.print_exc() + break + + def close(self): + self.log.info(f"close socket on {self.host}:{self.port}") + self.running = False + self.socket.close() + + +class SerialTransport(object): + def __init__(self, comport: str = "/dev/ttyS1", baudrate: int = 100_0000, timeout: float = None): + self.serial = serial.Serial(port=comport, baudrate=baudrate, timeout=timeout) + self.log = logging.getLogger("serial") + self.baudrate = baudrate + self.comport = comport + self.open() + self.log.info(f"start serial on [{self.comport}] with baudrate [{self.baudrate}]") + + def send(self, data: bytes): + self.serial.write(data) + + def recv(self, size: int = 1024) -> bytes: + return self.serial.read(size) + + @property + def is_open(self): + return self.serial.is_open + + def close(self): + self.serial.close() + + def open(self): + if not self.serial.is_open: + self.serial.open() + + +class Server280X5PI(object): + """ + Server for 280 X5 Pi + + 1. System GPIO operating protocol adheres to protocol MyCobot 280 x5 PI. + 2. This server only does the work of forwarding protocol and does not participate in the analysis of instructions. + 3. The server is only responsible for forwarding the data received from the socket to the serial port and vice versa. + 4. Instruction parsing is done entirely by the client + 5. The server is responsible for setting the GPIO mode + """ + def __init__(self, socket_transport: SocketTransport, serial_transport: SerialTransport, debug=True): + self.debug = debug + self.socket_transport = socket_transport + self.serial_transport = serial_transport + self.log = logging.getLogger("server") + + def mainloop(self): + try: + self.log.info("tcp server started.") + for conn, addr in self.socket_transport.accept(): + self.log.info(f"{addr} accepted!") + for data in self.socket_transport.context(conn, buffer_size=1024): + self.serial_transport.log.info(f"{addr} recv << {to_string(data)}") + if data[3] == GPIOProtocolCode.SETUP_GPIO_MODE: + try: + mode = GPIO.BCM if data[4] == 0 else GPIO.BOARD + GPIO.setmode(mode) + self.log.debug(f"{addr} setup gpio mode => {mode}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0x01, 0xfa]) + except Exception as e: + self.log.error(f"{addr} setup gpio mode error: {e}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0xff, 0xfa]) + + elif data[3] == GPIOProtocolCode.SETUP_GPIO_STATE: + try: + mode = GPIO.OUT if data[5] == 1 else GPIO.IN + level = GPIO.HIGH if data[6] == 1 else GPIO.LOW + self.log.debug(f"{addr} setup gpio state, mode => {mode}, level => {level}") + GPIO.setup(data[4], mode, initial=level) + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0x01, 0xfa]) + except Exception as e: + self.log.error(f"{addr} setup gpio state error: {e}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0xff, 0xfa]) + + elif data[3] == GPIOProtocolCode.SET_GPIO_OUTPUT: + try: + level = GPIO.HIGH if data[5] == 1 else GPIO.LOW + self.log.debug(f"{addr} set gpio output, level => {level}") + GPIO.output(data[4], level) + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0x01, 0xfa]) + except Exception as e: + self.log.error(f"{addr} set gpio output error: {e}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0xff, 0xfa]) + + elif data[3] == GPIOProtocolCode.GET_GPIO_INPUT: + try: + self.log.debug(f"{addr} get gpio input, channel => {data[4]}") + level = GPIO.input(data[4]) + self.log.debug(f"{addr} get gpio input, level => {level}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], level, 0xfa]) + except Exception as e: + self.log.error(f"{addr} get gpio input error: {e}") + serial_data = bytes([0xfe, 0xfe, 0x03, data[3], 0xff, 0xfa]) + else: + self.serial_transport.send(data) + serial_data = self.serial_transport.recv() + + self.serial_transport.log.info(f"{addr} send >> {to_string(serial_data)}") + conn.send(serial_data) + else: + self.log.info(f"{addr} closed!") + except Exception as e: + self.log.error(f"server error: {e}") + self.log.exception(traceback.format_exc()) + finally: + self.socket_transport.close() + self.serial_transport.close() + self.log.info("server closed") + + +def main(debug: bool = False): + logging.basicConfig( + level=logging.DEBUG if debug else logging.INFO, + format="%(asctime)s - [%(name)s] %(levelname)7s - %(message)s", + handlers=[ + logging.StreamHandler(), + logging.FileHandler("server.log") + ] + ) + + socket_transport = SocketTransport(host="0.0.0.0", port=30002) + + serial_transport = SerialTransport(comport="/dev/ttyS1", baudrate=100_0000, timeout=0.1) + + Server280X5PI(socket_transport, serial_transport).mainloop() + GPIO.cleanup() + + +if __name__ == '__main__': + main() diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index 157cc6f8..e3e13144 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -4,7 +4,7 @@ import datetime import sys from pymycobot.mycobot280 import MyCobot280 -from pymycobot.mycobot280x5pi import MyCobot280X5PI +from pymycobot.mycobot280x5pi import MyCobot280X5PI, MyCobot280X5PISocket from pymycobot.mypalletizer260 import MyPalletizer260 from pymycobot.mecharm270 import MechArm270 from pymycobot.mycobot280socket import MyCobot280Socket @@ -79,7 +79,8 @@ "MyArmMControl", "ChassisControl", "ConveyorAPI", - "MyCobot280X5PI" + "MyCobot280X5PI", + "MyCobot280X5PISocket" ] if sys.platform == "linux": diff --git a/pymycobot/mycobot280x5pi.py b/pymycobot/mycobot280x5pi.py index 59942327..d3200788 100644 --- a/pymycobot/mycobot280x5pi.py +++ b/pymycobot/mycobot280x5pi.py @@ -3,6 +3,7 @@ from __future__ import division import functools +import socket import time import threading import serial @@ -12,7 +13,7 @@ from pymycobot.error import calibration_parameters -def setup_serial_port(port, baudrate, timeout): +def setup_serial_connect(port, baudrate, timeout): serial_api = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) serial_api.rts = False if not serial_api.is_open: @@ -20,18 +21,28 @@ def setup_serial_port(port, baudrate, timeout): return serial_api +def setup_socket_connect(host, port, timeout): + socket_api = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + socket_api.settimeout(timeout) + socket_api.connect((host, port)) + return socket_api + + +class GPIOProtocolCode: + SETUP_GPIO_MODE = 0xAA + SETUP_GPIO_STATE = 0xAB + SET_GPIO_OUTPUT = 0xAC + GET_GPIO_INPUT = 0xAD + + class MyCobot280X5Api(CommandGenerator): - def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): + def __init__(self, debug=False, thread_lock=True): super(MyCobot280X5Api, self).__init__(debug) - self._serial_port = setup_serial_port(port, baudrate, timeout) + self.calibration_parameters = functools.partial(calibration_parameters, class_name="MyCobot280") self.thread_lock = thread_lock self.lock = threading.Lock() - self.calibration_parameters = functools.partial(calibration_parameters, class_name="MyCobot280") - self._write = functools.partial(write, self) - self._read = functools.partial(read, self) - def _mesg(self, genre, *args, **kwargs): """ @@ -161,24 +172,8 @@ def wait(self, t): time.sleep(t) return self - def close(self): - self._serial_port.close() - def open(self): - self._serial_port.open() - - -class MyCobot280X5PI(MyCobot280X5Api): - - def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): - """ - Args: - port : port string - baudrate : baud rate int, default 100_0000 - timeout : default 0.1 - debug : whether show debug info - """ - super().__init__(port, baudrate, timeout, debug, thread_lock) +class MyCobot280X5PICommandGenerator(MyCobot280X5Api): # System Status def get_modify_version(self): @@ -801,4 +796,103 @@ def drag_clear_record_data(self): Recording queue length 0 """ - return self._mesg(ProtocolCode.DRAG_CLEAR_RECORD_DATA, has_reply=True) \ No newline at end of file + return self._mesg(ProtocolCode.DRAG_CLEAR_RECORD_DATA, has_reply=True) + + +class MyCobot280X5PI(MyCobot280X5PICommandGenerator): + + def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): + """ + Args: + port : port string + baudrate : baud rate int, default 100_0000 + timeout : default 0.1 + debug : whether show debug info + """ + super().__init__(debug, thread_lock) + self._serial_port = setup_serial_connect(port=port, baudrate=baudrate, timeout=timeout) + self._write = functools.partial(write, self) + self._read = functools.partial(read, self) + + def close(self): + self._serial_port.close() + + def open(self): + self._serial_port.open() + + +class MyCobot280X5PISocket(MyCobot280X5PICommandGenerator): + """MyCobot 280 X5 PI Socket Control Class + + server file: https://github.com/elephantrobotics/pymycobot/demo/Server_280_X5PI.py + """ + def __init__(self, ip, port=30002, timeout=0.1, debug=False, thread_lock=True): + super().__init__(debug, thread_lock) + self.sock = setup_socket_connect(ip, port, timeout) + self._write = functools.partial(write, self, method="socket") + self._read = functools.partial(read, self, method="socket") + + def set_gpio_mode(self, mode): + """Set pin coding method + Args: + mode: (int) 0 - BCM, 1 - BOARD + + returns: + (int) 1 - success, 255 - error + """ + if mode not in (0, 1): + raise ValueError("mode must be 0 or 1") + return self._mesg(GPIOProtocolCode.SETUP_GPIO_MODE, mode) + + def setup_gpio_state(self, pin_no, mode, initial=1): + """Set the pin as input or output + Args: + pin_no: (int) pin id + mode: (int) 0 - input, 1 - output + initial: (int) 0 - low, 1 - high + returns: + (int) 1 - success, 255 - error + """ + if mode not in (0, 1): + raise ValueError("mode must be 0 or 1") + + if initial not in (0, 1): + raise ValueError("initial must be 0 or 1") + + return self._mesg(GPIOProtocolCode.SETUP_GPIO_STATE, pin_no, mode, initial) + + def set_gpio_output(self, pin_no, state): + """Set the pin to high or low level + Args: + pin_no: (int) pin id. + state: (int) 0 - low, 1 - high + returns: + (int) 1 - success, 255 - error + """ + return self._mesg(GPIOProtocolCode.SET_GPIO_OUTPUT, pin_no, state) + + def get_gpio_input(self, pin_no): + """Get pin level status. + Args: + pin_no: (int) pin id. + Returns: + (int) 0 - low, 1 - high, 255 - error + """ + return self._mesg(GPIOProtocolCode.GET_GPIO_INPUT, pin_no, has_reply=True) + + def close(self): + self.sock.close() + + +def main(): + mc_sock = MyCobot280X5PISocket('192.168.1.246', port=30002, debug=True) + # print(mc_sock.send_angle(1, 100, 50)) + # print(mc_sock.get_quick_move_message()) + print(mc_sock.set_gpio_mode(0)) + print(mc_sock.setup_gpio_state(5, 1, initial=1)) + print(mc_sock.set_gpio_output(5, 0)) + # print(mc_sock.get_gpio_input(5)) + + +if __name__ == '__main__': + main() From d6893f61af826ce11680104609b595a33980746f Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Fri, 14 Feb 2025 16:12:07 +0800 Subject: [PATCH 05/57] MyCobot 280 X5 PI server compatible with python2 --- demo/Server_280_X5PI.py | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/demo/Server_280_X5PI.py b/demo/Server_280_X5PI.py index 03cc6ec1..7f38b2d9 100644 --- a/demo/Server_280_X5PI.py +++ b/demo/Server_280_X5PI.py @@ -19,11 +19,11 @@ class GPIOProtocolCode: GET_GPIO_INPUT = 0xAD -def to_string(data: bytes) -> str: +def to_string(data: bytes): return ' '.join(map(lambda x: f'{x:02x}', data)) -def get_local_host(name: str) -> T.Optional[str]: +def get_local_host(name: str): host = None dgram_socket = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) try: @@ -40,7 +40,7 @@ def get_local_host(name: str) -> T.Optional[str]: class SocketTransport(object): - def __init__(self, host: str = "0.0.0.0", port: int = 30002): + def __init__(self, host="0.0.0.0", port=30002): self.port = port self.host = host self.running = True @@ -56,7 +56,7 @@ def accept(self): while self.running is True: yield self.socket.accept() - def context(self, conn: socket.socket, buffer_size: int = 1024): + def context(self, conn, buffer_size=1024): while self.running is True: try: data_buffer = conn.recv(buffer_size) @@ -75,7 +75,7 @@ def close(self): class SerialTransport(object): - def __init__(self, comport: str = "/dev/ttyS1", baudrate: int = 100_0000, timeout: float = None): + def __init__(self, comport="/dev/ttyS1", baudrate=100_0000, timeout=None): self.serial = serial.Serial(port=comport, baudrate=baudrate, timeout=timeout) self.log = logging.getLogger("serial") self.baudrate = baudrate @@ -83,10 +83,10 @@ def __init__(self, comport: str = "/dev/ttyS1", baudrate: int = 100_0000, timeou self.open() self.log.info(f"start serial on [{self.comport}] with baudrate [{self.baudrate}]") - def send(self, data: bytes): + def send(self, data): self.serial.write(data) - def recv(self, size: int = 1024) -> bytes: + def recv(self, size=1024): return self.serial.read(size) @property @@ -111,7 +111,7 @@ class Server280X5PI(object): 4. Instruction parsing is done entirely by the client 5. The server is responsible for setting the GPIO mode """ - def __init__(self, socket_transport: SocketTransport, serial_transport: SerialTransport, debug=True): + def __init__(self, socket_transport, serial_transport, debug=True): self.debug = debug self.socket_transport = socket_transport self.serial_transport = serial_transport @@ -181,7 +181,7 @@ def mainloop(self): self.log.info("server closed") -def main(debug: bool = False): +def main(debug=False): logging.basicConfig( level=logging.DEBUG if debug else logging.INFO, format="%(asctime)s - [%(name)s] %(levelname)7s - %(message)s", From 1bd4e1fefd219be37cfe965c8228e76f81ae22ab Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Mon, 17 Feb 2025 17:51:39 +0800 Subject: [PATCH 06/57] rename MyCobot280x5pi to MyCobot280RDKX5 --- ...{Server_280_X5PI.py => Server_280_RDKX5.py} | 9 ++++----- ..._280_X5PI_en.md => MyCobot_280_RDKX5_en.md} | 6 +++--- ..._280_X5PI_zh.md => MyCobot_280_RDKX5_zh.md} | 4 ++-- pymycobot/__init__.py | 6 +++--- .../{mycobot280x5pi.py => mycobot280rdkx5.py} | 18 +++++++++--------- 5 files changed, 21 insertions(+), 22 deletions(-) rename demo/{Server_280_X5PI.py => Server_280_RDKX5.py} (98%) rename docs/{MyCobot_280_X5PI_en.md => MyCobot_280_RDKX5_en.md} (99%) rename docs/{MyCobot_280_X5PI_zh.md => MyCobot_280_RDKX5_zh.md} (99%) rename pymycobot/{mycobot280x5pi.py => mycobot280rdkx5.py} (98%) diff --git a/demo/Server_280_X5PI.py b/demo/Server_280_RDKX5.py similarity index 98% rename from demo/Server_280_X5PI.py rename to demo/Server_280_RDKX5.py index 7f38b2d9..b6e9ff41 100644 --- a/demo/Server_280_X5PI.py +++ b/demo/Server_280_RDKX5.py @@ -3,7 +3,6 @@ import fcntl import logging import traceback -import typing as T import socket import struct import serial @@ -101,11 +100,11 @@ def open(self): self.serial.open() -class Server280X5PI(object): +class MyCobot280RDKX5Server(object): """ - Server for 280 X5 Pi + Server for 280 RDK-X5 - 1. System GPIO operating protocol adheres to protocol MyCobot 280 x5 PI. + 1. System GPIO operating protocol adheres to protocol MyCobot 280 RDK X5. 2. This server only does the work of forwarding protocol and does not participate in the analysis of instructions. 3. The server is only responsible for forwarding the data received from the socket to the serial port and vice versa. 4. Instruction parsing is done entirely by the client @@ -195,7 +194,7 @@ def main(debug=False): serial_transport = SerialTransport(comport="/dev/ttyS1", baudrate=100_0000, timeout=0.1) - Server280X5PI(socket_transport, serial_transport).mainloop() + MyCobot280RDKX5Server(socket_transport, serial_transport).mainloop() GPIO.cleanup() diff --git a/docs/MyCobot_280_X5PI_en.md b/docs/MyCobot_280_RDKX5_en.md similarity index 99% rename from docs/MyCobot_280_X5PI_en.md rename to docs/MyCobot_280_RDKX5_en.md index cf8bf1df..94d4e777 100644 --- a/docs/MyCobot_280_X5PI_en.md +++ b/docs/MyCobot_280_RDKX5_en.md @@ -8,9 +8,9 @@ API (Application Programming Interface), also known as Application Programming I ```python # Example -from pymycobot import MyCobot280X5PI +from pymycobot import MyCobot280RDKX5 -mc = MyCobot280X5PI('/dev/ttyS1') +mc = MyCobot280RDKX5('/dev/ttyS1') # Gets the current angle of all joints angles = mc.get_angles() @@ -464,7 +464,7 @@ mc.send_angle(1, 40, 20) #### `get_servo_temps()` - **function:** Get joint temperature - **Return value:** - - **A list unit ** + - **A list unit ��** ### 13. Drag Track Interface diff --git a/docs/MyCobot_280_X5PI_zh.md b/docs/MyCobot_280_RDKX5_zh.md similarity index 99% rename from docs/MyCobot_280_X5PI_zh.md rename to docs/MyCobot_280_RDKX5_zh.md index 6578ce47..85822b93 100644 --- a/docs/MyCobot_280_X5PI_zh.md +++ b/docs/MyCobot_280_RDKX5_zh.md @@ -8,9 +8,9 @@ API ```python # ʾ -from pymycobot import MyCobot280X5PI +from pymycobot import MyCobot280RDKX5 -mc = MyCobot280X5PI('/dev/ttyS1') +mc = MyCobot280RDKX5('/dev/ttyS1') # ȡйؽڵǰǶ angles = mc.get_angles() diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index e3e13144..1c1718fa 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -4,7 +4,7 @@ import datetime import sys from pymycobot.mycobot280 import MyCobot280 -from pymycobot.mycobot280x5pi import MyCobot280X5PI, MyCobot280X5PISocket +from pymycobot.mycobot280rdkx5 import MyCobot280RDKX5, MyCobot280RDKX5Socket from pymycobot.mypalletizer260 import MyPalletizer260 from pymycobot.mecharm270 import MechArm270 from pymycobot.mycobot280socket import MyCobot280Socket @@ -79,8 +79,8 @@ "MyArmMControl", "ChassisControl", "ConveyorAPI", - "MyCobot280X5PI", - "MyCobot280X5PISocket" + "MyCobot280RDKX5", + "MyCobot280RDKX5Socket" ] if sys.platform == "linux": diff --git a/pymycobot/mycobot280x5pi.py b/pymycobot/mycobot280rdkx5.py similarity index 98% rename from pymycobot/mycobot280x5pi.py rename to pymycobot/mycobot280rdkx5.py index d3200788..e73b34da 100644 --- a/pymycobot/mycobot280x5pi.py +++ b/pymycobot/mycobot280rdkx5.py @@ -35,10 +35,10 @@ class GPIOProtocolCode: GET_GPIO_INPUT = 0xAD -class MyCobot280X5Api(CommandGenerator): +class MyCobot280RDKX5Api(CommandGenerator): def __init__(self, debug=False, thread_lock=True): - super(MyCobot280X5Api, self).__init__(debug) + super(MyCobot280RDKX5Api, self).__init__(debug) self.calibration_parameters = functools.partial(calibration_parameters, class_name="MyCobot280") self.thread_lock = thread_lock self.lock = threading.Lock() @@ -55,7 +55,7 @@ def _mesg(self, genre, *args, **kwargs): **kwargs: support `has_reply` has_reply: Whether there is a return value to accept. """ - real_command, has_reply, _ = super(MyCobot280X5Api, self)._mesg(genre, *args, **kwargs) + real_command, has_reply, _ = super(MyCobot280RDKX5Api, self)._mesg(genre, *args, **kwargs) if self.thread_lock: with self.lock: return self._res(real_command, has_reply, genre) @@ -173,7 +173,7 @@ def wait(self, t): return self -class MyCobot280X5PICommandGenerator(MyCobot280X5Api): +class MyCobot280RDKX5CommandGenerator(MyCobot280RDKX5Api): # System Status def get_modify_version(self): @@ -799,7 +799,7 @@ def drag_clear_record_data(self): return self._mesg(ProtocolCode.DRAG_CLEAR_RECORD_DATA, has_reply=True) -class MyCobot280X5PI(MyCobot280X5PICommandGenerator): +class MyCobot280RDKX5(MyCobot280RDKX5CommandGenerator): def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_lock=True): """ @@ -821,10 +821,10 @@ def open(self): self._serial_port.open() -class MyCobot280X5PISocket(MyCobot280X5PICommandGenerator): - """MyCobot 280 X5 PI Socket Control Class +class MyCobot280RDKX5Socket(MyCobot280RDKX5CommandGenerator): + """MyCobot 280 RDK X5 Socket Control Class - server file: https://github.com/elephantrobotics/pymycobot/demo/Server_280_X5PI.py + server file: https://github.com/elephantrobotics/pymycobot/demo/Server_280_RDK_X5.py """ def __init__(self, ip, port=30002, timeout=0.1, debug=False, thread_lock=True): super().__init__(debug, thread_lock) @@ -885,7 +885,7 @@ def close(self): def main(): - mc_sock = MyCobot280X5PISocket('192.168.1.246', port=30002, debug=True) + mc_sock = MyCobot280RDKX5Socket('192.168.1.246', port=30002, debug=True) # print(mc_sock.send_angle(1, 100, 50)) # print(mc_sock.get_quick_move_message()) print(mc_sock.set_gpio_mode(0)) From 2dfef78cfc6147389596a14fb671a8324d861f9d Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Mon, 17 Feb 2025 18:08:05 +0800 Subject: [PATCH 07/57] fix MyArmMControl bugs --- pymycobot/error.py | 27 ++-- pymycobot/myarmm_control.py | 287 ++++++++++++++++++------------------ pymycobot/robot_info.py | 4 +- 3 files changed, 166 insertions(+), 152 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index 605c1240..d02dcba3 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1277,6 +1277,9 @@ def calibration_parameters(**kwargs): if value < min_angle or value > max_angle: raise ValueError(f"angle value not right, should be {min_angle} ~ {max_angle}, but received {value}") elif parameter == 'angles': + if not value: + raise ValueError("angles value can't be empty") + for i, v in enumerate(value): min_angle = limit_info["angles_min"][i] max_angle = limit_info["angles_max"][i] @@ -1285,14 +1288,14 @@ def calibration_parameters(**kwargs): f"angle value not right, should be {min_angle} ~ {max_angle}, but received {v}") elif parameter == 'coord': coord_index = kwargs['coord_id'] - 1 - min_coord = limit_info["coords_min"][coord_index] - max_coord = limit_info["coords_max"][coord_index] + min_coord = limit_info["coord_min"][coord_index] + max_coord = limit_info["coord_max"][coord_index] if not min_coord <= value <= max_coord: raise ValueError(f"coord value not right, should be {min_coord} ~ {max_coord}, but received {value}") elif parameter == 'coords': for i, v in enumerate(value): - min_coord = limit_info["coords_min"][i] - max_coord = limit_info["coords_max"][i] + min_coord = limit_info["coord_min"][i] + max_coord = limit_info["coord_max"][i] if not min_coord <= v <= max_coord: raise ValueError(f"coord value not right, should be {min_coord} ~ {max_coord}, but received {v}") elif parameter == 'encoder': @@ -1319,13 +1322,16 @@ def calibration_parameters(**kwargs): if not 1 <= s <= 100: raise ValueError(f"speed value not right, should be 1 ~ 100, the received speed is {value}") elif parameter == "servo_addr": + if not isinstance(value, int): + raise TypeError(f"The {parameter} must be an integer.") + if value in (0, 1, 2, 3, 4): if class_name == "MyArmMControl": raise ValueError("modification is not allowed between 0~4, current data id: {}".format(value)) raise ValueError("addr 0-4 cannot be modified") elif parameter == "account": - if not (8 <= len(value) <= 63): - raise ValueError("The length of password must be between 8 and 63.") + pass + elif parameter == "password": if not re.match(r'^[A-Za-z0-9]{8,63}$', value): raise ValueError("The password must be 8-63 characters long and contain only letters and numbers.") @@ -1342,13 +1348,16 @@ def calibration_parameters(**kwargs): raise ValueError(f"end_direction not right, should be 1 ~ 3, the received end_direction is {value}") elif parameter == "gripper_flag": if value not in (0, 1, 254): - raise ValueError(f"gripper_flag not right, should be 0 ~ 254, the received gripper_flag is {value}") + raise ValueError(f"gripper_flag not right, should be in (0, 1, 254), the received gripper_flag is {value}") elif parameter == "gripper_value": if not 0 <= value <= 100: raise ValueError(f"gripper_value not right, should be 0 ~ 100, the received gripper_value is {value}") elif parameter == "basic_pin_number": - if not 1 <= value <= 2: - raise ValueError("The basic pin number must be between 1 and 2.") + if not isinstance(value, int): + raise TypeError(f"The {parameter} must be an integer.") + + if not 1 <= value <= 6: + raise ValueError("The basic pin number must be between 1 ~ 6.") elif parameter == "rgb": for v in value: if not 0 <= v <= 255: diff --git a/pymycobot/myarmm_control.py b/pymycobot/myarmm_control.py index 2ba401de..0f402f23 100644 --- a/pymycobot/myarmm_control.py +++ b/pymycobot/myarmm_control.py @@ -1,5 +1,5 @@ # coding=utf-8 - +import functools import sys import logging import time @@ -35,56 +35,73 @@ def setup_logging(debug: bool = False): return logger +def setup_serial_port(port, baudrate, timeout=0.1): + serial_api = serial.Serial(port, baudrate, timeout=timeout) + serial_api.rts = False + if not serial_api.is_open: + serial_api.open() + return serial_api + + class MyArmMProcessor(DataProcessor): def __init__(self, port, baudrate, timeout=0.1, debug=False): - - self._serial_port = serial.Serial() - self._serial_port.port = port - self._serial_port.baudrate = baudrate - self._serial_port.timeout = timeout - self._serial_port.rts = False - self._serial_port.open() + super().__init__(debug) self.lock = threading.Lock() - self._version = sys.version_info[:2][0] - self.log = setup_logging(debug) - self.calibration_parameters = calibration_parameters - - def _write(self, command): - write(self, command, method=None) + self._serial_port = setup_serial_port(port, baudrate, timeout) + self.calibration_parameters = functools.partial(calibration_parameters, class_name=self.__class__.__name__) + self._write = functools.partial(write, self, method=None) + self._read = functools.partial(read, self, _class=self.__class__.__name__) - def _read(self, genre, command=None, _class=None, timeout=None): - return read(self, genre, command, timeout, _class) + # def _write(self, command): + # write(self, command, method=None) + # + # def _read(self, genre, command=None, _class=None, timeout=None): + # return read(self, genre, command, timeout, _class) + @classmethod + def __is_return(cls, genre, command): + """ + Check if the command is a return command. + """ + return len(command) == 6 and command[3] == genre + def _mesg(self, genre, *args, **kwargs): - real_command, has_reply = super(MyArmMProcessor, self)._mesg(genre, *args, **kwargs) + kwargs["has_reply"] = True + real_command, has_reply, _ = super(MyArmMProcessor, self)._mesg(genre, *args, **kwargs) real_command = self._flatten(real_command) self._write(real_command) - if genre == ProtocolCode.STOP: - has_reply = True - - if has_reply is False: - return None - with self.lock: return self._read_genre_result(genre) def _read_genre_result(self, genre): - data = self._read(genre, _class=self.__class__.__name__) + data = self._read(genre, timeout=None) if genre == ProtocolCode.SET_SSID_PWD: - return None - - res = self._process_received(data, genre) + if len(data) == 5 and data[3] == genre: + return 1 + + if genre == ProtocolCode.SET_BASIC_OUTPUT: + if self.__is_return(genre, data): + return data[-2] + + if genre == ProtocolCode.GET_ROBOT_STATUS: + res = [] + valid_data = data[4:-1] + for header_i in range(0, len(valid_data), 2): + one = valid_data[header_i: header_i + 2] + res.append(self._decode_int16(one)) + else: + res = self._process_received(data, genre) if not res: - return None + return -1 if genre in [ ProtocolCode.ROBOT_VERSION, ProtocolCode.GET_ROBOT_ID, ProtocolCode.IS_POWER_ON, ProtocolCode.IS_CONTROLLER_CONNECTED, - ProtocolCode.IS_PAUSED, # TODO have bug: return b'' + ProtocolCode.IS_PAUSED, ProtocolCode.IS_IN_POSITION, ProtocolCode.IS_MOVING, ProtocolCode.IS_SERVO_ENABLE, @@ -141,18 +158,9 @@ def _read_genre_result(self, genre): else: r.append(self._int2angle(res[index])) return r - elif genre == ProtocolCode.GET_ROBOT_STATUS: - for i in range(len(res)): - if res[i] == 0: - continue - data = bin(res[i])[2:] - res[i] = [] - while len(data) != 16: - data = "0" + data - for j in range(16): - if data[j] != "0": - res[i].append(15 - j) - return res + elif self.__is_return(genre, data): + print("11111111111111111111111") + return self._process_single(res) else: return res @@ -165,19 +173,19 @@ def __init__(self, port, baudrate=115200, timeout=0.1, debug=False): # System status def get_robot_modify_version(self): """Get the bot correction version number""" - return self._mesg(RobotProtocolCode.GET_ROBOT_MODIFY_VERSION, has_reply=True) + return self._mesg(RobotProtocolCode.GET_ROBOT_MODIFY_VERSION) def get_robot_system_version(self): """Obtaining the Robot Firmware Version (Major and Minor Versions)""" - return self._mesg(RobotProtocolCode.GET_ROBOT_SYSTEM_VERSION, has_reply=True) + return self._mesg(RobotProtocolCode.GET_ROBOT_SYSTEM_VERSION) def get_robot_tool_modify_version(self): """Get the remediation version of the bot tool""" - return self._mesg(ProtocolCode.GET_ROBOT_TOOL_MODIFY_VERSION, has_reply=True) + return self._mesg(ProtocolCode.GET_ROBOT_TOOL_MODIFY_VERSION) def get_robot_tool_system_version(self): """Get the Robot Tool Firmware Version (End Atom)""" - return self._mesg(RobotProtocolCode.GET_ROBOT_TOOL_SYSTEM_VERSION, has_reply=True) + return self._mesg(RobotProtocolCode.GET_ROBOT_TOOL_SYSTEM_VERSION) def power_on(self): """The robotic arm turns on the power""" @@ -195,7 +203,7 @@ def is_powered_on(self): 0 - power off -1 - error data """ - return self._mesg(RobotProtocolCode.IS_POWERED_ON, has_reply=True) + return self._mesg(RobotProtocolCode.IS_POWERED_ON) def release_all_servos(self, data=None): """The robot turns off the torque output @@ -216,16 +224,16 @@ def set_fresh_mode(self, mode): # TODO 22-5-19 need test 1 - Always execute the latest command first. 0 - Execute instructions sequentially in the form of a queue. """ - self.calibration_parameters(class_name=self.__class__.__name__, mode=mode) + self.calibration_parameters(mode=mode) return self._mesg(ProtocolCode.SET_FRESH_MODE, mode) def get_fresh_mode(self): """Query sports mode""" - return self._mesg(ProtocolCode.GET_FRESH_MODE, has_reply=True) + return self._mesg(ProtocolCode.GET_FRESH_MODE) def get_robot_status(self): """Get robot status""" - return self._mesg(ProtocolCode.GET_ROBOT_STATUS, has_reply=True) + return self._mesg(ProtocolCode.GET_ROBOT_STATUS) def get_angles(self): """ Get the angle of all joints. @@ -233,7 +241,7 @@ def get_angles(self): Return: list: A float list of all angle. """ - return self._mesg(ProtocolCode.GET_ANGLES, has_reply=True) + return self._mesg(ProtocolCode.GET_ANGLES) def write_angle(self, joint_id, degree, speed): """Send the angle of a joint to robot arm. @@ -243,7 +251,7 @@ def write_angle(self, joint_id, degree, speed): degree: (float) -150 ~ 150 speed : (int) 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, id=joint_id, angle=degree, speed=speed) + self.calibration_parameters(joint_id=joint_id, angle=degree, speed=speed) return self._mesg(ProtocolCode.SEND_ANGLE, joint_id, [self._angle2int(degree)], speed) def write_angles(self, angles, speed): @@ -253,7 +261,7 @@ def write_angles(self, angles, speed): angles: (list) A float list of all angle. speed : (int) 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, angles=angles, speed=speed) + self.calibration_parameters(angles=angles, speed=speed) angles = [self._angle2int(angle) for angle in angles] return self._mesg(ProtocolCode.SEND_ANGLES, angles, speed) @@ -263,7 +271,7 @@ def get_coords(self): Return: list: A float list of all coordinates. """ - return self._mesg(ProtocolCode.GET_COORDS, has_reply=True) + return self._mesg(ProtocolCode.GET_COORDS) def write_coord(self, coord_id, coord, speed): """Send the coordinates of a joint to robot arm. @@ -273,9 +281,9 @@ def write_coord(self, coord_id, coord, speed): coord: (float) -150 ~ 150 speed : (int) 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, coord_id=coord_id, coord=coord, speed=speed) + self.calibration_parameters(coord_id=coord_id, coord=coord, speed=speed) value = self._coord2int(coord) if coord_id <= 3 else self._angle2int(coord) - return self._mesg(ProtocolCode.SEND_COORD, id, [value], speed) + return self._mesg(ProtocolCode.SEND_COORD, coord_id, [value], speed) def write_coords(self, coords, speed, mode=None): """Send the coordinates of all joints to robot arm. @@ -285,7 +293,7 @@ def write_coords(self, coords, speed, mode=None): speed : (int) 1 ~ 100 mode: (int) 0 - normal, 1 - low, 2 - high """ - self.calibration_parameters(class_name=self.__class__.__name__, coords=coords, speed=speed) + self.calibration_parameters(coords=coords, speed=speed) coord_list = [] for idx in range(3): coord_list.append(self._coord2int(coords[idx])) @@ -309,20 +317,20 @@ def is_in_position(self, data, mode=0): 0 - False\n -1 - Error """ - if id == 1: - self.calibration_parameters(class_name=self.__class__.__name__, coords=data) + if mode == 1: + self.calibration_parameters(coords=data) data_list = [] for idx in range(3): data_list.append(self._coord2int(data[idx])) for idx in range(3, 6): data_list.append(self._angle2int(data[idx])) - elif id == 0: - self.calibration_parameters(class_name=self.__class__.__name__, angles=data) + elif mode == 0: + self.calibration_parameters(angles=data) data_list = [self._angle2int(i) for i in data] else: raise Exception("id is not right, please input 0 or 1") - return self._mesg(ProtocolCode.IS_IN_POSITION, data_list, mode, has_reply=True) + return self._mesg(ProtocolCode.IS_IN_POSITION, data_list, mode) def is_moving(self): """Detect if the robot is moving @@ -332,7 +340,7 @@ def is_moving(self): 1 - is moving -1 - error data """ - return self._mesg(ProtocolCode.IS_MOVING, has_reply=True) + return self._mesg(ProtocolCode.IS_MOVING) def jog_rpy(self, end_direction, direction, speed): """Rotate the end around a fixed axis in the base coordinate system @@ -342,8 +350,7 @@ def jog_rpy(self, end_direction, direction, speed): direction (int): 1 - forward rotation, 0 - reverse rotation speed (int): 1 ~ 100 """ - self.calibration_parameters( - class_name=self.__class__.__name__, direction=direction, speed=speed, end_direction=end_direction + self.calibration_parameters(direction=direction, speed=speed, end_direction=end_direction ) return self._mesg(ProtocolCode.JOG_ABSOLUTE, end_direction, direction, speed) @@ -357,9 +364,7 @@ def jog_angle(self, joint_id, direction, speed): direction: 0 - decrease, 1 - increase speed: int (0 - 100) """ - self.calibration_parameters( - class_name=self.__class__.__name__, joint_id=joint_id, direction=direction, speed=speed - ) + self.calibration_parameters(joint_id=joint_id, direction=direction, speed=speed) return self._mesg(ProtocolCode.JOG_ANGLE, joint_id, direction, speed) def jog_coord(self, coord_id, direction, speed): @@ -370,9 +375,7 @@ def jog_coord(self, coord_id, direction, speed): direction: 0 - decrease, 1 - increase speed: int (1 - 100) """ - self.calibration_parameters( - class_name=self.__class__.__name__, coord_id=coord_id, direction=direction, speed=speed - ) + self.calibration_parameters(coord_id=coord_id, direction=direction, speed=speed) return self._mesg(ProtocolCode.JOG_COORD, coord_id, direction, speed) def jog_increment(self, joint_id, increment, speed): @@ -380,11 +383,14 @@ def jog_increment(self, joint_id, increment, speed): Args: joint_id(int): - for myArm: Joint id 1 - 7. + for myArm: Joint id 1 - 6. increment(int): incremental speed(int): int (0 - 100) """ - self.calibration_parameters(class_name=self.__class__.__name__, id=joint_id, speed=speed) + if not (isinstance(increment, int) or isinstance(increment, float)): + raise ValueError("increment must be int or float") + + self.calibration_parameters(joint_id=joint_id, speed=speed) return self._mesg(ProtocolCode.JOG_INCREMENT, joint_id, [self._angle2int(increment)], speed) def pause(self): @@ -399,7 +405,7 @@ def is_paused(self): 0 - not paused -1 - error """ - return self._mesg(ProtocolCode.IS_PAUSED, has_reply=True) + return self._mesg(ProtocolCode.IS_PAUSED) def resume(self): """Recovery movement""" @@ -416,8 +422,8 @@ def get_encoder(self, joint_id): joint_id: (int) for myArm: Joint id 1 - 7. """ - self.calibration_parameters(class_name=self.__class__.__name__, encode_id=joint_id) - return self._mesg(ProtocolCode.GET_ENCODER, joint_id, has_reply=True) + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.GET_ENCODER, joint_id) def get_encoders(self): """Get the six joints of the manipulator @@ -425,7 +431,7 @@ def get_encoders(self): Returns: The list of encoders """ - return self._mesg(ProtocolCode.GET_ENCODERS, has_reply=True) + return self._mesg(ProtocolCode.GET_ENCODERS) # Running status and Settings def get_speed(self): @@ -434,7 +440,7 @@ def get_speed(self): Returns: int """ - return self._mesg(ProtocolCode.GET_SPEED, has_reply=True) + return self._mesg(ProtocolCode.GET_SPEED) def set_speed(self, speed): """Set speed value @@ -442,7 +448,7 @@ def set_speed(self, speed): Args: speed (int): 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, speed=speed) + self.calibration_parameters(speed=speed) return self._mesg(ProtocolCode.SET_SPEED, speed) def get_joint_min(self, joint_id): @@ -455,8 +461,8 @@ def get_joint_min(self, joint_id): Returns: angle value(float) """ - self.calibration_parameters(class_name=self.__class__.__name__, joint_id=joint_id) - return self._mesg(ProtocolCode.GET_JOINT_MIN_ANGLE, joint_id, has_reply=True) + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.GET_JOINT_MIN_ANGLE, joint_id) def get_joint_max(self, joint_id): """Gets the maximum movement angle of the specified joint @@ -468,8 +474,8 @@ def get_joint_max(self, joint_id): Return: angle value(float) """ - self.calibration_parameters(class_name=self.__class__.__name__, joint_id=joint_id) - return self._mesg(ProtocolCode.GET_JOINT_MAX_ANGLE, joint_id, has_reply=True) + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.GET_JOINT_MAX_ANGLE, joint_id) def set_joint_max(self, joint_id, angle): """Set the joint maximum angle @@ -479,8 +485,8 @@ def set_joint_max(self, joint_id, angle): for myArm: Joint id 1 - 7. angle: 0 ~ 180 """ - self.calibration_parameters(class_name=self.__class__.__name__, joint_id=joint_id, angle=angle) - return self._mesg(ProtocolCode.SET_JOINT_MAX, id, angle) + self.calibration_parameters(joint_id=joint_id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MAX, joint_id, angle) def set_joint_min(self, joint_id, angle): """Set the joint minimum angle @@ -490,8 +496,8 @@ def set_joint_min(self, joint_id, angle): for myArm: Joint id 1 - 7. angle: 0 ~ 180 """ - self.calibration_parameters(class_name=self.__class__.__name__, joint_id=joint_id, angle=angle) - return self._mesg(ProtocolCode.SET_JOINT_MIN, id, angle) + self.calibration_parameters(joint_id=joint_id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MIN, joint_id, angle) # Servo control def is_servo_enable(self, servo_id): @@ -506,8 +512,8 @@ def is_servo_enable(self, servo_id): 1 - enable -1 - error """ - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) - return self._mesg(ProtocolCode.IS_SERVO_ENABLE, servo_id, has_reply=True) + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.IS_SERVO_ENABLE, servo_id) def is_all_servo_enable(self): """Detect the connection status of all joints @@ -517,7 +523,7 @@ def is_all_servo_enable(self): 1 - enable -1 - error """ - return self._mesg(ProtocolCode.IS_ALL_SERVO_ENABLE, has_reply=True) + return self._mesg(ProtocolCode.IS_ALL_SERVO_ENABLE) def set_servo_data(self, servo_id, data_id, value, mode=None): """Set the data parameters of the specified address of the steering gear @@ -529,16 +535,14 @@ def set_servo_data(self, servo_id, data_id, value, mode=None): value: 0 - 4096 mode: 0 - indicates that value is one byte(default), 1 - 1 represents a value of two bytes. """ + if not isinstance(value, int): + raise TypeError("value must be int") if mode is None: - self.calibration_parameters( - class_name=self.__class__.__name__, servo_id=servo_id, servo_addr=data_id, value=value - ) + self.calibration_parameters(servo_id=servo_id, servo_addr=data_id, value=value) return self._mesg(ProtocolCode.SET_SERVO_DATA, servo_id, data_id, value) else: - self.calibration_parameters( - class_name=self.__class__.__name__, servo_id=servo_id, servo_addr=data_id, value=value, mode=mode - ) + self.calibration_parameters(servo_id=servo_id, servo_addr=data_id, value=value, mode=mode) return self._mesg(ProtocolCode.SET_SERVO_DATA, servo_id, data_id, [value], mode) def get_servo_data(self, servo_id, data_id, mode=None): @@ -553,13 +557,11 @@ def get_servo_data(self, servo_id, data_id, mode=None): values 0 - 4096 """ if mode is not None: - self.calibration_parameters( - class_name=self.__class__.__name__, servo_id=servo_id, address=data_id, mode=mode - ) - return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id, mode, has_reply=True) + self.calibration_parameters(servo_id=servo_id, servo_addr=data_id, mode=mode) + return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id, mode) - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id, address=data_id) - return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id, has_reply=True) + self.calibration_parameters(servo_id=servo_id, servo_addr=data_id) + return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id) def set_servo_calibration(self, servo_id): """The current position of the calibration joint actuator is the angle zero point, @@ -568,7 +570,7 @@ def set_servo_calibration(self, servo_id): Args: servo_id: 1 ~ 8 """ - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.SET_SERVO_CALIBRATION, servo_id) def release_servo(self, servo_id, mode=None): @@ -579,11 +581,11 @@ def release_servo(self, servo_id, mode=None): mode: Default damping, set to 1, cancel damping """ if mode is None: - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.RELEASE_SERVO, servo_id) else: - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id, mode=mode) + self.calibration_parameters(servo_id=servo_id, mode=mode) return self._mesg(ProtocolCode.RELEASE_SERVO, servo_id, mode) def focus_servo(self, servo_id): @@ -592,7 +594,7 @@ def focus_servo(self, servo_id): Args: servo_id: int 1 ~ 7 """ - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.FOCUS_SERVO, servo_id) def set_digital_output(self, pin_no, pin_signal): @@ -602,15 +604,15 @@ def set_digital_output(self, pin_no, pin_signal): pin_no (int): pin_signal (int): 0 / 1 """ - self.calibration_parameters(class_name=self.__class__.__name__, pin_number=pin_no, pin_signal=pin_signal) + self.calibration_parameters(pin_number=pin_no, pin_signal=pin_signal) return self._mesg(ProtocolCode.SET_DIGITAL_OUTPUT, pin_no, pin_signal) def get_digital_input(self, pin_no): """Get the terminal atom io status Returns: int 0/1 """ - self.calibration_parameters(class_name=self.__class__.__name__, pin_number=pin_no) - return self._mesg(ProtocolCode.GET_DIGITAL_INPUT, pin_no, has_reply=True) + self.calibration_parameters(pin_number=pin_no) + return self._mesg(ProtocolCode.GET_DIGITAL_INPUT, pin_no) def set_gripper_enabled(self): """Enable gripper""" @@ -622,7 +624,7 @@ def get_gripper_value(self): Return: gripper value (int) """ - return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, has_reply=True) + return self._mesg(ProtocolCode.GET_GRIPPER_VALUE) def set_gripper_state(self, flag, speed): """Set gripper switch state @@ -631,7 +633,7 @@ def set_gripper_state(self, flag, speed): flag (int): 0 - open, 1 - close, 254 - release speed (int): 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, gripper_flag=flag, speed=speed) + self.calibration_parameters(gripper_flag=flag, speed=speed) return self._mesg(ProtocolCode.SET_GRIPPER_STATE, flag, speed) def set_gripper_value(self, gripper_value, speed): @@ -642,7 +644,7 @@ def set_gripper_value(self, gripper_value, speed): speed (int): 1 ~ 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, gripper_value=gripper_value, speed=speed) + self.calibration_parameters(gripper_value=gripper_value, speed=speed) return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, gripper_value, speed) def set_gripper_calibration(self): @@ -657,7 +659,7 @@ def is_gripper_moving(self): 1 - is moving -1- error data """ - return self._mesg(ProtocolCode.IS_GRIPPER_MOVING, has_reply=True) + return self._mesg(ProtocolCode.IS_GRIPPER_MOVING) # Atom IO def set_led_color(self, r=0, g=0, b=0): @@ -669,7 +671,7 @@ def set_led_color(self, r=0, g=0, b=0): b (int): 0 ~ 255 """ - self.calibration_parameters(class_name=self.__class__.__name__, rgb=(r, g, b)) + self.calibration_parameters(rgb=(r, g, b)) return self._mesg(ProtocolCode.SET_COLOR, r, g, b) def is_tool_btn_clicked(self): @@ -680,7 +682,7 @@ def is_tool_btn_clicked(self): 1 - is clicked -1- error data """ - return self._mesg(ProtocolCode.IS_TOOL_BTN_CLICKED, has_reply=True) + return self._mesg(ProtocolCode.IS_TOOL_BTN_CLICKED) # Basic def set_basic_output(self, pin_no, pin_signal): @@ -690,7 +692,7 @@ def set_basic_output(self, pin_no, pin_signal): pin_no: pin port number. pin_signal: 0 / 1 """ - self.calibration_parameters(class_name=self.__class__.__name__, pin_signal=pin_signal, basic_pin_number=pin_no) + self.calibration_parameters(pin_signal=pin_signal, basic_pin_number=pin_no) return self._mesg(ProtocolCode.SET_BASIC_OUTPUT, pin_no, pin_signal) def get_basic_input(self, pin_no): @@ -699,8 +701,8 @@ def get_basic_input(self, pin_no): Args: pin_no: (int) pin port number. """ - self.calibration_parameters(class_name=self.__class__.__name__, basic_pin_number=pin_no) - return self._mesg(ProtocolCode.GET_BASIC_INPUT, pin_no, has_reply=True) + self.calibration_parameters(basic_pin_number=pin_no) + return self._mesg(ProtocolCode.GET_BASIC_INPUT, pin_no) def set_ssid_pwd(self, account: str, password: str): """Change connected wi-fi. @@ -711,8 +713,8 @@ def set_ssid_pwd(self, account: str, password: str): """ self._mesg(ProtocolCode.SET_SSID_PWD) time.sleep(0.02) - self.calibration_parameters(class_name=self.__class__.__name__, account=account, password=password) - return self._mesg(ProtocolCode.SET_SSID_PWD, account, password, has_reply=True) + self.calibration_parameters(account=account, password=password) + return self._mesg(ProtocolCode.SET_SSID_PWD, account, password) def get_ssid_pwd(self): """Get connected wi-fi account and password. @@ -720,7 +722,7 @@ def get_ssid_pwd(self): Return: (account, password) """ - return self._mesg(ProtocolCode.GET_SSID_PWD, has_reply=True) + return self._mesg(ProtocolCode.GET_SSID_PWD) def set_server_port(self, port): """Change the connection port of the server. @@ -728,6 +730,8 @@ def set_server_port(self, port): Args: port: (int) The new connection port of the server. """ + if not isinstance(port, int): + raise TypeError("server port must be int") return self._mesg(ProtocolCode.SET_SERVER_PORT, port) def get_tof_distance(self): @@ -736,7 +740,7 @@ def get_tof_distance(self): Return: (int) The unit is mm. """ - return self._mesg(ProtocolCode.GET_TOF_DISTANCE, has_reply=True) + return self._mesg(ProtocolCode.GET_TOF_DISTANCE) def set_tool_reference(self, coords): """Set tool coordinate system @@ -744,7 +748,7 @@ def set_tool_reference(self, coords): Args: coords: a list of coords value(List[float]), [x(mm), y, z, rx(angle), ry, rz] """ - self.calibration_parameters(class_name=self.__class__.__name__, coords=coords) + self.calibration_parameters(coords=coords) coord_list = [] for idx in range(3): coord_list.append(self._coord2int(coords[idx])) @@ -754,7 +758,7 @@ def set_tool_reference(self, coords): def get_tool_reference(self): """Get tool coordinate system """ - return self._mesg(ProtocolCode.GET_TOOL_REFERENCE, has_reply=True) + return self._mesg(ProtocolCode.GET_TOOL_REFERENCE) def set_world_reference(self, coords): """Set the world coordinate system @@ -762,7 +766,7 @@ def set_world_reference(self, coords): Args: coords: a list of coords value(List[float]), [x(mm), y, z, rx(angle), ry, rz]\n """ - self.calibration_parameters(class_name=self.__class__.__name__, coords=coords) + self.calibration_parameters(coords=coords) coord_list = [] for idx in range(3): coord_list.append(self._coord2int(coords[idx])) @@ -772,7 +776,7 @@ def set_world_reference(self, coords): def get_world_reference(self): """Get the world coordinate system""" - return self._mesg(ProtocolCode.GET_WORLD_REFERENCE, has_reply=True) + return self._mesg(ProtocolCode.GET_WORLD_REFERENCE) def set_reference_frame(self, rftype): """Set the base coordinate system @@ -780,7 +784,7 @@ def set_reference_frame(self, rftype): Args: rftype: 0 - base 1 - tool. """ - self.calibration_parameters(class_name=self.__class__.__name__, rftype=rftype) + self.calibration_parameters(rftype=rftype) return self._mesg(ProtocolCode.SET_REFERENCE_FRAME, rftype) def get_reference_frame(self): @@ -789,7 +793,7 @@ def get_reference_frame(self): Returns: 0 - base 1 - tool. """ - return self._mesg(ProtocolCode.GET_REFERENCE_FRAME, has_reply=True) + return self._mesg(ProtocolCode.GET_REFERENCE_FRAME) def set_movement_type(self, move_type): """Set movement type @@ -797,7 +801,7 @@ def set_movement_type(self, move_type): Args: move_type: 1 - movel, 0 - moveJ """ - self.calibration_parameters(class_name=self.__class__.__name__, move_type=move_type) + self.calibration_parameters(move_type=move_type) return self._mesg(ProtocolCode.SET_MOVEMENT_TYPE, move_type) def get_movement_type(self): @@ -806,7 +810,7 @@ def get_movement_type(self): Returns: 1 - movel, 0 - moveJ """ - return self._mesg(ProtocolCode.GET_MOVEMENT_TYPE, has_reply=True) + return self._mesg(ProtocolCode.GET_MOVEMENT_TYPE) def set_end_type(self, mode): """Set end coordinate system @@ -814,7 +818,7 @@ def set_end_type(self, mode): Args: mode: int, 0 - flange, 1 - tool """ - self.calibration_parameters(class_name=self.__class__.__name__, mode=mode) + self.calibration_parameters(mode=mode) return self._mesg(ProtocolCode.SET_END_TYPE, mode) def get_end_type(self): @@ -823,7 +827,7 @@ def get_end_type(self): Returns: 0 - flange, 1 - tool """ - return self._mesg(ProtocolCode.GET_END_TYPE, has_reply=True) + return self._mesg(ProtocolCode.GET_END_TYPE) def get_plan_speed(self): """Get planning speed @@ -831,7 +835,7 @@ def get_plan_speed(self): Returns: [movel planning speed, movej planning speed]. """ - return self._mesg(ProtocolCode.GET_PLAN_SPEED, has_reply=True) + return self._mesg(ProtocolCode.GET_PLAN_SPEED) def get_plan_acceleration(self): """Get planning acceleration @@ -839,7 +843,7 @@ def get_plan_acceleration(self): Returns: [movel planning acceleration, movej planning acceleration]. """ - return self._mesg(ProtocolCode.GET_PLAN_ACCELERATION, has_reply=True) + return self._mesg(ProtocolCode.GET_PLAN_ACCELERATION) def set_plan_speed(self, speed, is_linear): """Set planning speed @@ -848,7 +852,7 @@ def set_plan_speed(self, speed, is_linear): speed (int): (1 ~ 100). is_linear: 0 -> joint 1 -> straight line """ - self.calibration_parameters(class_name=self.__class__.__name__, speed=speed, is_linear=is_linear) + self.calibration_parameters(speed=speed, is_linear=is_linear) return self._mesg(ProtocolCode.SET_PLAN_SPEED, speed, is_linear) def set_plan_acceleration(self, acceleration, is_linear): @@ -858,7 +862,7 @@ def set_plan_acceleration(self, acceleration, is_linear): acceleration (int): (1 ~ 100). is_linear(int): 0 -> joint 1 -> straight line """ - self.calibration_parameters(class_name=self.__class__.__name__, speed=acceleration, is_linear=is_linear) + self.calibration_parameters(speed=acceleration, is_linear=is_linear) return self._mesg(ProtocolCode.SET_PLAN_ACCELERATION, acceleration, is_linear) def get_servo_speeds(self): @@ -866,14 +870,14 @@ def get_servo_speeds(self): Returns: speeds: list[float * 8] +- 3000 step/s """ - return self._mesg(ProtocolCode.GET_SERVO_SPEED, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_SPEED) def get_servo_currents(self): """Get the joint current Returns: currents: list[float * 8] 0 ~ 3250 """ - return self._mesg(ProtocolCode.GET_SERVO_CURRENTS, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_CURRENTS) def get_servo_voltages(self): """Get the joint voltages @@ -881,7 +885,7 @@ def get_servo_voltages(self): Returns: voltages: list[float] voltage 0 ~ 240 """ - return self._mesg(ProtocolCode.GET_SERVO_VOLTAGES, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_VOLTAGES) def get_servo_status(self): """ @@ -891,7 +895,7 @@ def get_servo_status(self): 0 - normal, other - error """ - return self._mesg(ProtocolCode.GET_SERVO_STATUS, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_STATUS) def get_servo_temps(self): """ @@ -899,7 +903,7 @@ def get_servo_temps(self): Returns: temperatures: list[float] 0 ~ 255 """ - return self._mesg(ProtocolCode.GET_SERVO_TEMPS, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_TEMPS) def set_void_compensate(self, mode): """Set the virtual position compensation mode ( @@ -909,5 +913,6 @@ def set_void_compensate(self, mode): Args: mode (int): 0 - close, 1 - open """ - self.calibration_parameters(class_name=self.__class__.__name__, mode=mode) + self.calibration_parameters(mode=mode) return self._mesg(ProtocolCode.SET_VOID_COMPENSATE, mode) + diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index c6ead56e..c16e0849 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -319,11 +319,11 @@ class RobotLimit: "encoders_max": [4004, 2945, 3079, 3026, 3724, 2994, 3704, 2048] }, "MyArmMControl": { - "joint_id": [1, 2, 3, 4, 5, 6, 7], + "joint_id": [1, 2, 3, 4, 5, 6], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], "coord_id": [1, 2, 3, 4, 5, 6], "coord_min": [-833.325, -833.325, -351.11, -180, -180, -180], - "coord_max": [-833.325, -833.325, 1007.225, -180, -180, -180], + "coord_max": [833.325, 833.325, 1007.225, 180, 180, 180], "angles_min": [-170, -83, -90, -155, -91, -153, -118], "angles_max": [170, 83, 84, 153, 88, 153, 2], "encoders_min": [137, 1163, 1035, 1013, 248, 979, 220, 706], From b743d96922d4aaf1fbc0911e17275f58da224537 Mon Sep 17 00:00:00 2001 From: Mrkun5018 <2220138602@qq.com> Date: Tue, 18 Feb 2025 15:05:55 +0800 Subject: [PATCH 08/57] fix MyArmC bugs --- pymycobot/error.py | 8 +- pymycobot/myarm_api.py | 189 ++++++++++++++++++++++++++++------------ pymycobot/myarmc.py | 9 +- pymycobot/robot_info.py | 6 ++ 4 files changed, 152 insertions(+), 60 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index d02dcba3..66925e8c 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1336,8 +1336,12 @@ def calibration_parameters(**kwargs): if not re.match(r'^[A-Za-z0-9]{8,63}$', value): raise ValueError("The password must be 8-63 characters long and contain only letters and numbers.") elif parameter == "pin_number": - if not 1 <= value <= 6: - raise ValueError("The pin number must be between 1 and 6.") + pin = 6 + if class_name == "MyArmC": + pin = 2 + if not 1 <= value <= pin: + raise ValueError(f"The pin number must be between 1 and {pin}.") + elif parameter in ("direction", "mode", "pin_signal", "is_linear", "move_type", "rftype"): if not isinstance(value, int): raise TypeError(f"The {parameter} must be an integer.") diff --git a/pymycobot/myarm_api.py b/pymycobot/myarm_api.py index 1394bf94..38da7e62 100644 --- a/pymycobot/myarm_api.py +++ b/pymycobot/myarm_api.py @@ -1,24 +1,24 @@ # coding=utf-8 from __future__ import division - -import sys -import logging +import functools import threading import time - -from pymycobot.common import ProtocolCode, write, read, DataProcessor +from pymycobot.common import ProtocolCode, DataProcessor from pymycobot.error import calibration_parameters -from pymycobot.log import setup_logging import serial -class MyArmAPI(DataProcessor): - """ +def setup_serial_connect(port, baudrate, timeout=None): + serial_api = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) + serial_api.rts = False + if not serial_api.is_open: + serial_api.open() + return serial_api - """ - def __init__(self, port, baudrate="115200", timeout=0.1, debug=False): +class MyArmMCProcessor(DataProcessor): + def __init__(self, port, baudrate=115200, timeout=0.1, debug=False): """ Args: port : port string @@ -26,22 +26,65 @@ def __init__(self, port, baudrate="115200", timeout=0.1, debug=False): timeout : default 0.1 debug : whether show debug info """ - super(MyArmAPI, self).__init__() - self.calibration_parameters = calibration_parameters - self._serial_port = serial.Serial() - self._serial_port.port = port - self._serial_port.baudrate = baudrate - self._serial_port.timeout = timeout - self._serial_port.rts = False - self._serial_port.open() + super(MyArmMCProcessor, self).__init__(debug=debug) + self.calibration_parameters = functools.partial(calibration_parameters, class_name=self.__class__.__name__) + self._serial_port = setup_serial_connect(port, baudrate, timeout) self.lock = threading.Lock() - self._version = sys.version_info[:2][0] - self.debug = debug - setup_logging(self.debug) - self.log = logging.getLogger(__name__) - _write = write - _read = read + @classmethod + def __check_command_integrity(cls, command): + """ + Check the integrity of the command. + Instruction format: header + header + length + genre + *data + footer + + :param command: the command to check + :return: True if the command is valid, False otherwise + """ + return len(command) >= 5 and command[-1] == ProtocolCode.FOOTER and command[2] == len(command) - 3 + + def _read_command_buffer(self, timeout=0.1): + commands = b"" + is_record = False + previous_frame = b"" + stime = time.perf_counter() + while time.perf_counter() - stime < timeout: + current_frame = self._serial_port.read(1) + + if current_frame == b"\xfe" and previous_frame == b"\xfe" and is_record is False: + is_record = True + commands = b"\xfe\xfe" + continue + + previous_frame = current_frame + if is_record is False: + continue + + commands += current_frame + if self.__check_command_integrity(commands): + break + return commands + + def _read(self, genre): + if genre == ProtocolCode.GET_ROBOT_STATUS: + timeout = 90 + elif genre == ProtocolCode.SET_SSID_PWD or genre == ProtocolCode.GET_SSID_PWD: + timeout = 0.05 + elif genre in [ProtocolCode.INIT_ELECTRIC_GRIPPER, ProtocolCode.SET_GRIPPER_MODE]: + timeout = 0.3 + elif genre in [ProtocolCode.SET_GRIPPER_CALIBRATION]: + timeout = 0.4 + else: + timeout = 0.1 + + command_buffer = self._read_command_buffer(timeout=timeout) + self.log.debug(f"_read : {' '.join(map(lambda x: f'{x:02x}', command_buffer))}") + return command_buffer + + def _write(self, command): + self.log.debug(f"_write: {' '.join(map(lambda x: f'{x:02x}', command))}") + if not self._serial_port.is_open: + self._serial_port.open() + self._serial_port.write(command) def _mesg(self, genre, *args, **kwargs): """ @@ -54,19 +97,16 @@ def _mesg(self, genre, *args, **kwargs): **kwargs: support `has_reply` has_reply: Whether there is a return value to accept. """ - time.sleep(0.01) - real_command, has_reply, _async = super(MyArmAPI, self)._mesg(genre, *args, **kwargs) - command = self._flatten(real_command) + real_command, has_reply, _async = super(MyArmMCProcessor, self)._mesg(genre, *args, **kwargs) with self.lock: - self._write(command) + time.sleep(0.1) + self._write(self._flatten(real_command)) if not has_reply: return None - timeout = kwargs.get('timeout', None) - data = self._read(genre, command=command, timeout=timeout, _class=self.__class__.__name__) + data = self._read(genre) res = self._process_received(data, genre, arm=8) - if not res: return None @@ -97,15 +137,20 @@ def _mesg(self, genre, *args, **kwargs): if genre in (ProtocolCode.COBOTX_GET_ANGLE,): result = self._int2angle(result) return result - if genre in (ProtocolCode.GET_ATOM_PRESS_STATUS, ): + if genre in (ProtocolCode.GET_ATOM_PRESS_STATUS,): if self.__class__.__name__ == 'MyArmM': return res[0] return res - elif genre in [ - ProtocolCode.GET_ANGLES, ProtocolCode.GET_JOINT_MAX_ANGLE, ProtocolCode.GET_JOINT_MIN_ANGLE, - ProtocolCode.GET_JOINTS_COORD - ]: + elif genre in [ProtocolCode.GET_ANGLES, ProtocolCode.GET_JOINT_MAX_ANGLE, ProtocolCode.GET_JOINT_MIN_ANGLE]: return [self._int2angle(angle) for angle in res] + elif genre == ProtocolCode.GET_JOINTS_COORD: + r = [] + for idx, val in enumerate(res): + if idx < 3: + r.append(self._int2coord(val)) + else: + r.append(self._int2angle(val)) + return r elif genre in [ProtocolCode.GET_SERVO_VOLTAGES]: return [self._int2coord(angle) for angle in res] elif genre == ProtocolCode.GET_ROBOT_ERROR_STATUS: @@ -124,6 +169,9 @@ def _mesg(self, genre, *args, **kwargs): else: return res + +class MyArmAPI(MyArmMCProcessor): + def get_robot_modified_version(self): """Get the bot correction version number @@ -154,6 +202,8 @@ def set_robot_err_check_state(self, status): Args: status (int): 1 open; o close """ + if status not in [0, 1]: + raise ValueError("status must be 0 or 1") self._mesg(ProtocolCode.SET_ROBOT_ERROR_CHECK_STATE, status) def get_robot_err_check_state(self): @@ -182,16 +232,21 @@ def get_recv_queue_len(self): """The current length of the read receive queue""" return self._mesg(ProtocolCode.GET_RECV_QUEUE_LENGTH, has_reply=True) + def clear_recv_queue(self): + """Clear the read receive queue""" + return self._mesg(ProtocolCode.CLEAR_RECV_QUEUE) + def get_joint_angle(self, joint_id): """ - Obtain the current angle of the specified joint, when the obtained angle is 200��, + Obtain the current angle of the specified joint, when the obtained angle is 200, it means that the joint has no communication Args: joint_id (int): 0 - 254 Returns: - + angle (int) """ + self.calibration_parameters(joint_id=joint_id) return self._mesg(ProtocolCode.COBOTX_GET_ANGLE, joint_id, has_reply=True) def get_joints_angle(self): @@ -209,7 +264,7 @@ def set_servo_calibrate(self, servo_id): Args: servo_id (int): 0 - 254 """ - + self.calibration_parameters(servo_id=servo_id) self._mesg(ProtocolCode.SET_SERVO_CALIBRATION, servo_id) def get_servo_encoder(self, servo_id): @@ -221,6 +276,7 @@ def get_servo_encoder(self, servo_id): Returns: encoder (int): 0-4095 """ + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_ENCODER, servo_id, has_reply=True) def get_servos_encoder_drag(self): @@ -277,7 +333,7 @@ def set_servo_p(self, servo_id, data): """ assert 0 <= data <= 254, "data must be between 0 and 254" - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) self._mesg(ProtocolCode.SET_SERVO_P, servo_id, data) def get_servo_p(self, servo_id): @@ -286,6 +342,7 @@ def get_servo_p(self, servo_id): Args: servo_id (int): 0-254 """ + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_SERVO_P, servo_id, has_reply=True) def set_servo_d(self, servo_id, data): @@ -296,7 +353,7 @@ def set_servo_d(self, servo_id, data): data (int): 0-254 """ assert 0 <= data <= 254, "data must be between 0 and 254" - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) self._mesg(ProtocolCode.MERCURY_DRAG_TECH_EXECUTE, servo_id, data) def get_servo_d(self, servo_id): @@ -305,7 +362,8 @@ def get_servo_d(self, servo_id): Args: servo_id (int): 0-254 """ - return self._mesg(ProtocolCode.GET_SERVO_D, servo_id, has_reply=True) + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.GET_SERVO_D, servo_id, has_reply=True, timeout=0.1) def set_servo_i(self, servo_id, data): """Set the proportional factor of the position ring I of the specified servo motor @@ -315,11 +373,12 @@ def set_servo_i(self, servo_id, data): data (int): 0 - 254 """ assert 0 <= data <= 254, "data must be between 0 and 254" - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) self._mesg(ProtocolCode.MERCURY_DRAG_TECH_PAUSE, servo_id, data) def get_servo_i(self, servo_id): """Reads the position loop I scale factor of the specified servo motor""" + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_ERROR_DETECT_MODE, servo_id, has_reply=True) def set_servo_cw(self, servo_id, data): @@ -330,7 +389,7 @@ def set_servo_cw(self, servo_id, data): data (int): 0 - 32 """ assert 0 <= data <= 32, "data must be between 0 and 32" - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) self._mesg(ProtocolCode.SET_SERVO_MOTOR_CLOCKWISE, servo_id, data) def get_servo_cw(self, servo_id): @@ -339,6 +398,7 @@ def get_servo_cw(self, servo_id): Args: servo_id (int): 0 - 254 """ + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_SERVO_MOTOR_CLOCKWISE, servo_id, has_reply=True) def set_servo_cww(self, servo_id, data): @@ -349,7 +409,7 @@ def set_servo_cww(self, servo_id, data): data (int): 0 - 32 """ assert 0 <= data <= 32, "data must be between 0 and 32" - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.SET_SERVO_MOTOR_COUNTER_CLOCKWISE, servo_id, data) def get_servo_cww(self, servo_id): @@ -358,6 +418,7 @@ def get_servo_cww(self, servo_id): Args: servo_id (int): 0 - 254 """ + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_SERVO_MOTOR_COUNTER_CLOCKWISE, servo_id, has_reply=True) def set_servo_system_data(self, servo_id, addr, data, mode): @@ -369,7 +430,13 @@ def set_servo_system_data(self, servo_id, addr, data, mode): data (int): 0 - 4096 mode (int): 1 - data 1byte. 2 - data 2byte """ - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id, servo_addr=addr) + if mode not in (1, 2): + raise ValueError('mode must be 1 or 2') + + if data not in range(0, 4097): + raise ValueError('data must be between 0 and 4096') + + self.calibration_parameters(servo_id=servo_id, servo_addr=addr) self._mesg(ProtocolCode.SET_SERVO_MOTOR_CONFIG, servo_id, addr, [data], mode) def get_servo_system_data(self, servo_id, addr, mode): @@ -380,28 +447,35 @@ def get_servo_system_data(self, servo_id, addr, mode): addr (int): mode (int): 1 - data 1byte. 2 - data 2byte """ + if mode not in (1, 2): + raise ValueError('mode must be 1 or 2') + self.calibration_parameters(servo_id=servo_id, servo_addr=addr) return self._mesg(ProtocolCode.GET_SERVO_MOTOR_CONFIG, servo_id, addr, mode, has_reply=True) - def set_master_out_io_state(self, io_number, status=1): + def set_master_out_io_state(self, pin_number, status=1): """Set the host I/O pin status Args: - io_number: 1 - 2 + pin_number: M750(1 -6), C650(1-2) status: 0/1; 0: low; 1: high. default: 1 """ - self._mesg(ProtocolCode.SET_MASTER_PIN_STATUS, io_number, status) + if status not in (0, 1): + raise ValueError('status must be 0 or 1') + self.calibration_parameters(pin_number=pin_number) + self._mesg(ProtocolCode.SET_MASTER_PIN_STATUS, pin_number, status) - def get_master_in_io_state(self, io_number): + def get_master_in_io_state(self, pin_number): """get the host I/O pin status Args: - io_number (int): 1 - 2 + pin_number (int): M750(1 -6), C650(1-2) Returns: 0 or 1. 1: high 0: low """ - return self._mesg(ProtocolCode.GET_MASTER_PIN_STATUS, io_number, has_reply=True) + self.calibration_parameters(pin_number=pin_number) + return self._mesg(ProtocolCode.GET_MASTER_PIN_STATUS, pin_number, has_reply=True) def set_tool_out_io_state(self, io_number, status=1): """Set the Atom pin status @@ -409,21 +483,24 @@ def set_tool_out_io_state(self, io_number, status=1): Args: io_number (int): 1 - 2 status: 0 or 1; 0: low; 1: high. default: 1 - """ + self.calibration_parameters(master_pin=io_number, status=status) self._mesg(ProtocolCode.SET_ATOM_PIN_STATUS, io_number, status) - def get_tool_in_io_state(self, io_number): + def get_tool_in_io_state(self, pin): """Get the Atom pin status Args: - io_number (int): pin number + pin (int): pin Returns: 0 or 1. 1: high 0: low """ - return self._mesg(ProtocolCode.GET_ATOM_PIN_STATUS, io_number, has_reply=True) + if pin not in (0, 1): + raise ValueError("pin must be 0 or 1") + + return self._mesg(ProtocolCode.GET_ATOM_PIN_STATUS, pin, has_reply=True) def set_tool_led_color(self, r, g, b): """Set the Atom LED color diff --git a/pymycobot/myarmc.py b/pymycobot/myarmc.py index 1c47f69e..f6d37e07 100644 --- a/pymycobot/myarmc.py +++ b/pymycobot/myarmc.py @@ -1,14 +1,13 @@ # coding=utf-8 from __future__ import division - from pymycobot.common import ProtocolCode from pymycobot.myarm_api import MyArmAPI class MyArmC(MyArmAPI): - def __init__(self, port, baudrate="1000000", timeout=0.1, debug=False): + def __init__(self, port, baudrate=1000000, timeout=0.1, debug=False): super(MyArmC, self).__init__(port, baudrate, timeout, debug) def is_tool_btn_clicked(self, mode=1): @@ -21,6 +20,12 @@ def is_tool_btn_clicked(self, mode=1): Returns: list[int]: 0/1, 1: press, 0: no press """ + if not isinstance(mode, int): + raise TypeError('mode must be int') + + if mode not in [1, 2, 3, 254]: + raise ValueError('mode must be 1, 2, 3 or 254') + return self._mesg(ProtocolCode.GET_ATOM_PRESS_STATUS, mode, has_reply=True) def get_joints_coord(self): diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index c16e0849..6b528cef 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -310,6 +310,12 @@ class RobotLimit: "coords_min": [-310, -310, -140, -180, -180, -180], "coords_max": [310, 310, 480, 180, 180, 180] }, + "MyArmC": { + "joint_id": [1, 2, 3, 4, 5, 6], + "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], + "angles_min": [-165, -80, -100, -160, -90, -180], + "angles_max": [165, 100, 80, 160, 90, 180] + }, "MyArmM": { "joint_id": [1, 2, 3, 4, 5, 6, 7], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], From 455b90571147ae6436b4d564286218350694313d Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 21 Mar 2025 17:07:11 +0800 Subject: [PATCH 09/57] fix myArmM&C demo bug --- demo/myArm_M&C_demo/myarm_c.py | 25 +++++++++++++++++-------- demo/myArm_M&C_demo/myarm_m.py | 15 ++++++++++----- 2 files changed, 27 insertions(+), 13 deletions(-) diff --git a/demo/myArm_M&C_demo/myarm_c.py b/demo/myArm_M&C_demo/myarm_c.py index 2d89f8b3..4ba68c60 100644 --- a/demo/myArm_M&C_demo/myarm_c.py +++ b/demo/myArm_M&C_demo/myarm_c.py @@ -1,10 +1,10 @@ # 读取myarm_c的角度并发送 import socket -from pymycobot import MyArmC, MyArmM +from pymycobot import MyArmC import serial.tools.list_ports -import time -def get_port(): # 获取所有串口号 + +def get_port(): # 获取所有串口号 port_list = serial.tools.list_ports.comports() i = 1 res = {} @@ -14,6 +14,7 @@ def get_port(): # 获取所有串口号 i += 1 return res + def main(): port_dict = get_port() port_c = input("input myArm C port: ") @@ -25,10 +26,18 @@ def main(): # 请求连接 client.connect((HOST, PORT)) while True: - angle = c.get_joints_angle() - if angle is not None: - data = '\n' + str(angle) - client.send(data.encode('utf-8')) + try: + angle = c.get_joints_angle() + if angle is not None: + data = '\n' + str(angle) + client.send(data.encode('utf-8')) + except KeyboardInterrupt: + break + + except ConnectionAbortedError: + print("socket closed.") + break + if __name__ == "__main__": - main() \ No newline at end of file + main() diff --git a/demo/myArm_M&C_demo/myarm_m.py b/demo/myArm_M&C_demo/myarm_m.py index 70adfe55..f57b54e5 100644 --- a/demo/myArm_M&C_demo/myarm_m.py +++ b/demo/myArm_M&C_demo/myarm_m.py @@ -5,7 +5,8 @@ import time import socket -def get_port(): # 获取所有串口号 + +def get_port(): # 获取所有串口号 port_list = serial.tools.list_ports.comports() i = 1 res = {} @@ -15,15 +16,19 @@ def get_port(): # 获取所有串口号 i += 1 return res + def processing_data(data): data = data.split('\n')[-1] angle = list(data[1:-1].split(',')) angle = [float(i) for i in angle] angle[2] *= -1 gripper_angle = angle.pop(-1) - angle.append((gripper_angle - 0.08) / (-95.27 - 0.08) * (-123.13 + 1.23) - 1.23) + gripper_angle = (gripper_angle - 0.08) / (-95.27 - 0.08) * (-123.13 + 1.23) - 1.23 + gripper_angle = max(min(gripper_angle, -118), 2) + angle.append(gripper_angle) return angle + def main(): HOST = '127.0.0.1' PORT = 8001 @@ -47,11 +52,11 @@ def main(): while True: try: data = conn.recv(1024).decode('utf-8') - angle = processing_data(data) - m.set_joints_angle(angle, speed) + angles = processing_data(data) + m.set_joints_angle(angles, speed) except MyArmDataException: pass - + if __name__ == "__main__": main() From 3fd7ce5a6181b3a5710a54ac0b697df57affc2cc Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 24 Mar 2025 09:48:16 +0800 Subject: [PATCH 10/57] update M&C demo --- demo/myArm_M&C_demo/myarm_c.py | 150 ++++++++++++++++++++++----- demo/myArm_M&C_demo/myarm_m.py | 183 ++++++++++++++++++++++++--------- demo/myArm_M&C_demo/utils.py | 56 ++++++++++ 3 files changed, 314 insertions(+), 75 deletions(-) create mode 100644 demo/myArm_M&C_demo/utils.py diff --git a/demo/myArm_M&C_demo/myarm_c.py b/demo/myArm_M&C_demo/myarm_c.py index 4ba68c60..75bf508c 100644 --- a/demo/myArm_M&C_demo/myarm_c.py +++ b/demo/myArm_M&C_demo/myarm_c.py @@ -1,43 +1,141 @@ -# 读取myarm_c的角度并发送 +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import threading +import traceback import socket +import typing as T +from serial import SerialException from pymycobot import MyArmC -import serial.tools.list_ports +import utils -def get_port(): # 获取所有串口号 - port_list = serial.tools.list_ports.comports() - i = 1 - res = {} - for port in port_list: - print("{} - {}".format(i, port.device)) - res[str(i)] = port.device - i += 1 - return res +class Config: + host = "0.0.0.0" # The host address to listen on + port = 8001 # The port to listen on + maximum_connections = 5 # The maximum number of connections allowed + + +def setup_robotic_connect(comport: str) -> T.Optional[MyArmC]: + robotic_api = None + try: + robotic_api = MyArmC(comport) + except Exception as e: + print(f" # (Error) Error while connecting robotic: {e}") + return robotic_api + + +class SocketTransportServer(threading.Thread): + def __init__(self, host="0.0.0.0", port=8001, listen_size=5): + super().__init__(daemon=True) + self.port = port + self.host = host + self.running = True + self.listen_size = listen_size + self.socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self.socket.bind((host, port)) + self.socket.listen(listen_size) + self.socket_client_table = {} + if host == "0.0.0.0": + host = utils.get_local_host() + print(f" # (Info) Start listening on {host}:{port}") + + def accept(self): + while self.running is True: + try: + yield self.socket.accept() + except OSError: + print(f" # (Error) Error while accepting socket") + continue + + def context(self, address, connection): + while self.running is True: + try: + data_buffer = connection.recv() + if len(data_buffer) == 0: + print(f" # (Warn) Close connection from {address}") + del self.socket_client_table[address] + connection.close() + break + yield data_buffer + except Exception as e: + print(f" # (Error) Error while reading socket: {e}") + traceback.print_exc() + break + + def run(self): + for conn, addr in self.accept(): + print(f" # (Info) Accept connection from {addr}") + self.socket_client_table[addr] = conn + + def sendall(self, data): + exit_addr_list = [] + for address, connection in self.socket_client_table.items(): + print(f" # (Info) {address} => {data}") + try: + connection.send(data) + except WindowsError: + print(f" # (Warn) Close connection from {address}") + exit_addr_list.append(address) + + for exit_addr in exit_addr_list: + del self.socket_client_table[exit_addr] + + def close(self): + print(f" # (Info) close socket on {self.host}:{self.port}") + self.running = False + self.socket.close() def main(): - port_dict = get_port() - port_c = input("input myArm C port: ") - c_port = port_dict[port_c] - c = MyArmC(c_port, debug=False) - HOST = '127.0.0.1' - PORT = 8001 - client = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - # 请求连接 - client.connect((HOST, PORT)) + serial_ports = utils.get_local_serial_port() + if len(serial_ports) == 0: + print(" # (Warn) No serial ports found. exit") + return + + serial_comport = utils.select("# (Info) Please select a serial port to connect robotic arm:", serial_ports, 1) + + print(f" # (Info) Selected {serial_comport} to connect robotic arm") + robotic_api = setup_robotic_connect(serial_comport) + if robotic_api is None: + print(" # (Error) Failed to connect robotic arm. exit") + return + + print(" # (Info) Start listening for changes in the angle of the robotic arm") + print(" # (Info) Press 【Ctrl+C】 to exit") + transport_server = SocketTransportServer( + host=Config.host, + port=Config.port, + listen_size=Config.maximum_connections + ) + transport_server.start() while True: try: - angle = c.get_joints_angle() - if angle is not None: - data = '\n' + str(angle) - client.send(data.encode('utf-8')) + angles = robotic_api.get_joints_angle() + if angles is None: + continue + + print(f" # (Info) Current angle: {angles}") + if max(angles) > 200 or min(angles) < -200: + print(" # (Warn) There is no communication between the joints, please check the connection") + continue + + transport_server.sendall(f"\n{angles}".encode('utf-8')) except KeyboardInterrupt: + print(" # (Info) Exit") break - except ConnectionAbortedError: - print("socket closed.") + except SerialException as e: + print(f" # (Error) Serial port error: {e}") break + except Exception as e: + print(f" # (Error) {e}") + + transport_server.close() + robotic_api._serial_port.close() + print(" # (Info) Close socket and serial port") + print(" # (Info) Exit") + if __name__ == "__main__": main() diff --git a/demo/myArm_M&C_demo/myarm_m.py b/demo/myArm_M&C_demo/myarm_m.py index f57b54e5..23ff5d71 100644 --- a/demo/myArm_M&C_demo/myarm_m.py +++ b/demo/myArm_M&C_demo/myarm_m.py @@ -1,61 +1,146 @@ -# myarm_m接收角度并执行 -from pymycobot.error import MyArmDataException -from pymycobot import MyArmC, MyArmM -import serial.tools.list_ports -import time +#!/usr/bin/env python +# -*- coding: UTF-8 -*- import socket +import typing as T +import utils +from serial import SerialException +from pymycobot import MyArmM -def get_port(): # 获取所有串口号 - port_list = serial.tools.list_ports.comports() - i = 1 - res = {} - for port in port_list: - print("{} - {}".format(i, port.device)) - res[str(i)] = port.device - i += 1 - return res +class Config: + host = "127.0.0.1" # C650 server host. + port = 8001 # C650 server port. + angle_conversion = False # Whether to roll back the angles of the robotic arm. + execution_speed: int = 50 # The speed of the robotic arm. + + +gripper_angular_transformation_equations = lambda x: round((x - 0.08) / (-95.27 - 0.08) * (-123.13 + 1.23) - 1.23) + + +M750_limit_info = [ + (-170, 170), + (-83, 83), + (-90, 84), + (-155, 153), + (-91, 88), + (-153, 153), + (-118, 2) +] + + +def flexible_parameters(angles: list, rollback: bool = True) -> list: + if rollback is True: + angles[-1] = gripper_angular_transformation_equations(angles[-1]) + angles[1] *= -1 + angles[2] *= -1 + + positions = [] + for i, angle in enumerate(angles): + min_angle, max_angle = M750_limit_info[i] + if angle < min_angle: + positions.append(min_angle) + elif angle > max_angle: + positions.append(max_angle) + else: + positions.append(angle) + + return positions + + +def setup_socket_connect(host, port): + try: + socket_api = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + socket_api.connect((host, port)) + except ConnectionRefusedError: + return None + except OSError as e: + print(f" # (Error) Error while connecting socket: {e}") + exit(1) + return socket_api + + +def setup_robotic_connect(comport: str) -> T.Optional[MyArmM]: + robotic_api = None + try: + robotic_api = MyArmM(comport) + except SerialException as serial_error: + for error in serial_error.args: + if error.startswith("could not open port"): + print(f" # (Error) Serial port 【{comport}】 is not available.") + else: + print(f" # (Error) Error while connecting robotic: {serial_error}") + return robotic_api def processing_data(data): data = data.split('\n')[-1] - angle = list(data[1:-1].split(',')) - angle = [float(i) for i in angle] - angle[2] *= -1 - gripper_angle = angle.pop(-1) - gripper_angle = (gripper_angle - 0.08) / (-95.27 - 0.08) * (-123.13 + 1.23) - 1.23 - gripper_angle = max(min(gripper_angle, -118), 2) - angle.append(gripper_angle) - return angle - - -def main(): - HOST = '127.0.0.1' - PORT = 8001 - server = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - server.bind((HOST, PORT)) - server.listen(5) - port_dict = get_port() - port_m = input("input myArm M port: ") - m_port = port_dict[port_m] - m = MyArmM(m_port, 1000000, debug=False) - speed = 100 - - print('Server start at: %s:%s' % (HOST, PORT)) - print('wait for connection...') - # 接收客户端请求 + angles = list(map(float, data[1:-1].split(','))) + return angles + +def main(host: str = Config.host, port: int = Config.port): + serial_ports = utils.get_local_serial_port() + if len(serial_ports) == 0: + print(" # (Warn) No serial ports found. exit") + return + + serial_comport = utils.select("# (Info) Please select a serial port to connect robotic arm:", serial_ports, 1) + + print(f" # (Info) Selected {serial_comport} to connect robotic arm") + + robotic_api = setup_robotic_connect(serial_comport) + if robotic_api is None: + print(" # (Error) Failed to connect robotic arm. exit") + return + + print(f" # (Info) Connected to robotic arm at {serial_comport}") + print(f" # (Info) Connecting to {host}:{port}...") + + while True: + socket_api = setup_socket_connect(host, port) + if socket_api is not None: + break + print(f" # (Error) Can't connect to {host}:{port}, connection retrying...") + + print(f" # (Info) Connected to {host}:{port}") + print(f" # (Info) Start listening for changes in the angle of the robotic arm") + print(f" # (Info) Press 【Ctrl+C】 to exit") while True: - conn, addr = server.accept() - # 客户端IP - print('Connected by ', addr) - while True: - try: - data = conn.recv(1024).decode('utf-8') - angles = processing_data(data) - m.set_joints_angle(angles, speed) - except MyArmDataException: - pass + try: + data = socket_api.recv(1024) + angles = processing_data(data.decode('utf-8')) + angles = flexible_parameters(angles, rollback=Config.angle_conversion) + + arm_angles: list = robotic_api.get_joints_angle() or [] + for joint_id, angle in enumerate(arm_angles, start=1): + if angle > 200 or angle < -200: + print( + f" # (Error) The angle of joint {joint_id} exceeds the limit {angle}, " + f"the M750 cannot follow the movement" + ) + break + else: + print(f" # (Info) Recv angles: {angles}") + robotic_api.set_joints_angle(angles=angles, speed=Config.execution_speed) + + except KeyboardInterrupt: + robotic_api.clear_recv_queue() + print(" # (Info) Received an exit instruction") + break + + except SerialException as serial_error: + print(f" # (Error) Serial port error: {serial_error}") + break + + except Exception as e: + print(f" # (Error) {e}") + break + + print(f" # (Info) Disconnecting from robotic arm at {serial_comport}...") + robotic_api._serial_port.close() + print(f" # (Info) Disconnecting from {host}:{port}...") + socket_api.close() + print(" # (Info) Exit") if __name__ == "__main__": diff --git a/demo/myArm_M&C_demo/utils.py b/demo/myArm_M&C_demo/utils.py new file mode 100644 index 00000000..25412c43 --- /dev/null +++ b/demo/myArm_M&C_demo/utils.py @@ -0,0 +1,56 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import socket +import typing as T +from serial.tools import list_ports +_T = T.TypeVar("_T") + + +def select( + message: str, + options: T.List[_T], + default: int = None, + level: int = 1, + echo: T.Callable = lambda msg: msg, + start: int = 1 +) -> T.Optional[_T]: + print(f"{message}\r\n") + p = " " * level + for ordinal, option in enumerate(options, start=start): + print(f"{p}{ordinal}. {echo(option)}") + else: + print() + + tips = f" # (Info) Select ({echo(options[default - 1])}) >" if default is not None else f" # (Info) Select: " + + while True: + try: + user_input = input(f"{tips}").lower().strip() + if len(user_input) == 0 and (default is not None or len(options) == 1): + return options[default - 1] + + if user_input.isdigit(): + return options[int(user_input) - 1] + + if user_input in options: + return user_input + + if user_input in ("q", "quit"): + return None + + raise ValueError + except ValueError: + print(f" * Invalid input, please enter a number.") + + except IndexError: + print(f" * Invalid input, please enter a valid number.") + + +def get_local_serial_port(): # 获取所有串口号 + return [comport.device for comport in list_ports.comports()] + + +def get_local_host(): + hostname = socket.gethostname() + ip_address = socket.gethostbyname(hostname) + return ip_address From 87eed94b0a75a13c6e8fa6844924788060d47755 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 24 Mar 2025 10:54:14 +0800 Subject: [PATCH 11/57] fix MyCobot280 rdkx5 bug --- pymycobot/common.py | 4 +- pymycobot/mycobot280rdkx5.py | 79 +++++++++++++++++++++--------------- 2 files changed, 50 insertions(+), 33 deletions(-) diff --git a/pymycobot/common.py b/pymycobot/common.py index 31f6c222..4d995f49 100644 --- a/pymycobot/common.py +++ b/pymycobot/common.py @@ -117,7 +117,9 @@ class ProtocolCode(object): GET_ATOM_VERSION = 0x09 CLEAR_ZERO_POS = 0x0A + SET_MONITOR_STATE = 0x0A SET_SERVO_CW = 0x0B + GET_MONITOR_STATE = 0x0B GET_SERVO_CW = 0x0C CLEAR_WAIST_QUEUE = 0x0D SET_LIMIT_SWITCH = 0x0E @@ -125,6 +127,7 @@ class ProtocolCode(object): SET_POS_SWITCH = 0x0B GET_POS_SWITCH = 0x0C + GET_COMMAND_QUEUE = 0x0C SetHTSGripperTorque = 0x35 GetHTSGripperTorque = 0x36 @@ -360,7 +363,6 @@ class ProtocolCode(object): GET_TOQUE_GRIPPER = 0xE9 SET_ERROR_DETECT_MODE = 0xE8 GET_ERROR_DETECT_MODE = 0xE9 - JOG_BASE_RPY = 0xEB MERCURY_GET_BASE_COORDS = 0xF0 MERCURY_SET_BASE_COORD = 0xF1 diff --git a/pymycobot/mycobot280rdkx5.py b/pymycobot/mycobot280rdkx5.py index e73b34da..c11cae18 100644 --- a/pymycobot/mycobot280rdkx5.py +++ b/pymycobot/mycobot280rdkx5.py @@ -13,11 +13,13 @@ from pymycobot.error import calibration_parameters -def setup_serial_connect(port, baudrate, timeout): - serial_api = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) +def setup_serial_port(port, baudrate, timeout=None): + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout serial_api.rts = False - if not serial_api.is_open: - serial_api.open() + serial_api.open() return serial_api @@ -79,16 +81,7 @@ def _res(self, real_command, has_reply, genre): if genre == ProtocolCode.SET_SSID_PWD: return 1 - if genre == ProtocolCode.GET_QUICK_INFO: - res = [] - valid_data = data[4:-1] - for header_i in range(0, len(valid_data), 2): - if header_i < 26: - one = valid_data[header_i: header_i + 2] - res.append(self._decode_int16(one)) - res.extend(valid_data[25:]) - else: - res = self._process_received(data, genre) + res = self._process_received(data, genre) if res is None: return None @@ -153,7 +146,7 @@ def _res(self, real_command, has_reply, genre): return self._int2coord(self._process_single(res)) elif genre in [ProtocolCode.GET_REBOOT_COUNT]: return self._process_high_low_bytes(res) - elif genre in (ProtocolCode.GET_ANGLES_COORDS, ProtocolCode.GET_QUICK_INFO): + elif genre in (ProtocolCode.GET_ANGLES_COORDS, ): r = [] for index, el in enumerate(res): if index < 6: @@ -188,6 +181,9 @@ def clear_queue(self): """Clear the command queue""" return self._mesg(ProtocolCode.CLEAR_COMMAND_QUEUE) + def get_queue_length(self): + return self._mesg(ProtocolCode.GET_COMMAND_QUEUE) + def async_or_sync(self): """Set the command execution mode Return: @@ -212,6 +208,25 @@ def clear_error_information(self): """Clear robot error message""" return self._mesg(ProtocolCode.CLEAR_ERROR_INFO, has_reply=True) + def set_monitor_state(self, state): + """ + Set the monitoring state + Args: + state: 0 - Disable monitoring + 1 - Enable monitoring + """ + return self._mesg(ProtocolCode.SET_MONITOR_STATE, state) + + def get_monitor_state(self): + """ + Get the monitoring state + """ + return self._mesg(ProtocolCode.GET_MONITOR_STATE, has_reply=True) + + def get_reboot_count(self): + """Get the number of times the robot has been restarted""" + return self._mesg(ProtocolCode.GET_REBOOT_COUNT, has_reply=True) + def power_on(self): """Open communication with Atom.""" return self._mesg(ProtocolCode.POWER_ON) @@ -231,15 +246,12 @@ def is_power_on(self): return self._mesg(ProtocolCode.IS_POWER_ON, has_reply=True) def release_all_servos(self, data=None): - """Relax all joints + """Relax all joints""" + return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS) - Args: - data: 1 - Undamping (The default is damping) - """ - if data is None: - return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS) - else: - return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS, data) + def focus_all_servos(self): + """Damping all joints""" + return self._mesg(ProtocolCode.FOCUS_ALL_SERVOS) def read_next_error(self): """Robot Error Detection @@ -316,10 +328,6 @@ def get_angles_coords(self): """Get joint angles and coordinates""" return self._mesg(ProtocolCode.GET_ANGLES_COORDS, has_reply=True) - def get_quick_move_message(self): - """Get the quick move message""" - return self._mesg(ProtocolCode.GET_QUICK_INFO, has_reply=True) - # JOG mode and operation def write_angles_time_control(self, angles, step_time): """Write the angle of a joint in time control mode @@ -509,6 +517,11 @@ def set_four_pieces_zero(self): """ return self._mesg(ProtocolCode.SET_FOUR_PIECES_ZERO, has_reply=True) + def set_servo_data(self, servo_id, data_id, value, mode=None): + if data_id in (0, 1, 2, 3, 4): + raise ValueError("Invalid data_id, addr 0 ~ 4 cannot be modified") + return super().set_servo_data(servo_id, data_id, value, mode) + # Running Status and Settings def set_joint_max(self, id, angle): """Set the joint maximum angle @@ -810,7 +823,7 @@ def __init__(self, port, baudrate=100_0000, timeout=0.1, debug=False, thread_loc debug : whether show debug info """ super().__init__(debug, thread_lock) - self._serial_port = setup_serial_connect(port=port, baudrate=baudrate, timeout=timeout) + self._serial_port = setup_serial_port(port=port, baudrate=baudrate, timeout=timeout) self._write = functools.partial(write, self) self._read = functools.partial(read, self) @@ -885,12 +898,14 @@ def close(self): def main(): - mc_sock = MyCobot280RDKX5Socket('192.168.1.246', port=30002, debug=True) + rdx_x5 = MyCobot280RDKX5("Com30", debug=True) + print(rdx_x5.get_reboot_count()) + # mc_sock = MyCobot280RDKX5Socket('192.168.1.246', port=30002, debug=True) # print(mc_sock.send_angle(1, 100, 50)) # print(mc_sock.get_quick_move_message()) - print(mc_sock.set_gpio_mode(0)) - print(mc_sock.setup_gpio_state(5, 1, initial=1)) - print(mc_sock.set_gpio_output(5, 0)) + # print(mc_sock.set_gpio_mode(0)) + # print(mc_sock.setup_gpio_state(5, 1, initial=1)) + # print(mc_sock.set_gpio_output(5, 0)) # print(mc_sock.get_gpio_input(5)) From 49872068136099b7b70104df1cb586e30a49e2ce Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 24 Mar 2025 15:57:51 +0800 Subject: [PATCH 12/57] fix MyArmM&C bugs --- pymycobot/error.py | 13 +++++++++++ pymycobot/myarm_api.py | 45 ++++++++++++++++++++++++------------- pymycobot/myarmm.py | 23 +++++++++---------- pymycobot/myarmm_control.py | 13 ++++++----- pymycobot/robot_info.py | 8 +++---- 5 files changed, 65 insertions(+), 37 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index 768ea45d..2f9b3182 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1325,6 +1325,9 @@ def calibration_parameters(**kwargs): if not value: raise ValueError("angles value can't be empty") + if len(value) != 7: + raise ValueError("The length of `angles` must be 7.") + for i, v in enumerate(value): min_angle = limit_info["angles_min"][i] max_angle = limit_info["angles_max"][i] @@ -1338,6 +1341,9 @@ def calibration_parameters(**kwargs): if not min_coord <= value <= max_coord: raise ValueError(f"coord value not right, should be {min_coord} ~ {max_coord}, but received {value}") elif parameter == 'coords': + if len(value) != 6: + raise ValueError("The length of `coords` must be 6.") + for i, v in enumerate(value): min_coord = limit_info["coord_min"][i] max_coord = limit_info["coord_max"][i] @@ -1351,12 +1357,19 @@ def calibration_parameters(**kwargs): raise ValueError( f"angle value not right, should be {min_encoder} ~ {max_encoder}, but received {value}") elif parameter == 'encoders': + if len(value) != 8: + raise ValueError("The length of `encoders` must be 8.") + for i, v in enumerate(value): max_encoder = limit_info["encoders_max"][i] min_encoder = limit_info["encoders_min"][i] if v < min_encoder or v > max_encoder: raise ValueError( f"encoder value not right, should be {min_encoder} ~ {max_encoder}, but received {v}") + + if (2048 - value[1]) + (2048 - value[2]) != 0: + raise ValueError("The 2 and 3 servos must be inverse") + elif parameter == "speed": check_value_type(parameter, value_type, TypeError, int) if not 1 <= value <= 100: diff --git a/pymycobot/myarm_api.py b/pymycobot/myarm_api.py index 38da7e62..a5e4b5da 100644 --- a/pymycobot/myarm_api.py +++ b/pymycobot/myarm_api.py @@ -10,10 +10,12 @@ def setup_serial_connect(port, baudrate, timeout=None): - serial_api = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout serial_api.rts = False - if not serial_api.is_open: - serial_api.open() + serial_api.open() return serial_api @@ -65,7 +67,7 @@ def _read_command_buffer(self, timeout=0.1): return commands def _read(self, genre): - if genre == ProtocolCode.GET_ROBOT_STATUS: + if genre == ProtocolCode.GET_ROBOT_ERROR_STATUS: timeout = 90 elif genre == ProtocolCode.SET_SSID_PWD or genre == ProtocolCode.GET_SSID_PWD: timeout = 0.05 @@ -99,7 +101,6 @@ def _mesg(self, genre, *args, **kwargs): """ real_command, has_reply, _async = super(MyArmMCProcessor, self)._mesg(genre, *args, **kwargs) with self.lock: - time.sleep(0.1) self._write(self._flatten(real_command)) if not has_reply: @@ -388,8 +389,11 @@ def set_servo_cw(self, servo_id, data): servo_id (int): 0 - 254 data (int): 0 - 32 """ - assert 0 <= data <= 32, "data must be between 0 and 32" self.calibration_parameters(servo_id=servo_id) + if servo_id == 8: + assert 0 <= data <= 16, "data must be between 0 and 16" + else: + assert 0 <= data <= 32, "data must be between 0 and 32" self._mesg(ProtocolCode.SET_SERVO_MOTOR_CLOCKWISE, servo_id, data) def get_servo_cw(self, servo_id): @@ -408,8 +412,11 @@ def set_servo_cww(self, servo_id, data): servo_id (int): 0 - 254 data (int): 0 - 32 """ - assert 0 <= data <= 32, "data must be between 0 and 32" self.calibration_parameters(servo_id=servo_id) + if servo_id == 8: + assert 0 <= data <= 16, "data must be between 0 and 16" + else: + assert 0 <= data <= 32, "data must be between 0 and 32" return self._mesg(ProtocolCode.SET_SERVO_MOTOR_COUNTER_CLOCKWISE, servo_id, data) def get_servo_cww(self, servo_id): @@ -449,7 +456,7 @@ def get_servo_system_data(self, servo_id, addr, mode): """ if mode not in (1, 2): raise ValueError('mode must be 1 or 2') - self.calibration_parameters(servo_id=servo_id, servo_addr=addr) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_SERVO_MOTOR_CONFIG, servo_id, addr, mode, has_reply=True) def set_master_out_io_state(self, pin_number, status=1): @@ -484,7 +491,10 @@ def set_tool_out_io_state(self, io_number, status=1): io_number (int): 1 - 2 status: 0 or 1; 0: low; 1: high. default: 1 """ - self.calibration_parameters(master_pin=io_number, status=status) + if io_number not in (1, 2): + raise ValueError("io_number must be 1 or 2") + if status not in (0, 1): + raise ValueError("status must be 0 or 1") self._mesg(ProtocolCode.SET_ATOM_PIN_STATUS, io_number, status) def get_tool_in_io_state(self, pin): @@ -497,8 +507,8 @@ def get_tool_in_io_state(self, pin): 0 or 1. 1: high 0: low """ - if pin not in (0, 1): - raise ValueError("pin must be 0 or 1") + if pin not in (1, 2): + raise ValueError("pin must be 1 or 2") return self._mesg(ProtocolCode.GET_ATOM_PIN_STATUS, pin, has_reply=True) @@ -511,8 +521,13 @@ def set_tool_led_color(self, r, g, b): b: 0-255 """ - self._mesg(ProtocolCode.GET_ATOM_LED_COLOR, r, g, b) + return self._mesg(ProtocolCode.GET_ATOM_LED_COLOR, r, g, b) - def restore_servo_system_param(self): - """Restore servo motor system parameters""" - self._mesg(ProtocolCode.RESTORE_SERVO_SYSTEM_PARAM) + def restore_servo_system_param(self, servo_id): + """ + Restore servo motor system parameters + Args: + servo_id: 0 - 255 + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.RESTORE_SERVO_SYSTEM_PARAM, servo_id) diff --git a/pymycobot/myarmm.py b/pymycobot/myarmm.py index 132d1036..b961f0fa 100644 --- a/pymycobot/myarmm.py +++ b/pymycobot/myarmm.py @@ -1,5 +1,8 @@ # coding=utf-8 from __future__ import division + +import time + from pymycobot.common import ProtocolCode from pymycobot.myarm_api import MyArmAPI @@ -17,7 +20,7 @@ def set_joint_angle(self, joint_id, angle, speed): angle (int) : 0 - 254 speed (int) : 1 - 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, joint_id=joint_id, angle=angle, speed=speed) + self.calibration_parameters(joint_id=joint_id, angle=angle, speed=speed) self._mesg(ProtocolCode.SEND_ANGLE, joint_id, [self._angle2int(angle)], speed) def set_joints_angle(self, angles, speed): @@ -27,7 +30,7 @@ def set_joints_angle(self, angles, speed): angles (list[int]): 0 - 254 speed (int): 0 - 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, angles=angles, speed=speed) + self.calibration_parameters(angles=angles, speed=speed) angles = list(map(self._angle2int, angles)) return self._mesg(ProtocolCode.SEND_ANGLES, angles, speed) @@ -44,13 +47,6 @@ def stop_robot(self): """The robot stops moving""" self._mesg(ProtocolCode.STOP) - # def is_in_position(self): - # """Whether the robot has reached the specified point - # Returns: - # - # """ - # return self._mesg(ProtocolCode.IS_IN_POSITION, reply=True) - def set_servo_encoder(self, servo_id, encoder, speed): """Sets the individual motor motion to the target encoder potential value @@ -60,7 +56,7 @@ def set_servo_encoder(self, servo_id, encoder, speed): speed: (int) 1 - 100 """ - self.calibration_parameters(class_name=self.__class__.__name__, servo_id=servo_id, encoder=encoder, speed=speed) + self.calibration_parameters(servo_id=servo_id, encoder=encoder, speed=speed) self._mesg(ProtocolCode.SET_ENCODER, servo_id, [encoder], speed) def set_servos_encoder(self, positions, speed): @@ -70,12 +66,12 @@ def set_servos_encoder(self, positions, speed): positions (list[int * 8]): 0 - 4095: speed (int): 1 - 100: """ - self.calibration_parameters(class_name=self.__class__.__name__, encoders=positions, speed=speed) + self.calibration_parameters(encoders=positions, speed=speed) self._mesg(ProtocolCode.SET_ENCODERS, positions, speed) def set_servos_encoder_drag(self, encoders, speeds): """Set multiple servo motors with a specified speed to the target encoder potential value""" - self.calibration_parameters(class_name=self.__class__.__name__, encoders=encoders, speeds=speeds) + self.calibration_parameters(encoders=encoders, speeds=speeds) self._mesg(ProtocolCode.SET_ENCODERS_DRAG, encoders, speeds) def set_assist_out_io_state(self, io_number, status=1): @@ -127,6 +123,9 @@ def set_servo_enabled(self, joint_id, state): 1-focus 0-release """ + if state not in (0, 1): + raise ValueError("state must be 0 or 1") + self.calibration_parameters(jonit_id=joint_id, state=state) self._mesg(ProtocolCode.RELEASE_ALL_SERVOS, joint_id, state) def get_joints_max(self): diff --git a/pymycobot/myarmm_control.py b/pymycobot/myarmm_control.py index 0f402f23..49eaac83 100644 --- a/pymycobot/myarmm_control.py +++ b/pymycobot/myarmm_control.py @@ -36,10 +36,12 @@ def setup_logging(debug: bool = False): def setup_serial_port(port, baudrate, timeout=0.1): - serial_api = serial.Serial(port, baudrate, timeout=timeout) + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout serial_api.rts = False - if not serial_api.is_open: - serial_api.open() + serial_api.open() return serial_api @@ -159,7 +161,6 @@ def _read_genre_result(self, genre): r.append(self._int2angle(res[index])) return r elif self.__is_return(genre, data): - print("11111111111111111111111") return self._process_single(res) else: return res @@ -387,10 +388,10 @@ def jog_increment(self, joint_id, increment, speed): increment(int): incremental speed(int): int (0 - 100) """ - if not (isinstance(increment, int) or isinstance(increment, float)): + if isinstance(increment, (int, float)): raise ValueError("increment must be int or float") - self.calibration_parameters(joint_id=joint_id, speed=speed) + self.calibration_parameters(joint_id=joint_id, speed=speed, angle=increment) return self._mesg(ProtocolCode.JOG_INCREMENT, joint_id, [self._angle2int(increment)], speed) def pause(self): diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 615603df..2c77d1df 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -327,8 +327,8 @@ class RobotLimit: "MyArmM": { "joint_id": [1, 2, 3, 4, 5, 6, 7], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], - "angles_min": [-170, -83, -90, -155, -91, -153, -118], - "angles_max": [170, 83, 84, 153, 88, 153, 2], + "angles_min": [-165, -80, -100, -160, -90, -180, -118], + "angles_max": [165, 100, 80, 160, 120, 180, 2], "encoders_min": [137, 1163, 1035, 1013, 248, 979, 220, 706], "encoders_max": [4004, 2945, 3079, 3026, 3724, 2994, 3704, 2048] }, @@ -338,8 +338,8 @@ class RobotLimit: "coord_id": [1, 2, 3, 4, 5, 6], "coord_min": [-833.325, -833.325, -351.11, -180, -180, -180], "coord_max": [833.325, 833.325, 1007.225, 180, 180, 180], - "angles_min": [-170, -83, -90, -155, -91, -153, -118], - "angles_max": [170, 83, 84, 153, 88, 153, 2], + "angles_min": [-165, -80, -100, -160, -90, -180, -118], + "angles_max": [165, 100, 80, 160, 120, 180, 2], "encoders_min": [137, 1163, 1035, 1013, 248, 979, 220, 706], "encoders_max": [4004, 2945, 3079, 3026, 3724, 2994, 3704, 2048] }, From 53241c7d0114d14696f3bbcf437628841a0f05b7 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 27 Mar 2025 19:30:37 +0800 Subject: [PATCH 13/57] fix bugs --- pymycobot/myarmm.py | 11 +++++++---- pymycobot/myarmm_control.py | 18 ++++++++++++------ pymycobot/robot_info.py | 2 +- 3 files changed, 20 insertions(+), 11 deletions(-) diff --git a/pymycobot/myarmm.py b/pymycobot/myarmm.py index b961f0fa..8e0ba8a1 100644 --- a/pymycobot/myarmm.py +++ b/pymycobot/myarmm.py @@ -115,18 +115,21 @@ def clear_robot_err(self): """Clear the robot abnormality Ignore the error joint and continue to move""" self._mesg(ProtocolCode.CLEAR_ROBOT_ERROR) - def set_servo_enabled(self, joint_id, state): + def set_servo_enabled(self, servo_id, state): """Set the servo motor torque switch Args: - joint_id (int): 0-254 254-all + servo_id (int): 0-254 254-all state: 0/1 1-focus 0-release """ if state not in (0, 1): raise ValueError("state must be 0 or 1") - self.calibration_parameters(jonit_id=joint_id, state=state) - self._mesg(ProtocolCode.RELEASE_ALL_SERVOS, joint_id, state) + + if servo_id not in range(0, 255): + raise ValueError("servo_id must be between 0 and 254") + + self._mesg(ProtocolCode.RELEASE_ALL_SERVOS, servo_id, state) def get_joints_max(self): """Read the maximum angle of all joints""" diff --git a/pymycobot/myarmm_control.py b/pymycobot/myarmm_control.py index 49eaac83..3b86edb1 100644 --- a/pymycobot/myarmm_control.py +++ b/pymycobot/myarmm_control.py @@ -91,8 +91,14 @@ def _read_genre_result(self, genre): res = [] valid_data = data[4:-1] for header_i in range(0, len(valid_data), 2): - one = valid_data[header_i: header_i + 2] - res.append(self._decode_int16(one)) + d = self._decode_int16(valid_data[header_i: header_i + 2]) + if d == 0: + res.append(d) + continue + reverse_bins = reversed(bin(d)[2:]) + rank = [i for i, e in enumerate(reverse_bins) if e != '0'] + res.append(rank) + else: res = self._process_received(data, genre) if not res: @@ -388,10 +394,10 @@ def jog_increment(self, joint_id, increment, speed): increment(int): incremental speed(int): int (0 - 100) """ - if isinstance(increment, (int, float)): + if not isinstance(increment, (int, float)): raise ValueError("increment must be int or float") - self.calibration_parameters(joint_id=joint_id, speed=speed, angle=increment) + self.calibration_parameters(joint_id=joint_id, angle=increment, speed=speed) return self._mesg(ProtocolCode.JOG_INCREMENT, joint_id, [self._angle2int(increment)], speed) def pause(self): @@ -558,10 +564,10 @@ def get_servo_data(self, servo_id, data_id, mode=None): values 0 - 4096 """ if mode is not None: - self.calibration_parameters(servo_id=servo_id, servo_addr=data_id, mode=mode) + self.calibration_parameters(servo_id=servo_id, mode=mode) return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id, mode) - self.calibration_parameters(servo_id=servo_id, servo_addr=data_id) + self.calibration_parameters(servo_id=servo_id) return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, data_id) def set_servo_calibration(self, servo_id): diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 2c77d1df..55586a04 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -319,7 +319,7 @@ class RobotLimit: "coords_max": [310, 310, 480, 180, 180, 180] }, "MyArmC": { - "joint_id": [1, 2, 3, 4, 5, 6], + "joint_id": [1, 2, 3, 4, 5, 6, 7], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], "angles_min": [-165, -80, -100, -160, -90, -180], "angles_max": [165, 100, 80, 160, 90, 180] From 3d60a0dc28592f38ae93eb67fd12e0b97f657f9b Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 28 Mar 2025 11:06:08 +0800 Subject: [PATCH 14/57] fix bug --- pymycobot/error.py | 5 +++-- pymycobot/myarmm_control.py | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index 2f9b3182..ab90e81b 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1325,8 +1325,9 @@ def calibration_parameters(**kwargs): if not value: raise ValueError("angles value can't be empty") - if len(value) != 7: - raise ValueError("The length of `angles` must be 7.") + joint_length = len(limit_info["joint_id"]) + if len(value) != joint_length: + raise ValueError(f"The length of `angles` must be {joint_length}.") for i, v in enumerate(value): min_angle = limit_info["angles_min"][i] diff --git a/pymycobot/myarmm_control.py b/pymycobot/myarmm_control.py index 3b86edb1..61f9a86a 100644 --- a/pymycobot/myarmm_control.py +++ b/pymycobot/myarmm_control.py @@ -254,7 +254,7 @@ def write_angle(self, joint_id, degree, speed): """Send the angle of a joint to robot arm. Args: - joint_id: (int) 1 ~ 7 + joint_id: (int) 1 ~ 6 degree: (float) -150 ~ 150 speed : (int) 1 ~ 100 """ From 4ff4ec45daaa6609cf6082b2483783a8faf64f41 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 28 Mar 2025 17:31:45 +0800 Subject: [PATCH 15/57] fix ThreeHand api bug --- pymycobot/end_control.py | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/pymycobot/end_control.py b/pymycobot/end_control.py index 9c8d48ae..2eb67c9e 100644 --- a/pymycobot/end_control.py +++ b/pymycobot/end_control.py @@ -418,13 +418,19 @@ def set_hand_gripper_pinch_action_speed_consort(self, pinch_pose, rank_mode, gri Idle flag. By default, there is no such byte. When this byte is 1, the idle finger can be freely manipulated. """ - self.calibration_parameters(class_name=self.__class__.__name__, pinch_pose=pinch_pose, rank_mode=rank_mode, idle_flag=idle_flag) + if idle_flag is None: + self.calibration_parameters( + class_name=self.__class__.__name__, pinch_pose=pinch_pose, rank_mode=rank_mode + ) return self.__set_tool_fittings_value( FingerGripper.SET_HAND_GRIPPER_PINCH_ACTION_SPEED_CONSORT, pinch_pose, rank_mode, gripper_id=gripper_id ) else: + self.calibration_parameters( + class_name=self.__class__.__name__, pinch_pose=pinch_pose, rank_mode=rank_mode, idle_flag=idle_flag + ) return self.__set_tool_fittings_value( FingerGripper.SET_HAND_GRIPPER_PINCH_ACTION_SPEED_CONSORT, pinch_pose, rank_mode, idle_flag, gripper_id=gripper_id - ) \ No newline at end of file + ) From 0c2fb1059147caa57873374df5c95291ecfe450e Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 1 Apr 2025 18:53:05 +0800 Subject: [PATCH 16/57] Fixed the issue that Pro630 could not read data --- pymycobot/pro630.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/pymycobot/pro630.py b/pymycobot/pro630.py index ab95ec57..d4a9cebd 100644 --- a/pymycobot/pro630.py +++ b/pymycobot/pro630.py @@ -9,7 +9,7 @@ class Pro630(CloseLoop): - def __init__(self, port, baudrate="115200", timeout=0.1, debug=False): + def __init__(self, port, baudrate="115200", timeout=0.1, debug=False, save_serial_log=False): """ Args: port : port string @@ -27,6 +27,7 @@ def __init__(self, port, baudrate="115200", timeout=0.1, debug=False): GPIO.setwarnings(False) GPIO.setup(self.power_control_1, GPIO.IN) GPIO.setup(self.power_control_2, GPIO.OUT) + self.save_serial_log = save_serial_log self._serial_port = serial.Serial() self._serial_port.port = port self._serial_port.baudrate = baudrate From a4b939639e29dffe0b9c058ac44ecb242d618889 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 3 Apr 2025 15:10:03 +0800 Subject: [PATCH 17/57] fix MyArmM bug --- pymycobot/myarm_api.py | 2 ++ pymycobot/myarmm.py | 16 ++++++++++++++-- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/pymycobot/myarm_api.py b/pymycobot/myarm_api.py index a5e4b5da..66cd3785 100644 --- a/pymycobot/myarm_api.py +++ b/pymycobot/myarm_api.py @@ -75,6 +75,8 @@ def _read(self, genre): timeout = 0.3 elif genre in [ProtocolCode.SET_GRIPPER_CALIBRATION]: timeout = 0.4 + elif genre == ProtocolCode.POWER_ON: + timeout = 2 else: timeout = 0.1 diff --git a/pymycobot/myarmm.py b/pymycobot/myarmm.py index 8e0ba8a1..ce51d151 100644 --- a/pymycobot/myarmm.py +++ b/pymycobot/myarmm.py @@ -70,8 +70,20 @@ def set_servos_encoder(self, positions, speed): self._mesg(ProtocolCode.SET_ENCODERS, positions, speed) def set_servos_encoder_drag(self, encoders, speeds): - """Set multiple servo motors with a specified speed to the target encoder potential value""" - self.calibration_parameters(encoders=encoders, speeds=speeds) + """ + Set multiple servo motors with a specified speed to the target encoder potential value + Args: + encoders (list[int * 8]): 0 - 4095: + speeds (list[int * 8]): -10000 - 10000: + """ + self.calibration_parameters(encoders=encoders) + if len(encoders) != len(speeds): + raise ValueError("encoders and speeds must have the same length") + + for sid, speed in enumerate(speeds): + if not -10000 < speed < 1000: + raise ValueError(f"servo {sid} speed must be between -10000 and 1000") + self._mesg(ProtocolCode.SET_ENCODERS_DRAG, encoders, speeds) def set_assist_out_io_state(self, io_number, status=1): From 75d06d699d37bb44f8390515c650dca2b0753c2a Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 7 Apr 2025 15:09:24 +0800 Subject: [PATCH 18/57] MyArmM&C adds get_joints_coord interface --- pymycobot/myarm_api.py | 7 +++++++ pymycobot/myarmc.py | 6 ------ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/pymycobot/myarm_api.py b/pymycobot/myarm_api.py index 66cd3785..76fa3f5a 100644 --- a/pymycobot/myarm_api.py +++ b/pymycobot/myarm_api.py @@ -261,6 +261,13 @@ def get_joints_angle(self): """ return self._mesg(ProtocolCode.GET_ANGLES, has_reply=True) + def get_joints_coord(self): + """Get the coordinates + Returns: + list[float] * 6: joints angle + """ + return self._mesg(ProtocolCode.GET_JOINTS_COORD, has_reply=True) + def set_servo_calibrate(self, servo_id): """Sets the zero position of the specified servo motor diff --git a/pymycobot/myarmc.py b/pymycobot/myarmc.py index f6d37e07..102cd72f 100644 --- a/pymycobot/myarmc.py +++ b/pymycobot/myarmc.py @@ -28,9 +28,3 @@ def is_tool_btn_clicked(self, mode=1): return self._mesg(ProtocolCode.GET_ATOM_PRESS_STATUS, mode, has_reply=True) - def get_joints_coord(self): - """Get the coordinates - Returns: - list[float] * 6: joints angle - """ - return self._mesg(ProtocolCode.GET_JOINTS_COORD, has_reply=True) From 06f187cc977cb7de24264504e63e4670cc47d76d Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 7 Apr 2025 17:16:02 +0800 Subject: [PATCH 19/57] fix Pro630 bug --- pymycobot/pro630.py | 17 ++++++++++++++--- pymycobot/pro630client.py | 17 ++++++++++++++--- 2 files changed, 28 insertions(+), 6 deletions(-) diff --git a/pymycobot/pro630.py b/pymycobot/pro630.py index d4a9cebd..b811ce7c 100644 --- a/pymycobot/pro630.py +++ b/pymycobot/pro630.py @@ -44,8 +44,10 @@ def _mesg(self, genre, *args, **kwargs): read_data = super(Pro630, self)._mesg(genre, *args, **kwargs) if read_data is None: return None - elif read_data == 1: - return 1 + + if isinstance(read_data, int): + return read_data + valid_data, data_len = read_data res = [] if data_len in [8, 12, 14, 16, 26, 60]: @@ -60,6 +62,14 @@ def _mesg(self, genre, *args, **kwargs): elif data_len == 6 and genre in [ProtocolCode.GET_SERVO_STATUS, ProtocolCode.GET_SERVO_VOLTAGES, ProtocolCode.GET_SERVO_CURRENTS]: for i in range(data_len): res.append(valid_data[i]) + elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: + res.extend(valid_data[:8]) + data = valid_data[8:20] + for header_i in range(0, len(data), 2): + one = data[header_i: header_i + 2] + res.append(self._decode_int16(one)) + res.extend(valid_data[20:26]) + return res else: for header_i in range(0, len(valid_data), 2): one = valid_data[header_i : header_i + 2] @@ -140,7 +150,8 @@ def _mesg(self, genre, *args, **kwargs): data1 = self._decode_int8(valid_data[i : i + 1]) res.append(0xFF & data1 if data1 < 0 else data1) res.append(self._decode_int8(valid_data)) - if res == []: + + if len(res) == 0: return None if genre in [ diff --git a/pymycobot/pro630client.py b/pymycobot/pro630client.py index 095ac5e1..602b22fe 100644 --- a/pymycobot/pro630client.py +++ b/pymycobot/pro630client.py @@ -39,8 +39,10 @@ def _mesg(self, genre, *args, **kwargs): read_data = super(Pro630Client, self)._mesg(genre, *args, **kwargs) if read_data is None: return None - elif read_data == 1: - return 1 + + if isinstance(read_data, int): + return read_data + valid_data, data_len = read_data res = [] if data_len in [8, 12, 14, 16, 26, 60]: @@ -55,6 +57,14 @@ def _mesg(self, genre, *args, **kwargs): elif data_len == 6 and genre in [ProtocolCode.GET_SERVO_STATUS, ProtocolCode.GET_SERVO_VOLTAGES, ProtocolCode.GET_SERVO_CURRENTS]: for i in range(data_len): res.append(valid_data[i]) + elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: + res.extend(valid_data[:8]) + data = valid_data[8:20] + for header_i in range(0, len(data), 2): + one = data[header_i: header_i + 2] + res.append(self._decode_int16(one)) + res.extend(valid_data[20:26]) + return res else: for header_i in range(0, len(valid_data), 2): one = valid_data[header_i : header_i + 2] @@ -135,7 +145,8 @@ def _mesg(self, genre, *args, **kwargs): data1 = self._decode_int8(valid_data[i : i + 1]) res.append(0xFF & data1 if data1 < 0 else data1) res.append(self._decode_int8(valid_data)) - if res == []: + + if len(res) == 0: return None if genre in [ From 99dcb2497b6a03d97eaf1b265702673a790ec846 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 11 Apr 2025 18:48:04 +0800 Subject: [PATCH 20/57] fix Pro630 bugs --- pymycobot/error.py | 56 ++++++ pymycobot/pro630.py | 387 +++++++++++++++++++++++--------------- pymycobot/pro630client.py | 23 +-- pymycobot/robot_info.py | 9 + 4 files changed, 309 insertions(+), 166 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index ab90e81b..6f5a61a5 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1426,6 +1426,62 @@ def calibration_parameters(**kwargs): if not 0 <= v <= 255: raise ValueError(f"rgb value not right, should be 0 ~ 255, the received rgb is {value}") + elif class_name in ["Pro630"]: + limit_info = robot_limit[class_name] + for parameter, value in kwargs.items(): + value_type = type(value) + if parameter in ("servo_id", "joint_id", "coord_id") and value not in limit_info[parameter]: + raise ValueError( + f"The {parameter} not right, should be in {limit_info[parameter]}, but received {value}.") + elif parameter == 'angle': + i = kwargs['joint_id'] - 1 + min_angle = limit_info["angles_min"][i] + max_angle = limit_info["angles_max"][i] + if value < min_angle or value > max_angle: + raise ValueError( + f"angle value not right, should be {min_angle} ~ {max_angle}, but received {value}") + elif parameter == 'angles': + if not value: + raise ValueError("angles value can't be empty") + + joint_length = len(limit_info["joint_id"]) + if len(value) != joint_length: + raise ValueError(f"The length of `angles` must be {joint_length}.") + + for i, v in enumerate(value): + min_angle = limit_info["angles_min"][i] + max_angle = limit_info["angles_max"][i] + if v < min_angle or v > max_angle: + raise ValueError( + f"angle value not right, should be {min_angle} ~ {max_angle}, but received {v}") + elif parameter == 'coord': + coord_index = kwargs['coord_id'] - 1 + min_coord = limit_info["coords_min"][coord_index] + max_coord = limit_info["coords_max"][coord_index] + if not min_coord <= value <= max_coord: + raise ValueError( + f"coord value not right, should be {min_coord} ~ {max_coord}, but received {value}") + elif parameter == 'coords': + if len(value) != 6: + raise ValueError("The length of `coords` must be 6.") + + for i, v in enumerate(value): + min_coord = limit_info["coords_min"][i] + max_coord = limit_info["coords_max"][i] + if not min_coord <= v <= max_coord: + raise ValueError( + f"coord value not right, should be {min_coord} ~ {max_coord}, but received {v}") + elif parameter == "speed": + check_value_type(parameter, value_type, TypeError, int) + if not 1 <= value <= 100: + raise ValueError(f"speed value not right, should be 1 ~ 100, the received speed is {value}") + elif parameter == "speeds": + assert len(value) == 8, "The length of `speeds` must be 8." + for i, s in enumerate(value): + if not 1 <= s <= 100: + raise ValueError( + f"speed value not right, should be 1 ~ 100, the received speed is {value}") + def restrict_serial_port(func): """ diff --git a/pymycobot/pro630.py b/pymycobot/pro630.py index b811ce7c..f11cc3f4 100644 --- a/pymycobot/pro630.py +++ b/pymycobot/pro630.py @@ -1,14 +1,46 @@ # coding=utf-8 - +import locale import time import threading - +import numpy as np +import serial from pymycobot.close_loop import CloseLoop from pymycobot.error import calibration_parameters from pymycobot.common import ProtocolCode +from pymycobot.robot_info import _interpret_status_code + + +def get_local_language(): + language, _ = locale.getdefaultlocale() + if language not in ["zh_CN", "en_US"]: + language = "en_US" + return language -class Pro630(CloseLoop): +def setup_serial_connect(port, baudrate="115200", timeout=0.1): + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout + serial_api.rts = False + serial_api.open() + return serial_api + + +class Pro630Api(CloseLoop): + joint_number = 6 + power_control_1 = 3 + power_control_2 = 4 + arm_span_maximum = 630 + pin_numbered_mapping_table = { + 1: 17, + 2: 27, + 3: 22, + 4: 5, + 5: 6, + 6: 19 + } + def __init__(self, port, baudrate="115200", timeout=0.1, debug=False, save_serial_log=False): """ Args: @@ -17,129 +49,141 @@ def __init__(self, port, baudrate="115200", timeout=0.1, debug=False, save_seria timeout : default 0.1 debug : whether show debug info """ - super(Pro630, self).__init__(debug) - self.calibration_parameters = calibration_parameters - import serial + super(Pro630Api, self).__init__(debug) import RPi.GPIO as GPIO - self.power_control_1 = 3 - self.power_control_2 = 4 + GPIO.setmode(GPIO.BCM) GPIO.setwarnings(False) GPIO.setup(self.power_control_1, GPIO.IN) GPIO.setup(self.power_control_2, GPIO.OUT) + self.save_serial_log = save_serial_log - self._serial_port = serial.Serial() - self._serial_port.port = port - self._serial_port.baudrate = baudrate - self._serial_port.timeout = timeout - self._serial_port.rts = False - self._serial_port.open() + + self._serial_port = setup_serial_connect(port, baudrate, timeout) + self.calibration_parameters = calibration_parameters + self.language = get_local_language() + self.lock = threading.Lock() self.lock_out = threading.Lock() + self.read_threading = threading.Thread(target=self.read_thread) self.read_threading.daemon = True self.read_threading.start() - - def _mesg(self, genre, *args, **kwargs): - read_data = super(Pro630, self)._mesg(genre, *args, **kwargs) + + self._joint_max_angles = [0] * self.joint_number + self._joint_min_angles = [0] * self.joint_number + + def _decode_command(self, genre, read_data): if read_data is None: return None if isinstance(read_data, int): return read_data + decode_respond = [] + valid_data, data_len = read_data - res = [] + if data_len in [8, 12, 14, 16, 26, 60]: if data_len == 8 and (genre == ProtocolCode.IS_INIT_CALIBRATION): if valid_data[0] == 1: return 1 n = len(valid_data) - for v in range(1,n): - res.append(valid_data[v]) + for v in range(1, n): + decode_respond.append(valid_data[v]) elif data_len == 8 and genre == ProtocolCode.GET_DOWN_ENCODERS: - res = self.bytes4_to_int(valid_data) - elif data_len == 6 and genre in [ProtocolCode.GET_SERVO_STATUS, ProtocolCode.GET_SERVO_VOLTAGES, ProtocolCode.GET_SERVO_CURRENTS]: + decode_respond = self.bytes4_to_int(valid_data) + elif data_len == 6 and genre in [ProtocolCode.GET_SERVO_STATUS, ProtocolCode.GET_SERVO_VOLTAGES, + ProtocolCode.GET_SERVO_CURRENTS]: for i in range(data_len): - res.append(valid_data[i]) + decode_respond.append(valid_data[i]) elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: - res.extend(valid_data[:8]) - data = valid_data[8:20] - for header_i in range(0, len(data), 2): - one = data[header_i: header_i + 2] - res.append(self._decode_int16(one)) - res.extend(valid_data[20:26]) + i = 0 + res = [] + while i < data_len: + if i < 8: + res.append(valid_data[i]) + i += 1 + else: + one = valid_data[i: i + 2] + res.append(self._decode_int16(one)) + i += 2 return res else: for header_i in range(0, len(valid_data), 2): - one = valid_data[header_i : header_i + 2] - res.append(self._decode_int16(one)) + one = valid_data[header_i: header_i + 2] + decode_respond.append(self._decode_int16(one)) elif data_len == 2: if genre in [ProtocolCode.IS_SERVO_ENABLE]: return [self._decode_int8(valid_data[1:2])] elif genre in [ProtocolCode.GET_ERROR_INFO]: return [self._decode_int8(valid_data[1:])] - res.append(self._decode_int16(valid_data)) + elif genre in [ProtocolCode.GET_LIMIT_SWITCH]: + for i in valid_data: + decode_respond.append(i) + elif genre in [ProtocolCode.GET_ROBOT_ID]: + decode_respond.append(self._decode_int16(valid_data)) elif data_len == 3: - res.append(self._decode_int16(valid_data[1:])) + decode_respond.append(self._decode_int16(valid_data[1:])) elif data_len == 4: if genre == ProtocolCode.COBOTX_GET_ANGLE: - res = self.bytes4_to_int(valid_data) - for i in range(1,4): - res.append(valid_data[i]) + decode_respond = self.bytes4_to_int(valid_data) + for i in range(1, 4): + decode_respond.append(valid_data[i]) elif data_len == 7: error_list = [i for i in valid_data] for i in error_list: - if i in range(16,23): - res.append(1) - elif i in range(23,29): - res.append(2) - elif i in range(32,112): - res.append(3) + if i in range(16, 23): + decode_respond.append(1) + elif i in range(23, 29): + decode_respond.append(2) + elif i in range(32, 112): + decode_respond.append(3) else: - res.append(i) + decode_respond.append(i) elif data_len == 24: - res = self.bytes4_to_int(valid_data) + decode_respond = self.bytes4_to_int(valid_data) elif data_len == 40: i = 0 while i < data_len: if i < 28: - res += self.bytes4_to_int(valid_data) - i+=4 + decode_respond += self.bytes4_to_int(valid_data) + i += 4 else: - one = valid_data[i : i + 2] - res.append(self._decode_int16(one)) - i+=2 - elif data_len == 30: + one = valid_data[i: i + 2] + decode_respond.append(self._decode_int16(one)) + i += 2 + elif data_len == 32: i = 0 res = [] while i < 30: if i < 9 or i >= 23: res.append(valid_data[i]) - i+=1 + i += 1 elif i < 23: - one = valid_data[i : i + 2] + one = valid_data[i: i + 2] res.append(self._decode_int16(one)) - i+=2 + i += 2 + return res elif data_len == 38: i = 0 res = [] while i < data_len: if i < 10 or i >= 30: res.append(valid_data[i]) - i+=1 + i += 1 elif i < 38: - one = valid_data[i : i + 2] + one = valid_data[i: i + 2] res.append(self._decode_int16(one)) - i+=2 + i += 2 + return res elif data_len == 56: for i in range(0, data_len, 8): - - byte_value = int.from_bytes(valid_data[i:i+4], byteorder='big', signed=True) - res.append(byte_value) + byte_value = int.from_bytes(valid_data[i:i + 4], byteorder='big', signed=True) + decode_respond.append(byte_value) elif data_len == 6: for i in valid_data: - res.append(i) + decode_respond.append(i) else: if genre in [ ProtocolCode.GET_SERVO_VOLTAGES, @@ -147,19 +191,25 @@ def _mesg(self, genre, *args, **kwargs): ProtocolCode.GET_SERVO_TEMPS, ]: for i in range(data_len): - data1 = self._decode_int8(valid_data[i : i + 1]) - res.append(0xFF & data1 if data1 < 0 else data1) - res.append(self._decode_int8(valid_data)) + data1 = self._decode_int8(valid_data[i: i + 1]) + decode_respond.append(0xFF & data1 if data1 < 0 else data1) + decode_respond.append(self._decode_int8(valid_data)) - if len(res) == 0: + return decode_respond + + def _parsing_parameters(self, genre, res): + if res is None: return None - + + if isinstance(res, int): + return res + if genre in [ ProtocolCode.ROBOT_VERSION, ProtocolCode.GET_ROBOT_ID, ProtocolCode.IS_POWER_ON, ProtocolCode.IS_CONTROLLER_CONNECTED, - ProtocolCode.IS_PAUSED, # TODO have bug: return b'' + ProtocolCode.IS_PAUSED, ProtocolCode.IS_IN_POSITION, ProtocolCode.IS_MOVING, ProtocolCode.IS_SERVO_ENABLE, @@ -192,11 +242,12 @@ def _mesg(self, genre, *args, **kwargs): ProtocolCode.GET_VR_MODE, ProtocolCode.GET_FILTER_LEN, ProtocolCode.IS_SERVO_ENABLE, - ProtocolCode.GET_POS_SWITCH + ProtocolCode.GET_POS_SWITCH, + ProtocolCode.GET_ERROR_INFO ]: return self._process_single(res) - elif genre in [ProtocolCode.GET_ANGLES]: - return [self._int2angle(angle) for angle in res] + elif genre in [ProtocolCode.GET_ANGLES, ProtocolCode.SOLVE_INV_KINEMATICS]: + return [self._int3angle(angle) for angle in res] elif genre in [ ProtocolCode.GET_COORDS, ProtocolCode.MERCURY_GET_BASE_COORDS, @@ -241,57 +292,129 @@ def _mesg(self, genre, *args, **kwargs): if res[i] == 1: r.append(i) return r - elif genre in [ProtocolCode.COBOTX_GET_ANGLE, ProtocolCode.COBOTX_GET_SOLUTION_ANGLES, ProtocolCode.GET_POS_OVER]: - return self._int2angle(res[0]) + elif genre in [ProtocolCode.COBOTX_GET_ANGLE, ProtocolCode.COBOTX_GET_SOLUTION_ANGLES, + ProtocolCode.GET_POS_OVER]: + return self._int2angle(res[0]) elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: - if len(res) == 23: - i = 9 - for i in range(9, len(res)): - if res[i] != 0: - data = bin(res[i])[2:] - res[i] = [] - while len(data) != 16: - data = "0"+data - for j in range(16): - if data[j] != "0": - res[i].append(15-j) - return res - else: - for i in range(10, len(res)): - if res[i] != 0: - data = bin(res[i])[2:] - res[i] = [] - while len(data) != 16: - data = "0"+data - for j in range(16): - if data[j] != "0": - res[i].append(15-j) - return res + for i in range(9, len(res)): + if res[i] != 0: + data = bin(res[i])[2:] + res[i] = [] + while len(data) != 16: + data = "0" + data + for j in range(16): + if data[j] != "0": + error_id = 15 - j + res[i].append(error_id) + if not res[i]: + res[i] = 0 + return res + elif genre == ProtocolCode.GET_MOTORS_RUN_ERR: + for i in range(len(res)): + if res[i] != 0: + data = bin(res[i])[2:] + res[i] = [] + while len(data) != 16: + data = "0" + data + for j in range(16): + if data[j] != "0": + error_id = 15 - j + res[i].append(error_id) + if not res[i]: + res[i] = 0 + return res else: return res + def _mesg(self, genre, *args, **kwargs): + read_data = super(Pro630Api, self)._mesg(genre, *args, **kwargs) + decode_result = self._decode_command(genre, read_data) + return self._parsing_parameters(genre, decode_result) + + def _joint_limit_init(self): + for joint, index in enumerate(range(6), start=1): + if self._joint_max_angles[index] is None: + angle = self.get_joint_max_angle(joint) + self._joint_max_angles[index] = angle + if self._joint_min_angles[index] is None: + angle = self.get_joint_min_angle(joint) + self._joint_min_angles[index] = angle + + def _joint_limit_judge(self, angles): + offset = 3 + try: + for joint, angle in enumerate(angles, start=1): + min_angle = self._joint_min_angles[joint - 1] + max_angle = self._joint_max_angles[joint - 1] + if min_angle + offset < angle < max_angle - offset: + continue + + if self.language == "zh_CN": + return f"当前关节{joint}角度为{angle}, 角度范围为: {min_angle} ~ {max_angle}" + return f"The angle of the current joint {joint} is {angle}, and the angle range is: {min_angle} ~ {max_angle}" + except TypeError: + return "joint limit error" + return "over limit error {}".format(angles) + + def _check_coords(self, new_coords, is_print=False): + if isinstance(new_coords, list): + return "check coords error" + + error_info = "" + first_three = new_coords[:3] + first_three[2] -= 83.64 + + magnitude = np.linalg.norm(first_three) # Calculate the Euclidean norm (magnitude) + if is_print == 1: + if self.language == "zh_CN": + error_info += f"当前臂展为{magnitude}, 最大的臂展为{self.arm_span_maximum}" + else: + error_info += f"Arm span is {magnitude}, max is {self.arm_span_maximum}" + + return error_info + + def _status_explain(self, status): + error_info = _interpret_status_code(self.language, status) + if 0x00 < status <= 0x07: + self._joint_limit_init() + angles = self.get_angles() + error_info += self._joint_limit_judge(angles) + elif status in [32, 33]: + error_coords = self.get_coords() + error_info += self._check_coords(error_coords, is_print=True) + elif status == 36: + angles = self.get_angles() + if self.language == "zh_CN": + error_info += f"当前角度为{angles}, 检测到奇异点" + else: + error_info += f"The current angle is {angles}, and a singularity is detected" + return error_info + + +class Pro630(Pro630Api): + def open(self): self._serial_port.open() - + def close(self): self._serial_port.close() - + def power_on(self, delay=2): import RPi.GPIO as GPIO GPIO.output(self.power_control_2, GPIO.HIGH) time.sleep(delay) return super(Pro630, self).power_on() - + def power_off(self): import RPi.GPIO as GPIO res = super(Pro630, self).power_off() GPIO.output(self.power_control_2, GPIO.LOW) return res - + def power_on_only(self): import RPi.GPIO as GPIO GPIO.output(self.power_control_2, GPIO.HIGH) - + def set_basic_output(self, pin_no, pin_signal): """Set basic output.IO low-level output high-level, high-level output high resistance state @@ -300,66 +423,36 @@ def set_basic_output(self, pin_no, pin_signal): pin_signal: 0 / 1 """ import RPi.GPIO as GPIO - if pin_no == 1: - pin_no = 17 - elif pin_no == 2: - pin_no = 27 - elif pin_no == 3: - pin_no = 22 - elif pin_no == 4: - pin_no = 5 - elif pin_no == 5: - pin_no = 6 - elif pin_no == 6: - pin_no = 19 - GPIO.setup(pin_no, GPIO.OUT) - GPIO.output(pin_no, pin_signal) - + pin_number = self.pin_numbered_mapping_table.get(pin_no, None) + if pin_number is None: + raise ValueError("pin_no must be in range 1 ~ 6") + GPIO.setup(pin_number, GPIO.OUT) + GPIO.output(pin_number, pin_signal) + def get_basic_input(self, pin_no): """Get basic input. Args: pin_no: pin port number. range 1 ~ 6 - + Return: 1 - high 0 - low """ import RPi.GPIO as GPIO - if pin_no == 1: - pin_no = 26 - elif pin_no == 2: - pin_no = 21 - elif pin_no == 3: - pin_no = 20 #23 - elif pin_no == 4: - pin_no = 16 - elif pin_no == 5: - pin_no = 24 - elif pin_no == 6: - pin_no = 23 - GPIO.setup(pin_no, GPIO.IN) - return GPIO.input(pin_no) - + pin_number = self.pin_numbered_mapping_table.get(pin_no, None) + if pin_number is None: + raise ValueError("pin_no must be in range 1 ~ 6") + GPIO.setup(pin_number, GPIO.IN) + return GPIO.input(pin_number) + def send_angles_sync(self, angles, speed): - self.calibration_parameters(class_name = self.__class__.__name__, angles=angles, speed=speed) angles = [self._angle2int(angle) for angle in angles] + self.calibration_parameters(class_name=self.__class__.__name__, angles=angles, speed=speed) return self._mesg(ProtocolCode.SEND_ANGLES, angles, speed, no_return=True) - - def set_pos_switch(self, mode): - """Set position switch mode. - Args: - mode: 0 - switch off, 1 - switch on - """ - if mode == 0: - return self._mesg(ProtocolCode.SET_POS_SWITCH, mode, asyn_mode=True) - return self._mesg(ProtocolCode.SET_POS_SWITCH, mode,asyn_mode=False) - - def get_pos_switch(self): - """Get position switch mode. + def set_monitor_mode(self, mode): + raise NotImplementedError("Pro630 does not support monitor mode") - Return: - 1 - switch on, 0 - switch off - """ - return self._mesg(ProtocolCode.GET_POS_SWITCH, has_reply=True) \ No newline at end of file + def get_monitor_mode(self): + raise NotImplementedError("Pro630 does not support monitor mode") diff --git a/pymycobot/pro630client.py b/pymycobot/pro630client.py index 602b22fe..a024e587 100644 --- a/pymycobot/pro630client.py +++ b/pymycobot/pro630client.py @@ -1,6 +1,4 @@ # coding=utf-8 - -import time import threading import socket @@ -296,22 +294,9 @@ def send_angles_sync(self, angles, speed): self.calibration_parameters(class_name = self.__class__.__name__, angles=angles, speed=speed) angles = [self._angle2int(angle) for angle in angles] return self._mesg(ProtocolCode.SEND_ANGLES, angles, speed, no_return=True) - - def set_pos_switch(self, mode): - """Set position switch mode. - Args: - mode: 0 - switch off, 1 - switch on - """ - if mode == 0: - return self._mesg(ProtocolCode.SET_POS_SWITCH, mode, asyn_mode=True) - return self._mesg(ProtocolCode.SET_POS_SWITCH, mode,asyn_mode=False) - - - def get_pos_switch(self): - """Get position switch mode. + def set_monitor_mode(self, mode): + raise NotImplementedError("Pro630 does not support monitor mode") - Return: - 1 - switch on, 0 - switch off - """ - return self._mesg(ProtocolCode.GET_POS_SWITCH, has_reply=True) + def get_monitor_mode(self): + raise NotImplementedError("Pro630 does not support monitor mode") \ No newline at end of file diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 57682d3f..d1cdaefb 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -399,5 +399,14 @@ class RobotLimit: "left_coords_max": [250, 260, 480, 180, 180, 180], "right_coords_min": [0, -260, 0, -180, -180, -180], "right_coords_max": [250, 40, 480, 180, 180, 180] + }, + "Pro630": { + "joint_id": [1, 2, 3, 4, 5, 6], + "servo_id": [1, 2, 3, 4, 5, 6], + "coord_id": (1, 2, 3, 4, 5, 6), + "angles_min": [-180, -45, -165, -90, -180, -180], + "angles_max": [180, 225, 165, 270, 180, 180], + "coords_min": [-630, -630, -425, -180, -180, -180], + "coords_max": [630, 630, 835, 180, 180, 180] } } From a6f705353fea6e1a217eb8c4a9916489c5ae3ec6 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 15 Apr 2025 13:52:32 +0800 Subject: [PATCH 21/57] Fixed the pro630 socket communication bug --- demo/Server_Pro630.py | 89 +++++++---- pymycobot/error.py | 2 +- pymycobot/pro630.py | 34 ++-- pymycobot/pro630client.py | 323 +++++++------------------------------- 4 files changed, 130 insertions(+), 318 deletions(-) diff --git a/demo/Server_Pro630.py b/demo/Server_Pro630.py index 17508f2b..7f1d0906 100644 --- a/demo/Server_Pro630.py +++ b/demo/Server_Pro630.py @@ -11,6 +11,8 @@ import traceback import RPi.GPIO as GPIO import threading + + class ProtocolCode(object): # BASIC HEADER = 0xFE @@ -22,14 +24,14 @@ class ProtocolCode(object): GET_ROBOT_ID = 0x03 OVER_LIMIT_RETURN_ZERO = 0x04 SET_ROBOT_ID = 0x04 - + GET_ERROR_INFO = 0x07 CLEAR_ERROR_INFO = 0x08 GET_ATOM_VERSION = 0x09 - + SET_POS_SWITCH = 0x0B GET_POS_SWITCH = 0x0C - + SetHTSGripperTorque = 0x35 GetHTSGripperTorque = 0x36 GetGripperProtectCurrent = 0x37 @@ -81,10 +83,10 @@ class ProtocolCode(object): JOG_INCREMENT = 0x33 JOG_STOP = 0x34 JOG_INCREMENT_COORD = 0x34 - + COBOTX_GET_SOLUTION_ANGLES = 0x35 COBOTX_SET_SOLUTION_ANGLES = 0x36 - + SET_ENCODER = 0x3A GET_ENCODER = 0x3B SET_ENCODERS = 0x3C @@ -114,8 +116,7 @@ class ProtocolCode(object): SET_GRIPPER_ENABLED = 0x58 GET_ZERO_POS = 0x59 IS_INIT_CALIBRATION = 0x5A - - + # ATOM IO SET_PIN_MODE = 0x60 SET_DIGITAL_OUTPUT = 0x61 @@ -148,7 +149,6 @@ class ProtocolCode(object): SET_MODEL_DIRECTION = 0x7D GET_FILTER_LEN = 0x7E SET_FILTER_LEN = 0x7F - # Basic SET_BASIC_OUTPUT = 0xA0 @@ -228,12 +228,12 @@ class ProtocolCode(object): SET_VOID_COMPENSATE = 0xE7 SET_ERROR_DETECT_MODE = 0xE8 GET_ERROR_DETECT_MODE = 0xE9 - + MERCURY_GET_BASE_COORDS = 0xF0 MERCURY_SET_BASE_COORD = 0xF1 MERCURY_SET_BASE_COORDS = 0xF2 MERCURY_JOG_BASE_COORD = 0xF3 - + MERCURY_DRAG_TECH_SAVE = 0x70 MERCURY_DRAG_TECH_EXECUTE = 0x71 MERCURY_DRAG_TECH_PAUSE = 0x72 @@ -277,8 +277,25 @@ class ProtocolCode(object): CLEAR_ROBOT_ERROR = 0x16 GET_RECV_QUEUE_SIZE = 0x17 SET_RECV_QUEUE_SIZE = 0x18 -has_return = [0x02, 0x03, 0x04, 0x09, 0x10, 0x11, 0x12, 0x13, 0x1c, 0x18, 0x19, 0x20, 0x23, 0x27, 0x29, 0x2A, 0x2B, 0x35, 0x4A, 0x4B,0x4C, 0x4D, - 0x50, 0x51, 0x56,0x57, 0x59,0x5A,0x62, 0x82, 0x84, 0x86, 0x88, 0x8A, 0xA1, 0xA2, 0xB2, 0xB3, 0xB4, 0xB5, 0xB7, 0xD6, 0xe1, 0xe2, 0xe4, 0xC] + + +has_return = [ + 0x02, 0x03, 0x04, 0x09, 0x10, 0x11, 0x12, 0x13, 0x1c, 0x18, 0x19, 0x20, 0x23, 0x27, 0x29, 0x2A, 0x2B, 0x35, 0x4A, + 0x4B, 0x4C, 0x4D, + 0x50, 0x51, 0x56, 0x57, 0x59, 0x5A, 0x62, 0x82, 0x84, 0x86, 0x88, 0x8A, 0xA1, 0xA2, 0xB2, 0xB3, + 0xB4, 0xB5, 0xB7, 0xD6, 0xe1, 0xe2, 0xe4, 0xC, 0x9C +] + +has_closed_loop = [ + ProtocolCode.SEND_ANGLE, + ProtocolCode.SEND_ANGLES, + ProtocolCode.SEND_COORD, + ProtocolCode.SEND_COORDS, + ProtocolCode.JOG_INCREMENT, + ProtocolCode.JOG_INCREMENT_COORD, + ProtocolCode.COBOTX_SET_SOLUTION_ANGLES +] + def get_logger(name): logger = logging.getLogger(name) @@ -299,10 +316,11 @@ def get_logger(name): logger.addHandler(console) return logger + class pro630Server(object): - + def __init__(self, host, port, serial_num="/dev/ttyAMA0", baud=115200) -> None: - + self.logger = get_logger("AS") self.mc = None self.serial_num = serial_num @@ -320,22 +338,20 @@ def __init__(self, host, port, serial_num="/dev/ttyAMA0", baud=115200) -> None: GPIO.setup(self.power_control_1, GPIO.IN) GPIO.setup(self.power_control_2, GPIO.OUT) self.conn = None - check_mode = [0xfe,0xfe,0x3,0xc,0xc9,0x50] + check_mode = [0xfe, 0xfe, 0x3, 0xc, 0xc9, 0x50] self.connected = True - self.asynchronous=False + self.asynchronous = False self.mc.write(check_mode) res = self.read(check_mode) self.connected = False - - + if len(res) > 5 and res[4] == 0: print("This is asynchronous mode") - self.asynchronous=True + self.asynchronous = True else: print("This is synchronous mode") - self.asynchronous=False + self.asynchronous = False self.connect() - def connect(self): while True: @@ -395,12 +411,12 @@ def connect(self): continue elif command[3] == 161: pin_no = command[4] - if pin_no == 1: + if pin_no == 1: pin_no = 26 elif pin_no == 2: pin_no = 21 elif pin_no == 3: - pin_no = 20 #23 + pin_no = 20 # 23 elif pin_no == 4: pin_no = 16 elif pin_no == 5: @@ -409,8 +425,8 @@ def connect(self): pin_no = 23 GPIO.setup(pin_no, GPIO.IN) statue = GPIO.input(pin_no) - res = command[:-2]+[statue] - res+=self.crc_check(res) + res = command[:-2] + [statue] + res += self.crc_check(res) self.conn.sendall(bytearray(res)) continue self.write(command) @@ -421,7 +437,8 @@ def connect(self): elif command[4] == 0: # 关闭闭环 self.asynchronous = True - if command[3] in has_return or (command[3] in [ProtocolCode.SEND_ANGLE, ProtocolCode.SEND_ANGLES, ProtocolCode.SEND_COORD, ProtocolCode.SEND_COORDS, ProtocolCode.JOG_INCREMENT, ProtocolCode.JOG_INCREMENT_COORD, ProtocolCode.COBOTX_SET_SOLUTION_ANGLES] and self.asynchronous == False): + if command[3] in has_return or ( + command[3] in has_closed_loop and self.asynchronous is False): # res = self.read(command) self.read_thread = threading.Thread(target=self.read, args=(command,), daemon=True) self.read_thread.start() @@ -436,7 +453,7 @@ def connect(self): self.connected = False self.conn.close() self.mc.close() - + def _encode_int16(self, data): if isinstance(data, int): return [ @@ -449,15 +466,15 @@ def _encode_int16(self, data): t = self._encode_int16(v) res.extend(t) return res - - @classmethod + + @classmethod def crc_check(cls, command): crc = 0xffff for index in range(len(command)): crc ^= command[index] for _ in range(8): if crc & 1 == 1: - crc >>= 1 + crc >>= 1 crc ^= 0xA001 else: crc >>= 1 @@ -481,7 +498,9 @@ def read(self, command): wait_time = 8 elif command[3] in [0x11, 0x13, 0x18, 0x56, 0x57, 0x29]: wait_time = 3 - elif command[3] in [ProtocolCode.SEND_ANGLE, ProtocolCode.SEND_ANGLES, ProtocolCode.SEND_COORD, ProtocolCode.SEND_COORDS, ProtocolCode.JOG_INCREMENT, ProtocolCode.JOG_INCREMENT_COORD, ProtocolCode.COBOTX_SET_SOLUTION_ANGLES] and self.asynchronous == False: + elif command[3] in [ProtocolCode.SEND_ANGLE, ProtocolCode.SEND_ANGLES, ProtocolCode.SEND_COORD, + ProtocolCode.SEND_COORDS, ProtocolCode.JOG_INCREMENT, ProtocolCode.JOG_INCREMENT_COORD, + ProtocolCode.COBOTX_SET_SOLUTION_ANGLES] and self.asynchronous == False: wait_time = 300 while True and time.time() - t < wait_time and self.connected: data = self.mc.read() @@ -493,7 +512,7 @@ def read(self, command): datas += data crc = self.mc.read(2) if self.crc_check(datas) == [v for v in crc]: - datas+=crc + datas += crc break if data_len == 1 and data == b"\xfa": datas += data @@ -527,11 +546,13 @@ def read(self, command): else: datas = b"\xfe" pre = k + else: + time.sleep(0.001) else: datas = b'' if self.conn is not None: self.logger.info("return datas: {}".format([hex(v) for v in datas])) - + self.conn.sendall(datas) datas = b'' return datas @@ -552,4 +573,4 @@ def re_data_2(self, command): # HOST = "localhost" PORT = 9000 print("ip: {} port: {}".format(HOST, PORT)) - pro630Server(HOST, PORT) \ No newline at end of file + pro630Server(HOST, PORT) diff --git a/pymycobot/error.py b/pymycobot/error.py index 6f5a61a5..a95c6b92 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1426,7 +1426,7 @@ def calibration_parameters(**kwargs): if not 0 <= v <= 255: raise ValueError(f"rgb value not right, should be 0 ~ 255, the received rgb is {value}") - elif class_name in ["Pro630"]: + elif class_name in ["Pro630", "Pro630Client"]: limit_info = robot_limit[class_name] for parameter, value in kwargs.items(): value_type = type(value) diff --git a/pymycobot/pro630.py b/pymycobot/pro630.py index f11cc3f4..4d32973f 100644 --- a/pymycobot/pro630.py +++ b/pymycobot/pro630.py @@ -41,38 +41,21 @@ class Pro630Api(CloseLoop): 6: 19 } - def __init__(self, port, baudrate="115200", timeout=0.1, debug=False, save_serial_log=False): - """ - Args: - port : port string - baudrate : baud rate string, default '115200' - timeout : default 0.1 - debug : whether show debug info - """ + def __init__(self, debug=False, save_serial_log=False, method=None): super(Pro630Api, self).__init__(debug) - import RPi.GPIO as GPIO - - GPIO.setmode(GPIO.BCM) - GPIO.setwarnings(False) - GPIO.setup(self.power_control_1, GPIO.IN) - GPIO.setup(self.power_control_2, GPIO.OUT) - + self._joint_max_angles = [0] * self.joint_number + self._joint_min_angles = [0] * self.joint_number self.save_serial_log = save_serial_log - self._serial_port = setup_serial_connect(port, baudrate, timeout) self.calibration_parameters = calibration_parameters self.language = get_local_language() - self.lock = threading.Lock() self.lock_out = threading.Lock() - self.read_threading = threading.Thread(target=self.read_thread) + self.read_threading = threading.Thread(target=self.read_thread, args=(method, )) self.read_threading.daemon = True self.read_threading.start() - self._joint_max_angles = [0] * self.joint_number - self._joint_min_angles = [0] * self.joint_number - def _decode_command(self, genre, read_data): if read_data is None: return None @@ -393,6 +376,15 @@ def _status_explain(self, status): class Pro630(Pro630Api): + def __init__(self, port, baudrate="115200", timeout=0.1, debug=False, save_serial_log=False): + self._serial_port = setup_serial_connect(port, baudrate, timeout) + super(Pro630, self).__init__(debug, save_serial_log) + import RPi.GPIO as GPIO + GPIO.setmode(GPIO.BCM) + GPIO.setwarnings(False) + GPIO.setup(self.power_control_1, GPIO.IN) + GPIO.setup(self.power_control_2, GPIO.OUT) + def open(self): self._serial_port.open() diff --git a/pymycobot/pro630client.py b/pymycobot/pro630client.py index a024e587..aef23c3a 100644 --- a/pymycobot/pro630client.py +++ b/pymycobot/pro630client.py @@ -1,274 +1,73 @@ # coding=utf-8 -import threading import socket +import sys +import time +import traceback -from pymycobot.close_loop import CloseLoop -from pymycobot.error import calibration_parameters +from pymycobot.pro630 import Pro630Api from pymycobot.common import ProtocolCode +SYS_VERSION_INFO = sys.version_info.major -class Pro630Client(CloseLoop): - def __init__(self, ip, netport=9000, debug=False): - """ - Args: - port : port string - baudrate : baud rate string, default '115200' - timeout : default 0.1 - debug : whether show debug info - """ - super(Pro630Client, self).__init__(debug) - self.calibration_parameters = calibration_parameters - self.SERVER_IP = ip - self.SERVER_PORT = netport - self.sock = self.connect_socket() - self.lock = threading.Lock() - self.lock_out = threading.Lock() - self.is_stop = False - self.read_threading = threading.Thread(target=self.read_thread, args=("socket",)) - self.read_threading.daemon = True - self.read_threading.start() - def connect_socket(self): - sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - sock.connect((self.SERVER_IP, self.SERVER_PORT)) - return sock - - def _mesg(self, genre, *args, **kwargs): - read_data = super(Pro630Client, self)._mesg(genre, *args, **kwargs) - if read_data is None: - return None +def format_hex_log(data): + if SYS_VERSION_INFO == 2: + command_log = "" + for d in data: + command_log += hex(ord(d))[2:] + " " + else: + command_log = "" + for d in data: + command_log += hex(d)[2:] + " " + + return command_log - if isinstance(read_data, int): - return read_data - valid_data, data_len = read_data - res = [] - if data_len in [8, 12, 14, 16, 26, 60]: - if data_len == 8 and (genre == ProtocolCode.IS_INIT_CALIBRATION): - if valid_data[0] == 1: - return 1 - n = len(valid_data) - for v in range(1,n): - res.append(valid_data[v]) - elif data_len == 8 and genre == ProtocolCode.GET_DOWN_ENCODERS: - res = self.bytes4_to_int(valid_data) - elif data_len == 6 and genre in [ProtocolCode.GET_SERVO_STATUS, ProtocolCode.GET_SERVO_VOLTAGES, ProtocolCode.GET_SERVO_CURRENTS]: - for i in range(data_len): - res.append(valid_data[i]) - elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: - res.extend(valid_data[:8]) - data = valid_data[8:20] - for header_i in range(0, len(data), 2): - one = data[header_i: header_i + 2] - res.append(self._decode_int16(one)) - res.extend(valid_data[20:26]) - return res - else: - for header_i in range(0, len(valid_data), 2): - one = valid_data[header_i : header_i + 2] - res.append(self._decode_int16(one)) - elif data_len == 2: - if genre in [ProtocolCode.IS_SERVO_ENABLE]: - return [self._decode_int8(valid_data[1:2])] - elif genre in [ProtocolCode.GET_ERROR_INFO]: - return [self._decode_int8(valid_data[1:])] - res.append(self._decode_int16(valid_data)) - elif data_len == 3: - res.append(self._decode_int16(valid_data[1:])) - elif data_len == 4: - if genre == ProtocolCode.COBOTX_GET_ANGLE: - res = self.bytes4_to_int(valid_data) - for i in range(1,4): - res.append(valid_data[i]) - elif data_len == 7: - error_list = [i for i in valid_data] - for i in error_list: - if i in range(16,23): - res.append(1) - elif i in range(23,29): - res.append(2) - elif i in range(32,112): - res.append(3) - else: - res.append(i) - elif data_len == 24: - res = self.bytes4_to_int(valid_data) - elif data_len == 40: - i = 0 - while i < data_len: - if i < 28: - res += self.bytes4_to_int(valid_data) - i+=4 - else: - one = valid_data[i : i + 2] - res.append(self._decode_int16(one)) - i+=2 - elif data_len == 30: - i = 0 - res = [] - while i < 30: - if i < 9 or i >= 23: - res.append(valid_data[i]) - i+=1 - elif i < 23: - one = valid_data[i : i + 2] - res.append(self._decode_int16(one)) - i+=2 - elif data_len == 38: - i = 0 - res = [] - while i < data_len: - if i < 10 or i >= 30: - res.append(valid_data[i]) - i+=1 - elif i < 38: - one = valid_data[i : i + 2] - res.append(self._decode_int16(one)) - i+=2 - # elif data_len == 56: - # for i in range(0, data_len, 8): - - # byte_value = int.from_bytes(valid_data[i:i+4], byteorder='big', signed=True) - # res.append(byte_value) - elif data_len == 6: - for i in valid_data: - res.append(i) - else: - if genre in [ - ProtocolCode.GET_SERVO_VOLTAGES, - ProtocolCode.GET_SERVO_STATUS, - ProtocolCode.GET_SERVO_TEMPS, - ]: - for i in range(data_len): - data1 = self._decode_int8(valid_data[i : i + 1]) - res.append(0xFF & data1 if data1 < 0 else data1) - res.append(self._decode_int8(valid_data)) +def connect_socket(addr, port): + sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + sock.connect((addr, port)) + return sock - if len(res) == 0: - return None - - if genre in [ - ProtocolCode.ROBOT_VERSION, - ProtocolCode.GET_ROBOT_ID, - ProtocolCode.IS_POWER_ON, - ProtocolCode.IS_CONTROLLER_CONNECTED, - ProtocolCode.IS_PAUSED, # TODO have bug: return b'' - ProtocolCode.IS_IN_POSITION, - ProtocolCode.IS_MOVING, - ProtocolCode.IS_SERVO_ENABLE, - ProtocolCode.IS_ALL_SERVO_ENABLE, - ProtocolCode.GET_SERVO_DATA, - ProtocolCode.GET_DIGITAL_INPUT, - ProtocolCode.GET_GRIPPER_VALUE, - ProtocolCode.IS_GRIPPER_MOVING, - ProtocolCode.GET_SPEED, - ProtocolCode.GET_ENCODER, - ProtocolCode.GET_BASIC_INPUT, - ProtocolCode.GET_TOF_DISTANCE, - ProtocolCode.GET_END_TYPE, - ProtocolCode.GET_MOVEMENT_TYPE, - ProtocolCode.GET_REFERENCE_FRAME, - ProtocolCode.GET_FRESH_MODE, - ProtocolCode.GET_GRIPPER_MODE, - ProtocolCode.SET_SSID_PWD, - ProtocolCode.GET_ERROR_DETECT_MODE, - ProtocolCode.POWER_ON, - ProtocolCode.POWER_OFF, - ProtocolCode.RELEASE_ALL_SERVOS, - ProtocolCode.RELEASE_SERVO, - ProtocolCode.FOCUS_ALL_SERVOS, - ProtocolCode.FOCUS_SERVO, - ProtocolCode.STOP, - ProtocolCode.SET_BREAK, - ProtocolCode.IS_BTN_CLICKED, - ProtocolCode.GET_CONTROL_MODE, - ProtocolCode.GET_VR_MODE, - ProtocolCode.GET_FILTER_LEN, - ProtocolCode.IS_SERVO_ENABLE, - ProtocolCode.GET_POS_SWITCH - ]: - return self._process_single(res) - elif genre in [ProtocolCode.GET_ANGLES]: - return [self._int2angle(angle) for angle in res] - elif genre in [ - ProtocolCode.GET_COORDS, - ProtocolCode.MERCURY_GET_BASE_COORDS, - ProtocolCode.GET_TOOL_REFERENCE, - ProtocolCode.GET_WORLD_REFERENCE, - ]: - if res: - r = [] - for idx in range(3): - r.append(self._int2coord(res[idx])) - for idx in range(3, 6): - r.append(self._int2angle(res[idx])) - return r - else: - return res - elif genre in [ProtocolCode.GET_SERVO_VOLTAGES]: - return [self._int2coord(angle) for angle in res] - elif genre in [ProtocolCode.GET_BASIC_VERSION, ProtocolCode.SOFTWARE_VERSION, ProtocolCode.GET_ATOM_VERSION]: - return self._int2coord(self._process_single(res)) - elif genre in [ - ProtocolCode.GET_JOINT_MAX_ANGLE, - ProtocolCode.GET_JOINT_MIN_ANGLE, - ]: - return self._int2coord(res[0]) - elif genre == ProtocolCode.GET_ANGLES_COORDS: - r = [] - for index in range(len(res)): - if index < 7: - r.append(self._int2angle(res[index])) - elif index < 10: - r.append(self._int2coord(res[index])) - else: - r.append(self._int2angle(res[index])) - return r - elif genre == ProtocolCode.GO_ZERO: - r = [] - if res: - if 1 not in res[1:]: - return res[0] - else: - for i in range(1, len(res)): - if res[i] == 1: - r.append(i) - return r - elif genre in [ProtocolCode.COBOTX_GET_ANGLE, ProtocolCode.COBOTX_GET_SOLUTION_ANGLES, ProtocolCode.GET_POS_OVER]: - return self._int2angle(res[0]) - elif genre == ProtocolCode.MERCURY_ROBOT_STATUS: - if len(res) == 23: - i = 9 - for i in range(9, len(res)): - if res[i] != 0: - data = bin(res[i])[2:] - res[i] = [] - while len(data) != 16: - data = "0"+data - for j in range(16): - if data[j] != "0": - res[i].append(15-j) - return res - else: - for i in range(10, len(res)): - if res[i] != 0: - data = bin(res[i])[2:] - res[i] = [] - while len(data) != 16: - data = "0"+data - for j in range(16): - if data[j] != "0": - res[i].append(15-j) - return res - else: - return res - def open(self): - self.sock = self.connect_socket() - +class Pro630Client(Pro630Api): + def __init__(self, host, port=9000, timeout=0.1, debug=False): + """ + Args: + host: host address + port: port number + timeout: socket timeout + debug: debug mode + """ + self.sock = connect_socket(host, port) + self.timeout = timeout + self.host = host + self.port = port + super().__init__(debug=debug, method='socket') + def close(self): self.sock.close() - + + def read_thread(self, method=None): + self.sock.settimeout(self.timeout) + while True: + try: + data = self.sock.recv(1024) + print(data) + result = self._process_received(data) + command_log = format_hex_log(result) + self.log.debug(f"_read :{command_log}") + if not result: + continue + + with self.lock: + self.read_command.append([result, time.time()]) + except socket.timeout: + print("socket timeout") + time.sleep(0.1) + except Exception as e: + print(e) + traceback.print_exc() + def set_basic_output(self, pin_no, pin_signal): """Set basic output.IO low-level output high-level, high-level output high resistance state @@ -276,8 +75,8 @@ def set_basic_output(self, pin_no, pin_signal): pin_no: pin port number. range 1 ~ 6 pin_signal: 0 / 1 """ - return super(Pro630Client, self).set_basic_output(pin_no, pin_signal) - + return self._mesg(ProtocolCode.SET_BASIC_OUTPUT, pin_no, pin_signal) + def get_basic_input(self, pin_no): """Get basic input. @@ -288,8 +87,8 @@ def get_basic_input(self, pin_no): 1 - high 0 - low """ - return super(Pro630Client, self).get_basic_input(pin_no) - + return self._mesg(ProtocolCode.GET_BASIC_INPUT, pin_no) + def send_angles_sync(self, angles, speed): self.calibration_parameters(class_name = self.__class__.__name__, angles=angles, speed=speed) angles = [self._angle2int(angle) for angle in angles] From fb747645a628d4ca4f22964c0072b1a69c59a174 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 8 May 2025 12:02:37 +0800 Subject: [PATCH 22/57] Optimize MyCobot280 RDK X5 interface parameter error prompt --- pymycobot/error.py | 111 +++++ pymycobot/mycobot280rdkx5.py | 776 +++++++++++++++++++++++++---------- pymycobot/robot_info.py | 118 +++--- 3 files changed, 725 insertions(+), 280 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index a95c6b92..3696e64a 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -278,6 +278,8 @@ def public_check(parameter_list, kwargs, robot_limit, class_name, exception_clas elif parameter == "pin_no": if "Mercury" in class_name: check_0_or_1(parameter, value, [1, 2, 3, 4, 5, 6], value_type, exception_class, int) + + def calibration_parameters(**kwargs): # with open(os.path.dirname(os.path.abspath(__file__))+"/robot_limit.json") as f: robot_limit = RobotLimit.robot_limit @@ -1481,6 +1483,115 @@ def calibration_parameters(**kwargs): if not 1 <= s <= 100: raise ValueError( f"speed value not right, should be 1 ~ 100, the received speed is {value}") + elif class_name in ("MyCobot280RDK-X5", ): + robotic_limit_table = RobotLimit.robot_limit["MyCobot280RDK-X5"] + kwargs.pop("class_name", None) + for parameter, value in kwargs.items(): + if value is None: + continue + + if parameter in ("servo_id", "joint_id", "coord_id"): + servo_ids = robot_limit[class_name][parameter] + if value not in servo_ids: + raise ValueError(f"The {parameter} not right, should be in {servo_ids}, but received {value}.") + + elif parameter in ('angle', 'coord'): + if parameter == "angle": + _id = kwargs.get("joint_id") + else: + _id = kwargs.get("coord_id") + + index = _id - 1 + minimum_position = robotic_limit_table[f"{parameter}s_min"][index] + maximum_position = robotic_limit_table[f"{parameter}s_max"][index] + if not minimum_position <= value <= maximum_position: + raise ValueError( + f"The {parameter} not right, should be in {minimum_position} ~ {maximum_position}, but received {value}." + ) + + elif parameter in ('angles', 'coords'): + if len(value) != 6: + raise ValueError(f"The length of `{parameter}` must be 6.") + minimum_position = robotic_limit_table[f"{parameter}_min"] + maximum_position = robotic_limit_table[f"{parameter}_max"] + for index, angle in enumerate(value): + min_pos = minimum_position[index] + max_pos = maximum_position[index] + if not min_pos <= angle <= max_pos: + raise ValueError( + f"The {parameter} not right, should be in {min_pos} ~ {max_pos}, but received {angle}." + ) + + elif parameter == "speed": + if not 1 <= value <= 100: + raise ValueError(f"speed value not right, should be 1 ~ 100, the received speed is {value}") + + elif parameter == "speeds": + if len(value) != 6: + raise ValueError("The length of `speeds` must be 6.") + + for speed in value: + if not 1 <= speed <= 100: + raise ValueError(f"speed value not right, should be 1 ~ 100, the received speed is {speed}") + + elif parameter == 'encoder': + if not 0 <= value <= 4096: + raise ValueError(f"The range of encoder is 0 ~ 4096, but the received value is {value}") + + elif parameter == 'encoders': + if not len(value) == 6: + raise ValueError(f"The length of encoders is 6, but the received value is {len(value)}") + + for encoder in value: + if not 0 <= encoder <= 4096: + raise ValueError(f"The range of encoder is 0 ~ 4096, but the received value is {encoder}") + elif parameter == "drag_speeds": + if len(value) != 6: + raise ValueError("The length of `speeds` must be 6.") + + for speed in value: + if not 1 <= speed <= 10000: + raise ValueError(f"speed value not right, should be 1 ~ 10000, the received speed is {speed}") + + elif parameter in ( + "monitor_state", "fresh_mode", "vision_mode", "move_type", "pin_signal", "transponder_mode", + "reference_frame_type", "end_type", "direction", "coord_mode" + ): + if value not in (0, 1): + raise ValueError(f"The {parameter} not right, should be in (0, 1), but received {value}.") + + elif parameter == "gripper_state": + if value not in (0, 1, 254): + raise ValueError(f"The {parameter} not right, should be in (0, 1, 254), but received {value}.") + + elif parameter == "gripper_speed": + if not 0 <= value <= 100: + raise ValueError(f"The gripper_speed value not right, should be 0 ~ 100, the received speed is {value}") + elif parameter == "gripper_torque": + if not 150 <= value <= 980: + raise ValueError(f"The gripper_torque value not right, should be 150 ~ 980, the received speed is {value}") + elif parameter == "gripper_type": + gripper_types = (1, 2, 3, 4) + if value not in gripper_types: + raise ValueError(f"The gripper_type not right, should be in {gripper_types}, but received {value}.") + elif parameter == "is_torque": + torque_gripper_types = (0, 1) + if value not in torque_gripper_types: + raise ValueError(f"The is_torque not right, should be in {torque_gripper_types}, but received {value}.") + elif parameter == "value": + if not 0 <= value <= 4096: + raise ValueError(f"The value not right, should be 0 ~ 4096, but received {value}.") + elif parameter == "protect_current": + if not 1 <= value <= 500: + raise ValueError(f"The protect_current not right, should be 1 ~ 500, but received {value}.") + elif parameter == "end_direction": + if value not in (1, 2, 3): + raise ValueError(f"The end_direction not right, should be in (1, 2, 3), but received {value}.") + + elif parameter == "color": + for color in value: + if not 0 <= color <= 255: + raise ValueError(f"The color not right, should be 0 ~ 255, but received {color}.") def restrict_serial_port(func): diff --git a/pymycobot/mycobot280rdkx5.py b/pymycobot/mycobot280rdkx5.py index c11cae18..40ba6cca 100644 --- a/pymycobot/mycobot280rdkx5.py +++ b/pymycobot/mycobot280rdkx5.py @@ -8,7 +8,7 @@ import threading import serial -from pymycobot.generate import CommandGenerator +from pymycobot.generate import DataProcessor from pymycobot.common import ProtocolCode, write, read from pymycobot.error import calibration_parameters @@ -37,14 +37,19 @@ class GPIOProtocolCode: GET_GPIO_INPUT = 0xAD -class MyCobot280RDKX5Api(CommandGenerator): +class MyCobot280RDKX5Api(DataProcessor): def __init__(self, debug=False, thread_lock=True): super(MyCobot280RDKX5Api, self).__init__(debug) - self.calibration_parameters = functools.partial(calibration_parameters, class_name="MyCobot280") + self.calibration_parameters = functools.partial(self.parametric_verification, class_name="MyCobot280") self.thread_lock = thread_lock self.lock = threading.Lock() + @classmethod + def parametric_verification(cls, **kwargs): + kwargs["class_name"] = "MyCobot280RDK-X5" + return calibration_parameters(**kwargs) + def _mesg(self, genre, *args, **kwargs): """ @@ -168,7 +173,7 @@ def wait(self, t): class MyCobot280RDKX5CommandGenerator(MyCobot280RDKX5Api): - # System Status + # Overall Status def get_modify_version(self): """get modify version""" return self._mesg(ProtocolCode.ROBOT_VERSION) @@ -182,6 +187,7 @@ def clear_queue(self): return self._mesg(ProtocolCode.CLEAR_COMMAND_QUEUE) def get_queue_length(self): + """Get current queue length""" return self._mesg(ProtocolCode.GET_COMMAND_QUEUE) def async_or_sync(self): @@ -208,14 +214,15 @@ def clear_error_information(self): """Clear robot error message""" return self._mesg(ProtocolCode.CLEAR_ERROR_INFO, has_reply=True) - def set_monitor_state(self, state): + def set_monitor_state(self, monitor_state): """ Set the monitoring state Args: - state: 0 - Disable monitoring + monitor_state: 0 - Disable monitoring 1 - Enable monitoring """ - return self._mesg(ProtocolCode.SET_MONITOR_STATE, state) + self.calibration_parameters(monitor_state=monitor_state) + return self._mesg(ProtocolCode.SET_MONITOR_STATE, monitor_state) def get_monitor_state(self): """ @@ -245,7 +252,7 @@ def is_power_on(self): """ return self._mesg(ProtocolCode.IS_POWER_ON, has_reply=True) - def release_all_servos(self, data=None): + def release_all_servos(self): """Relax all joints""" return self._mesg(ProtocolCode.RELEASE_ALL_SERVOS) @@ -265,30 +272,117 @@ def read_next_error(self): """ return self._mesg(ProtocolCode.READ_NEXT_ERROR, has_reply=True) - def set_fresh_mode(self, mode): + def set_fresh_mode(self, fresh_mode): """Set command refresh mode Args: - mode: int. + fresh_mode: int. 1 - Always execute the latest command first. 0 - Execute instructions sequentially in the form of a queue. """ - self.calibration_parameters(mode=mode) - return self._mesg(ProtocolCode.SET_FRESH_MODE, mode) + self.calibration_parameters(fresh_mode=fresh_mode) + return self._mesg(ProtocolCode.SET_FRESH_MODE, fresh_mode) def get_fresh_mode(self): """Query sports mode""" return self._mesg(ProtocolCode.GET_FRESH_MODE, has_reply=True) - def set_vision_mode(self, flag): + def set_vision_mode(self, vision_mode): """Set the visual tracking mode to limit the posture flipping of send_coords in refresh mode. (Only for visual tracking function) Args: - flag: 0/1; 0 - close; 1 - open + vision_mode: 0/1; 0 - close; 1 - open + """ + self.calibration_parameters(vision_mode=vision_mode) + return self._mesg(ProtocolCode.SET_VISION_MODE, vision_mode) + + # Motion interface + def get_angles(self): + """ Get the angle of all joints. + + Return: + list: A float list of all angle. + """ + return self._mesg(ProtocolCode.GET_ANGLES, has_reply=True) + + def send_angle(self, joint_id, angle, speed, _async=False): + """Send one angle of joint to robot arm. + + Args: + joint_id : Joint id(genre.Angle) int 1-6. + angle : angle value(float). + speed : (int) 1 ~ 100 + _async: (default False) Whether to execute asynchronously, Currently invalid + """ + self.calibration_parameters(joint_id=joint_id, angle=angle, speed=speed) + return self._mesg(ProtocolCode.SEND_ANGLE, joint_id, [self._angle2int(angle)], speed, has_reply=True, _async=_async) + + def send_angles(self, angles, speed, _async=False): + """Send the angles of all joints to robot arm. + + Args: + angles: a list of angle values(List[float]). len 6. + speed : (int) 1 ~ 100 + _async: (default False) Whether to execute asynchronously, Currently invalid + """ + self.calibration_parameters(angles=angles, speed=speed) + angles = [self._angle2int(angle) for angle in angles] + return self._mesg(ProtocolCode.SEND_ANGLES, angles, speed, has_reply=True, _async=_async) + + def get_coords(self): + """Get the coords from robot arm, coordinate system based on base. + + Return: + list : A float list of coord .[x, y, z, rx, ry, rz] + """ + return self._mesg(ProtocolCode.GET_COORDS, has_reply=True) + + def angles_to_coords(self, angles): + """ Convert angles to coordinates + + Args: + angles : A float list of all angle. + + Return: + list: A float list of all coordinates. + """ + self.calibration_parameters(angles=angles) + angles = [self._angle2int(angle) for angle in angles] + return self._mesg(ProtocolCode.GET_COORDS, angles, has_reply=True) + + def send_coord(self, coord_id, coord, speed, _async=False): + """Send one coord to robot arm. + + Args: + coord_id(int) : coord id(genre.Coord) int 1-6. + coord(float) : coord value, mm + speed(int) : 1 ~ 100 + _async: (default False) Whether to execute asynchronously, Currently invalid """ - self.calibration_parameters(flag=flag) - return self._mesg(ProtocolCode.SET_VISION_MODE, flag) + self.calibration_parameters(coord_id=coord_id, coord=coord, speed=speed) + value = self._coord2int(coord) if coord_id <= 3 else self._angle2int(coord) + return self._mesg(ProtocolCode.SEND_COORD, coord_id, [value], speed, has_reply=True, _async=_async) + + def send_coords(self, coords, speed, coord_mode=None, _async=False): + """Send all coords to robot arm. + + Args: + coords: a list of coords value(List[float]).[x(mm), y, z, rx(angle), ry, rz]\n + speed : (int) 1 ~ 100 + coord_mode : (int) 0 - angluar, 1 - linear + _async: (default False) Whether to execute asynchronously, Currently invalid + """ + self.calibration_parameters(coords=coords, speed=speed, coord_mode=coord_mode) + coord_list = [] + for idx in range(3): + coord_list.append(self._coord2int(coords[idx])) + for angle in coords[3:]: + coord_list.append(self._angle2int(angle)) + if coord_mode is not None: + return self._mesg(ProtocolCode.SEND_COORDS, coord_list, speed, coord_mode, _async=_async) + else: + return self._mesg(ProtocolCode.SEND_COORDS, coord_list, speed, has_reply=True, _async=_async) def sync_send_angles(self, degrees, speed, timeout=15): """Send the angle in synchronous state and return when the target point is reached @@ -324,21 +418,76 @@ def sync_send_coords(self, coords, speed, mode=0, timeout=15): time.sleep(0.1) return 1 - def get_angles_coords(self): - """Get joint angles and coordinates""" - return self._mesg(ProtocolCode.GET_ANGLES_COORDS, has_reply=True) + def pause(self): + """Pause movement""" + return self._mesg(ProtocolCode.PAUSE) + + def is_paused(self): + """Judge whether the manipulator pauses or not. + + Return: + 1 - paused + 0 - not paused + -1 - error + """ + return self._mesg(ProtocolCode.IS_PAUSED, has_reply=True) + + def resume(self): + """Recovery movement""" + return self._mesg(ProtocolCode.RESUME) + + def stop(self): + """Stop moving""" + return self._mesg(ProtocolCode.STOP) + + def is_in_position(self, data, mode=0): + """Judge whether in the position. + + Args: + data: A data list, angles or coords.len 6. + mode: 1 - coords, 0 - angles + + Return: + 1 - True\n + 0 - False\n + -1 - Error + """ + if mode == 1: + self.calibration_parameters(coords=data) + data_list = [] + for idx in range(3): + data_list.append(self._coord2int(data[idx])) + for idx in range(3, 6): + data_list.append(self._angle2int(data[idx])) + elif mode == 0: + self.calibration_parameters(angles=data) + data_list = [self._angle2int(i) for i in data] + else: + raise Exception("mode is not right, please input 0 or 1") + + return self._mesg(ProtocolCode.IS_IN_POSITION, data_list, id, has_reply=True) + + def is_moving(self): + """Detect if the robot is moving + + Return: + 0 - not moving + 1 - is moving + -1 - error data + """ + return self._mesg(ProtocolCode.IS_MOVING, has_reply=True) # JOG mode and operation - def write_angles_time_control(self, angles, step_time): - """Write the angle of a joint in time control mode + def jog_angle(self, joint_id, direction, speed): + """Jog control angle. + Args: - angles: Angle value - step_time: Time unit: 30ms, range(1 ~ 255) + joint_id: int 1-6. + direction: 0 - decrease, 1 - increase + speed: int (0 - 100) """ - if step_time not in range(1, 256): - raise ValueError("step_time must be in range(1 ~ 255)") - angles = [self._angle2int(angle) for angle in angles] - return self._mesg(ProtocolCode.WRITE_ANGLE_TIME, angles, step_time) + self.calibration_parameters(joint_id=joint_id, direction=direction, speed=speed) + return self._mesg(ProtocolCode.JOG_ANGLE, joint_id, direction, speed) def jog_rpy(self, end_direction, direction, speed): """Rotate the end around a fixed axis in the base coordinate system @@ -351,41 +500,52 @@ def jog_rpy(self, end_direction, direction, speed): self.calibration_parameters(end_direction=end_direction, speed=speed) return self._mesg(ProtocolCode.JOG_ABSOLUTE, end_direction, direction, speed) + def jog_coord(self, coord_id, direction, speed): + """Jog control coord. + + Args: + coord_id: int 1-6 + direction: 0 - decrease, 1 - increase + speed: int (1 - 100) + """ + self.calibration_parameters(coord_id=coord_id, direction=direction, speed=speed) + return self._mesg(ProtocolCode.JOG_COORD, coord_id, direction, speed) + def jog_increment_angle(self, joint_id, increment, speed): """ angle step mode Args: joint_id: int 1-6. increment: Angle increment value - speed: int (0 - 100) + speed: int (1 - 100) """ - self.calibration_parameters(id=joint_id, speed=speed) + self.calibration_parameters(id=joint_id, speed=speed, angle=increment) return self._mesg(ProtocolCode.JOG_INCREMENT, joint_id, [self._angle2int(increment)], speed) - def jog_increment_coord(self, axis, increment, speed): + def jog_increment_coord(self, coord_id, increment, speed): """coord step mode Args: - axis: axis id 1 - 6. + coord_id: coord id 1 - 6. increment: Coord increment value speed: int (1 - 100) """ - self.calibration_parameters(id=axis, speed=speed) - value = self._coord2int(increment) if axis <= 3 else self._angle2int(increment) - return self._mesg(ProtocolCode.JOG_INCREMENT_COORD, axis, [value], speed) + self.calibration_parameters(coord_id=coord_id, speed=speed, coord=increment) + value = self._coord2int(increment) if coord_id <= 3 else self._angle2int(increment) + return self._mesg(ProtocolCode.JOG_INCREMENT_COORD, coord_id, [value], speed) - def set_HTS_gripper_torque(self, torque): + def set_HTS_gripper_torque(self, gripper_torque): """Set new adaptive gripper torque Args: - torque (int): 150 ~ 980 + gripper_torque (int): 150 ~ 980 Return: 0: Set failed 1: Set successful """ - self.calibration_parameters(torque=torque) - return self._mesg(ProtocolCode.SetHTSGripperTorque, [torque], has_reply=True) + self.calibration_parameters(gripper_torque=gripper_torque) + return self._mesg(ProtocolCode.SetHTSGripperTorque, [gripper_torque], has_reply=True) def get_HTS_gripper_torque(self): """Get gripper torque @@ -411,28 +571,206 @@ def init_gripper(self): """ return self._mesg(ProtocolCode.InitGripper, has_reply=True) - def set_gripper_protect_current(self, current): + def set_gripper_protect_current(self, protect_current): """Set the gripper protection current Args: - current (int): 1 ~ 500 + protect_current (int): 1 ~ 500 """ - self.calibration_parameters(current=current) + self.calibration_parameters(protect_current=protect_current) - return self._mesg(ProtocolCode.SetGripperProtectCurrent, [current]) + return self._mesg(ProtocolCode.SetGripperProtectCurrent, [protect_current]) - # Atom IO - def set_pin_mode(self, pin_no, pin_mode): - """Set the state mode of the specified pin in atom. + def set_encoder(self, servo_id, encoder, speed): + """Set a single joint rotation to the specified potential value. Args: - pin_no (int): pin. - pin_mode (int): 0 - input, 1 - output, 2 - input pull up + servo_id: int 1 - 7 + encoder: The value of the set encoder. + speed : 1 - 100 """ - self.calibration_parameters(pin_mode=pin_mode) - return self._mesg(ProtocolCode.SET_PIN_MODE, pin_no, pin_mode) + self.calibration_parameters(servo_id=servo_id, encoder=encoder, speed=speed) + return self._mesg(ProtocolCode.SET_ENCODER, servo_id, [encoder], speed) + + def get_encoder(self, servo_id): + """Obtain the specified joint potential value. - def get_gripper_value(self, gripper_type=None): + Args: + servo_id: (int) 1 - 6 + for gripper: Joint id 7 + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.GET_ENCODER, servo_id, has_reply=True) + + def set_encoders(self, encoders, speed): + """Set the six joints of the manipulator to execute synchronously to the specified position. + + Args: + encoders: A encoder list. len 6. + speed: speed 1 ~ 100 + """ + self.calibration_parameters(encoders=encoders, speed=speed) + return self._mesg(ProtocolCode.SET_ENCODERS, encoders, speed) + + def set_encoders_drag(self, encoders, speeds): + """Send all encoders and speeds + + Args: + encoders: encoders list. + speeds: Obtained by the get_servo_speeds() method + """ + self.calibration_parameters(encoders=encoders, drag_speeds=speeds) + return self._mesg(ProtocolCode.SET_ENCODERS_DRAG, encoders, speeds) + + def get_joint_min_angle(self, joint_id): + """Gets the minimum movement angle of the specified joint + + Args: + joint_id: 1 - 6 + + Return: + angle value(float) + """ + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.GET_JOINT_MIN_ANGLE, joint_id, has_reply=True) + + def get_joint_max_angle(self, joint_id): + """Gets the maximum movement angle of the specified joint + + Args: + joint_id: 1 - 6 + + Return: + angle value(float) + """ + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.GET_JOINT_MAX_ANGLE, joint_id, has_reply=True) + + def set_joint_max(self, joint_id, angle): + """Set the joint maximum angle + + Args: + joint_id: int. + Joint id 1 - 6 + for gripper: Joint id 7 + angle: 0 ~ 180 + """ + self.calibration_parameters(joint_id=joint_id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MAX, joint_id, angle) + + def set_joint_min(self, joint_id, angle): + """Set the joint minimum angle + + Args: + joint_id: int. + Joint id 1 - 6 + for gripper: Joint id 7 + angle: 0 ~ 180 + """ + self.calibration_parameters(joint_id=joint_id, angle=angle) + return self._mesg(ProtocolCode.SET_JOINT_MIN, joint_id, angle) + + # servo control + def is_servo_enable(self, servo_id): + """To detect the connection state of a single joint + + Args: + servo_id: 1 - 6 + Return: + 0 - disable + 1 - enable + -1 - error + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.IS_SERVO_ENABLE, servo_id, has_reply=True) + + def is_all_servo_enable(self): + """Detect the connection status of all joints + + Return: + 0 - disable + 1 - enable + -1 - error + """ + return self._mesg(ProtocolCode.IS_ALL_SERVO_ENABLE, has_reply=True) + + def set_servo_data(self, servo_id, address, value, mode=None): + """Set the data parameters of the specified address of the steering gear + + Args: + servo_id: Serial number of articulated steering gear. 1 - 7 + address: Data address. + value: 0 - 4096 + mode: 0 - indicates that value is one byte(default), 1 - 1 represents a value of two bytes. + """ + + unique_address = (0, 1, 2, 3, 4) + if value in unique_address: + raise ValueError(f"The address not right, Invalid address, address {unique_address} cannot be modified.") + + if mode is None: + self.calibration_parameters(servo_id=servo_id, address=address, value=value) + return self._mesg(ProtocolCode.SET_SERVO_DATA, servo_id, address, value) + else: + self.calibration_parameters(servo_id=servo_id, address=address, value=value, mode=mode) + return self._mesg(ProtocolCode.SET_SERVO_DATA, servo_id, address, [value], mode) + + def get_servo_data(self, servo_id, address, mode=None): + """Read the data parameter of the specified address of the steering gear. + + Args: + servo_id: Serial number of articulated steering gear.1 - 7 + address: Data address. + mode: 0 - indicates that value is one byte(default), 1 - 1 represents a value of two bytes. + + Return: + values 0 - 4096 + """ + if mode is not None: + self.calibration_parameters(servo_id=servo_id, address=address, mode=mode) + return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, address, mode, has_reply=True) + self.calibration_parameters(servo_id=servo_id, address=address) + return self._mesg(ProtocolCode.GET_SERVO_DATA, servo_id, address, has_reply=True) + + def set_servo_calibration(self, servo_id): + """The current position of the calibration joint actuator is the angle zero point, + and the corresponding potential value is 2048. + + Args: + servo_id: Serial number of articulated steering gear. 1 - 7 + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.SET_SERVO_CALIBRATION, servo_id) + + def joint_brake(self, joint_id): + """Make it stop when the joint is in motion, and the buffer distance is positively related to the existing speed + + Args: + joint_id: 1 - 6 + """ + self.calibration_parameters(joint_id=joint_id) + return self._mesg(ProtocolCode.JOINT_BRAKE, joint_id) + + def release_servo(self, servo_id): + """Power off designated servo + + Args: + servo_id: int 1 - 7 + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.RELEASE_SERVO, servo_id) + + def focus_servo(self, servo_id): + """Power on designated servo + + Args: + servo_id: int 1 - 7 + """ + self.calibration_parameters(servo_id=servo_id) + return self._mesg(ProtocolCode.FOCUS_SERVO, servo_id) + + # 夹爪控制 + def get_gripper_value(self, gripper_type=1): """Get the value of gripper. Args: @@ -444,11 +782,64 @@ def get_gripper_value(self, gripper_type=None): Return: gripper value (int) """ - if gripper_type is None: - return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, has_reply=True) - else: - self.calibration_parameters(gripper_type=gripper_type) - return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, gripper_type, has_reply=True) + self.calibration_parameters(gripper_type=gripper_type) + return self._mesg(ProtocolCode.GET_GRIPPER_VALUE, gripper_type, has_reply=True) + + def set_gripper_state(self, gripper_state, gripper_speed, gripper_type=None, is_torque=None): + """Set gripper switch state + + Args: + gripper_state (int): 0 - open, 1 - close, 254 - release + gripper_speed (int): 1 ~ 100 + gripper_type (int): default 1 + 1 : Adaptive gripper. default to adaptive gripper + 2 : 5 finger dexterous hand + 3 : Parallel gripper, this parameter can be omitted + 4 : Flexible gripper + is_torque (int): When there is no type parameter, this parameter can be omitted. + 1: Force control + 0: Non-force control + """ + self.calibration_parameters( + gripper_state=gripper_state, gripper_speed=gripper_speed, gripper_type=gripper_type, is_torque=is_torque + ) + args = [gripper_state, gripper_speed] + if gripper_type is not None: + args.append(gripper_type) + if is_torque is not None: + args.append(is_torque) + return self._mesg(ProtocolCode.SET_GRIPPER_STATE, *args) + + def set_gripper_value(self, gripper_value, gripper_speed, gripper_type=None, is_torque=None): + """Set gripper value + + Args: + gripper_value (int): 0 ~ 100 + gripper_speed (int): 1 ~ 100 + gripper_type (int): default 1 + 1: Adaptive gripper + 3: Parallel gripper, this parameter can be omitted + 4: Flexible gripper + is_torque (int): When there is no type parameter, this parameter can be omitted. + 1: Force control + 0: Non-force control + """ + self.calibration_parameters( + gripper_value=gripper_value, + speed=gripper_speed, + gripper_type=gripper_type, + is_torque=is_torque + ) + args = [gripper_value, gripper_speed] + if gripper_type is not None: + args.append(gripper_type) + if is_torque is not None: + args.append(is_torque) + return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, *args, has_reply=True) + + def set_gripper_calibration(self): + """Set the current position to zero, set current position value is `2048`.""" + return self._mesg(ProtocolCode.SET_GRIPPER_CALIBRATION) def is_gripper_moving(self): """Judge whether the gripper is moving or not @@ -460,6 +851,7 @@ def is_gripper_moving(self): """ return self._mesg(ProtocolCode.IS_GRIPPER_MOVING, has_reply=True) + # Atom IO def get_tool_system_version(self): """ Read the terminal primary and minor version numbers @@ -476,117 +868,66 @@ def is_tool_connected(self): """Check the end connection status""" return self._mesg(ProtocolCode.IS_CONTROLLER_CONNECTED, has_reply=True) - def is_tool_button_click(self): - """Check whether the button on the end is pressed""" - return self._mesg(ProtocolCode.IS_CONTROLLER_BUTTON_PRESSED, has_reply=True) - - def set_pwm_output(self, channel, frequency, pin_val): - """ PWM control - - Args: - channel (int): IO number. - frequency (int): clock frequency - pin_val (int): Duty cycle 0 ~ 256; 128 means 50% - """ - return self._mesg(ProtocolCode.SET_PWM_OUTPUT, channel, [frequency], pin_val) - - # communication mode - def set_transponder_mode(self, mode): - """Set basic communication mode + def set_tool_color(self, r=0, g=0, b=0): + """Set the light color on the top of the robot arm. Args: - mode: 0 - Turn off transparent transmission,1 - Open transparent transmission - """ - self.calibration_parameters(mode=mode) - return self._mesg(ProtocolCode.SET_COMMUNICATE_MODE, mode, has_reply=True) - - def get_transponder_mode(self): - return self._mesg(ProtocolCode.GET_COMMUNICATE_MODE, has_reply=True) + r (int): 0 ~ 255 + g (int): 0 ~ 255 + b (int): 0 ~ 255 - # g9 servo - def move_round(self): - """Drive the 9g steering gear clockwise for one revolution """ - return self._mesg(ProtocolCode.move_round) - - def set_four_pieces_zero(self): - """Set the zero position of the four-piece motor + self.calibration_parameters(color=[r, g, b]) + return self._mesg(ProtocolCode.SET_COLOR, r, g, b) - Returns: - int: 0 or 1 (1 - success) - """ - return self._mesg(ProtocolCode.SET_FOUR_PIECES_ZERO, has_reply=True) - - def set_servo_data(self, servo_id, data_id, value, mode=None): - if data_id in (0, 1, 2, 3, 4): - raise ValueError("Invalid data_id, addr 0 ~ 4 cannot be modified") - return super().set_servo_data(servo_id, data_id, value, mode) - - # Running Status and Settings - def set_joint_max(self, id, angle): - """Set the joint maximum angle - - Args: - id: int. - Joint id 1 - 6 - for gripper: Joint id 7 - angle: 0 ~ 180 - """ - self.calibration_parameters(id=id, angle=angle) - return self._mesg(ProtocolCode.SET_JOINT_MAX, id, angle) + def is_tool_button_click(self): + """Check whether the button on the end is pressed""" + return self._mesg(ProtocolCode.IS_CONTROLLER_BUTTON_PRESSED, has_reply=True) - def set_joint_min(self, id, angle): - """Set the joint minimum angle + def set_digital_output(self, pin_no, pin_signal): + """Set the terminal atom io status Args: - id: int. - Joint id 1 - 6 - for gripper: Joint id 7 - angle: 0 ~ 180 + pin_no (int): 1 or 2 + pin_signal (int): 0 / 1 """ - self.calibration_parameters(id=id, angle=angle) - return self._mesg(ProtocolCode.SET_JOINT_MIN, id, angle) - # servo state value - def get_servo_speeds(self): - """Get joint speed + if pin_no not in (1, 2): + raise ValueError("pin_no must be 1 or 2") - Return: - A list unit step/s - """ - return self._mesg(ProtocolCode.GET_SERVO_SPEED, has_reply=True) + self.calibration_parameters(class_name=self.__class__.__name__, pin_signal=pin_signal) + return self._mesg(ProtocolCode.SET_DIGITAL_OUTPUT, pin_no, pin_signal) - def get_servo_currents(self): - """Get all joint current - - Return: - A list unit mA - """ - return self._mesg(ProtocolCode.GET_SERVO_CURRENTS, has_reply=True) + def get_digital_input(self, pin_no): + """Get atom digital input value - def get_servo_voltages(self): - """Get joint voltages - - Return: - A list volts < 24 V + Args: + pin_no (int): 1 or 2 """ - return self._mesg(ProtocolCode.GET_SERVO_VOLTAGES, has_reply=True) + if pin_no not in (1, 2): + raise ValueError("pin_no must be 1 or 2") - def get_servo_status(self): - """Get joint status + return self._mesg(ProtocolCode.GET_DIGITAL_INPUT, pin_no, has_reply=True) - Return: - [voltage, sensor, temperature, current, angle, overload], a value of 0 means no error, a value of 1 indicates an error - """ - return self._mesg(ProtocolCode.GET_SERVO_STATUS, has_reply=True) + # Kinematic algorithm interface api + def solve_inv_kinematics(self, target_coords, current_angles): + """ Convert target coordinates to angles - def get_servo_temps(self): - """Get joint temperature + Args: + target_coords: A float list of all coordinates. + current_angles : A float list of all angle. Return: - A list unit ℃ + list: A float list of all angle. """ - return self._mesg(ProtocolCode.GET_SERVO_TEMPS, has_reply=True) + self.calibration_parameters(coords=target_coords, angles=current_angles) + angles = [self._angle2int(angle) for angle in current_angles] + coord_list = [] + for idx in range(3): + coord_list.append(self._coord2int(target_coords[idx])) + for angle in target_coords[3:]: + coord_list.append(self._angle2int(angle)) + return self._mesg(ProtocolCode.SOLVE_INV_KINEMATICS, coord_list, angles, has_reply=True) # Coordinate transformation def set_tool_reference(self, coords): @@ -627,14 +968,14 @@ def get_world_reference(self): """Get the world coordinate system""" return self._mesg(ProtocolCode.GET_WORLD_REFERENCE, has_reply=True) - def set_reference_frame(self, rftype): + def set_reference_frame(self, reference_frame_type): """Set the base coordinate system Args: - rftype: 0 - base 1 - tool. + reference_frame_type: 0 - base 1 - tool. """ - self.calibration_parameters(rftype=rftype) - return self._mesg(ProtocolCode.SET_REFERENCE_FRAME, rftype) + self.calibration_parameters(reference_frame_type=reference_frame_type) + return self._mesg(ProtocolCode.SET_REFERENCE_FRAME, reference_frame_type) def get_reference_frame(self): """Get the base coordinate system @@ -661,15 +1002,15 @@ def get_movement_type(self): """ return self._mesg(ProtocolCode.GET_MOVEMENT_TYPE, has_reply=True) - def set_end_type(self, end): + def set_end_type(self, end_type): """Set end coordinate system Args: - end: int + end_type: int 0 - flange, 1 - tool """ - self.calibration_parameters(end=end) - return self._mesg(ProtocolCode.SET_END_TYPE, end) + self.calibration_parameters(end_type=end_type) + return self._mesg(ProtocolCode.SET_END_TYPE, end_type) def get_end_type(self): """Get end coordinate system @@ -679,92 +1020,68 @@ def get_end_type(self): """ return self._mesg(ProtocolCode.GET_END_TYPE, has_reply=True) - def angles_to_coords(self, angles): - """ Convert angles to coordinates + # 9G Servo backgammon + def move_round(self): + """Drive the 9g steering gear clockwise for one revolution + """ + return self._mesg(ProtocolCode.move_round) - Args: - angles : A float list of all angle. + def set_four_pieces_zero(self): + """Set the zero position of the four-piece motor - Return: - list: A float list of all coordinates. + Returns: + int: 0 or 1 (1 - success) """ - angles = [self._angle2int(angle) for angle in angles] - return self._mesg(ProtocolCode.GET_COORDS, angles, has_reply=True) + return self._mesg(ProtocolCode.SET_FOUR_PIECES_ZERO, has_reply=True) - def solve_inv_kinematics(self, target_coords, current_angles): - """ Convert target coordinates to angles + # Stdio api + def get_angles_coords(self): + """Get joint angles and coordinates""" + return self._mesg(ProtocolCode.GET_ANGLES_COORDS, has_reply=True) - Args: - target_coords: A float list of all coordinates. - current_angles : A float list of all angle. + # Servo state value + def get_servo_speeds(self): + """Get joint speed Return: - list: A float list of all angle. + A list unit step/s """ - angles = [self._angle2int(angle) for angle in current_angles] - coord_list = [] - for idx in range(3): - coord_list.append(self._coord2int(target_coords[idx])) - for angle in target_coords[3:]: - coord_list.append(self._angle2int(angle)) - return self._mesg(ProtocolCode.SOLVE_INV_KINEMATICS, coord_list, angles, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_SPEED, has_reply=True) - def is_torque_gripper(self): - """Whether it is a force-controlled gripper + def get_servo_currents(self): + """Get all joint current Return: - 40 - Force control - 9 - Non-force control + A list unit mA """ - return self.get_servo_data(7, 1) + return self._mesg(ProtocolCode.GET_SERVO_CURRENTS, has_reply=True) - def set_gripper_state(self, flag, speed, _type_1=None, is_torque=None): - """Set gripper switch state + def get_servo_voltages(self): + """Get joint voltages - Args: - flag (int): 0 - open, 1 - close, 254 - release - speed (int): 1 ~ 100 - _type_1 (int): default 1 - 1 : Adaptive gripper. default to adaptive gripper - 2 : 5 finger dexterous hand - 3 : Parallel gripper, this parameter can be omitted - 4 : Flexible gripper - is_torque (int): When there is no type parameter, this parameter can be omitted. - 1: Force control - 0: Non-force control + Return: + A list volts < 24 V """ - self.calibration_parameters(flag=flag, speed=speed, _type_1=_type_1, is_torque=is_torque) - args = [flag, speed] - if _type_1 is not None: - args.append(_type_1) - if is_torque is not None: - args.append(is_torque) - return self._mesg(ProtocolCode.SET_GRIPPER_STATE, *args) + return self._mesg(ProtocolCode.GET_SERVO_VOLTAGES, has_reply=True) - def set_gripper_value(self, gripper_value, speed, gripper_type=None, is_torque=None): - """Set gripper value + def get_servo_status(self): + """Get joint status - Args: - gripper_value (int): 0 ~ 100 - speed (int): 1 ~ 100 - gripper_type (int): default 1 - 1: Adaptive gripper - 3: Parallel gripper, this parameter can be omitted - 4: Flexible gripper - is_torque (int): When there is no type parameter, this parameter can be omitted. - 1: Force control - 0: Non-force control + Return: + [voltage, sensor, temperature, current, angle, overload], a value of 0 means no error, a value of 1 indicates an error """ - self.calibration_parameters(gripper_value=gripper_value, speed=speed, - gripper_type=gripper_type, is_torque=is_torque) - args = [gripper_value, speed] - if gripper_type is not None: - args.append(gripper_type) - if is_torque is not None: - args.append(is_torque) - return self._mesg(ProtocolCode.SET_GRIPPER_VALUE, *args, has_reply=True) + return self._mesg(ProtocolCode.GET_SERVO_STATUS, has_reply=True) + + def get_servo_temps(self): + """Get joint temperature + + Return: + A list unit ℃ + """ + return self._mesg(ProtocolCode.GET_SERVO_TEMPS, has_reply=True) - def drag_start_record(self): + # Drag the teach-in + def start_drag_record(self): """Start track recording Return: @@ -773,7 +1090,7 @@ def drag_start_record(self): return self._mesg(ProtocolCode.DRAG_START_RECORD, has_reply=True) - def drag_end_record(self): + def end_drag_record(self): """End track recording Return: @@ -782,7 +1099,7 @@ def drag_end_record(self): return self._mesg(ProtocolCode.DRAG_END_RECORD, has_reply=True) - def drag_get_record_data(self): + def get_drag_record_data(self): """Get the recorded track Return: @@ -793,7 +1110,7 @@ def drag_get_record_data(self): return self._mesg(ProtocolCode.DRAG_GET_RECORD_DATA, has_reply=True) - def drag_get_record_len(self): + def get_drag_record_len(self): """Get the total number of recorded points Return: @@ -802,7 +1119,7 @@ def drag_get_record_len(self): return self._mesg(ProtocolCode.DRAG_GET_RECORD_LEN, has_reply=True) - def drag_clear_record_data(self): + def clear_drag_record_data(self): """Clear recording track Return: @@ -898,8 +1215,13 @@ def close(self): def main(): - rdx_x5 = MyCobot280RDKX5("Com30", debug=True) - print(rdx_x5.get_reboot_count()) + rdx_x5 = MyCobot280RDKX5("/dev/ttyS1", debug=True) + # print(rdx_x5.get_angles()) + # rdx_x5.send_angle(6, 168, 100) + rdx_x5.send_angles([0, 0, 0, 0, 0, 0], 100) + time.sleep(3) + # print(rdx_x5.get_coords()) + rdx_x5.send_coords([169.7, -65.8, 200.5, 178.14, -0.41, -89.98], 10) # mc_sock = MyCobot280RDKX5Socket('192.168.1.246', port=30002, debug=True) # print(mc_sock.send_angle(1, 100, 50)) # print(mc_sock.get_quick_move_message()) diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 64c0c378..50a3c98e 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -1,4 +1,4 @@ - # coding=utf-8 +# coding=utf-8 class Robot320Info(object): error_info = { @@ -20,42 +20,44 @@ class Robot320Info(object): 255: "未知错误" }, "servo_error": - { - 0: "伺服电机欠压/过压,查看电压,如果为0,需要修改舵机参数;如果大于实际,可能散热片损坏", - 1: "伺服电机磁编码异常", - 2: "伺服电机过温", - 3: "伺服电机过流", - 5: "伺服电机过载", - } + { + 0: "伺服电机欠压/过压,查看电压,如果为0,需要修改舵机参数;如果大于实际,可能散热片损坏", + 1: "伺服电机磁编码异常", + 2: "伺服电机过温", + 3: "伺服电机过流", + 5: "伺服电机过载", + } }, "en_US": { "robot_error": - { - 0: "Communication exception, please check the line, servo motor firmware version, power supply, firmware burning, baud rate, etc.", - 1: "Servo motor model error, need to replace the motor", - 2: "Servo motor firmware version is too low, need to use FD upgrade", - 3: "Servo motor p value exception, default 32, this exception will be automatically restored", - 4: "Servo motor D value exception, default 8, this exception will be automatically restored", - 5: "Servo motor I value exception, default 0, this exception will be automatically restored", - 6: "Servo motor clockwise insensitive zone parameter exception, default 3, this exception will be automatically restored", - 7: "Servo motor counterclockwise insensitive zone parameter exception, default 3, this exception will be automatically restored", - 8: "Servo motor phase exception, this exception will be automatically restored", - 9: "Servo motor return delay exception, default 0, this exception will be automatically restored", - 10: "Servo motor minimum starting force exception, default 0, this exception will be automatically restored", - 11: "Servo motor exception, when the servo is abnormal, the robot cannot move, please query the servo feedback interface get_servo_status, view the specific error", - 255: "Unknown error" - }, + { + 0: "Communication exception, please check the line, servo motor firmware version, power supply, firmware burning, baud rate, etc.", + 1: "Servo motor model error, need to replace the motor", + 2: "Servo motor firmware version is too low, need to use FD upgrade", + 3: "Servo motor p value exception, default 32, this exception will be automatically restored", + 4: "Servo motor D value exception, default 8, this exception will be automatically restored", + 5: "Servo motor I value exception, default 0, this exception will be automatically restored", + 6: "Servo motor clockwise insensitive zone parameter exception, default 3, this exception will be automatically restored", + 7: "Servo motor counterclockwise insensitive zone parameter exception, default 3, this exception will be automatically restored", + 8: "Servo motor phase exception, this exception will be automatically restored", + 9: "Servo motor return delay exception, default 0, this exception will be automatically restored", + 10: "Servo motor minimum starting force exception, default 0, this exception will be automatically restored", + 11: "Servo motor exception, when the servo is abnormal, the robot cannot move, please query the servo feedback interface get_servo_status, view the specific error", + 255: "Unknown error" + }, "servo_error": - { - 0: "Servo motor under-voltage/over-voltage, check the voltage, if it is 0, you need to modify the servo parameters; if it is greater than the actual, it may be damaged", - 1: "Servo motor magnetic encoder exception", - 2: "Servo motor over-temperature", - 3: "Servo motor over-current", - 5: "Servo motor over-load", - } + { + 0: "Servo motor under-voltage/over-voltage, check the voltage, if it is 0, you need to modify the servo parameters; if it is greater than the actual, it may be damaged", + 1: "Servo motor magnetic encoder exception", + 2: "Servo motor over-temperature", + 3: "Servo motor over-current", + 5: "Servo motor over-load", + } } } + + # coding=utf-8 def _interpret_status_code(language, status_code): @@ -222,31 +224,32 @@ def _interpret_status_code(language, status_code): 255: "Error: Unknown error code: " } } - return status_messages[language].get(status_code, status_messages[language].get(255)+str(status_code)) + return status_messages[language].get(status_code, status_messages[language].get(255) + str(status_code)) + class RobotLimit: robot_limit = { - "Mercury":{ - "joint_id":[1,2,3,4,5,6,7,11,12,13], - "angles_min":[-165, -50, -165, -165, -165, -75, -165, -55, -70, -160], - "angles_max":[165, 120, 165, 1, 165, 255, 165, 0, 245, 160], - "coords_min":[-459, -459, -300, -180, -180, -180], - "coords_max":[459, 459, 542, 180, 180, 180], - "left_coords_min":[-351.11, -272.12, -262.91, -180, -180, -180], - "left_coords_max":[566.92, 645.91, 655.13, 180, 180, 180], - "right_coords_min":[-351.11, -645.91, -262.91, -180, -180, -180], - "right_coords_max":[566.92, 272.12, 655.13, 180, 180, 180] + "Mercury": { + "joint_id": [1, 2, 3, 4, 5, 6, 7, 11, 12, 13], + "angles_min": [-165, -50, -165, -165, -165, -75, -165, -55, -70, -160], + "angles_max": [165, 120, 165, 1, 165, 255, 165, 0, 245, 160], + "coords_min": [-459, -459, -300, -180, -180, -180], + "coords_max": [459, 459, 542, 180, 180, 180], + "left_coords_min": [-351.11, -272.12, -262.91, -180, -180, -180], + "left_coords_max": [566.92, 645.91, 655.13, 180, 180, 180], + "right_coords_min": [-351.11, -645.91, -262.91, -180, -180, -180], + "right_coords_max": [566.92, 272.12, 655.13, 180, 180, 180] }, - "MercurySocket":{ - "joint_id":[1,2,3,4,5,6,7,11,12,13], - "angles_min":[-165, -50, -165, -165, -165, -75, -165, -55, -70, -160], - "angles_max":[165, 120, 165, 1, 165, 255, 165, 0, 245, 160], - "coords_min":[-459, -459, -300, -180, -180, -180], - "coords_max":[459, 459, 542, 180, 180, 180], - "left_coords_min":[-351.11, -272.12, -262.91, -180, -180, -180], - "left_coords_max":[566.92, 645.91, 655.13, 180, 180, 180], - "right_coords_min":[-351.11, -645.91, -262.91, -180, -180, -180], - "right_coords_max":[566.92, 272.12, 655.13, 180, 180, 180] + "MercurySocket": { + "joint_id": [1, 2, 3, 4, 5, 6, 7, 11, 12, 13], + "angles_min": [-165, -50, -165, -165, -165, -75, -165, -55, -70, -160], + "angles_max": [165, 120, 165, 1, 165, 255, 165, 0, 245, 160], + "coords_min": [-459, -459, -300, -180, -180, -180], + "coords_max": [459, 459, 542, 180, 180, 180], + "left_coords_min": [-351.11, -272.12, -262.91, -180, -180, -180], + "left_coords_max": [566.92, 645.91, 655.13, 180, 180, 180], + "right_coords_min": [-351.11, -645.91, -262.91, -180, -180, -180], + "right_coords_max": [566.92, 272.12, 655.13, 180, 180, 180] }, "MyCobot": { "id": [1, 2, 3, 4, 5, 6, 7], @@ -269,12 +272,21 @@ class RobotLimit: "coords_min": [-350, -350, -70, -180, -180, -180], "coords_max": [350, 350, 523.9, 180, 180, 180] }, + "MyCobot280RDK-X5": { + "joint_id": [1, 2, 3, 4, 5, 6], + "coord_id": [1, 2, 3, 4, 5, 6], + "servo_id": [1, 2, 3, 4, 5, 6, 7], + "angles_min": [-168, -135, -150, -145, -165, -180], + "angles_max": [168, 135, 150, 145, 165, 180], + "coords_min": [-281.45, -281.45, -70, -180, -180, -180], + "coords_max": [281.45, 281.45, 412.67, 180, 180, 180] + }, "MyCobot280Socket": { "id": [1, 2, 3, 4, 5, 6], "angles_min": [-168, -135, -150, -145, -165, -180], "angles_max": [168, 135, 150, 145, 165, 180], - "coords_min": [-350, -350, -70, -180, -180, -180], - "coords_max": [350, 350, 523.9, 180, 180, 180] + "coords_min": [-281.45, -281.45, -70, -180, -180, -180], + "coords_max": [281.45, 281.45, 412.67, 180, 180, 180] }, "MyCobot320": { "id": [1, 2, 3, 4, 5, 6], From 19b7e86ab3f8e977cdf4974b0f02b246216f0405 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 23 May 2025 16:16:22 +0800 Subject: [PATCH 23/57] Optimized the way MyAGV reads MCU data --- pymycobot/myagv.py | 185 +++++++++++++++++++++++++++------------------ 1 file changed, 111 insertions(+), 74 deletions(-) diff --git a/pymycobot/myagv.py b/pymycobot/myagv.py index c802e154..ddf984c5 100644 --- a/pymycobot/myagv.py +++ b/pymycobot/myagv.py @@ -1,4 +1,4 @@ -import enum +# -*- coding: utf-8 -*- import threading import serial import time @@ -9,7 +9,7 @@ def setup_logging(name: str = __name__, debug: bool = False) -> logging.Logger: debug_formatter = logging.Formatter( - fmt="%(asctime)s %(levelname)s [%(name)s] - %(message)s", + fmt="%(asctime)s.%(msecs)06d %(levelname).4s [%(name)s] %(message)s", datefmt="%H:%M:%S", ) logger = logging.getLogger(name) @@ -30,7 +30,17 @@ def setup_logging(name: str = __name__, debug: bool = False) -> logging.Logger: return logger -class ProtocolCode(enum.Enum): +def setup_serial_connect(port, baudrate, timeout=None): + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout + serial_api.rts = False + serial_api.open() + return serial_api + + +class ProtocolCode: HEADER = (0xFE, 0xFE) RESTORE = (0x01, 0x00) SET_LED = (0x01, 0x02) @@ -43,35 +53,33 @@ class ProtocolCode(enum.Enum): UNDEFINED = () -class SerialStreamProtocol(object): +class CommunicationProtocol(object): + def write(self, command): + raise NotImplementedError - def __init__(self, port="/dev/ttyAMA0", baudrate=115200, timeout=0.1): - self._serial_port = serial.Serial(port=port, baudrate=baudrate, timeout=timeout) - self._serial_port.rts = False - - def open(self): - if self._serial_port.is_open is False: - self._serial_port.open() + def read(self, size=1): + raise NotImplementedError def close(self): - if self._serial_port.is_open is True: - self._serial_port.close() + raise NotImplementedError - def flush(self): - self._serial_port.flush() + def open(self): + raise NotImplementedError - def write(self, data): - self._serial_port.write(data) - self._serial_port.flush() + def is_open(self): + raise NotImplementedError - def read(self, size): - return self._serial_port.read(size) + def clear(self): + raise NotImplementedError - def readall(self): - return self._serial_port.read_all() +class MyAGVCommandProtocolApi(CommunicationProtocol): -class CommandProtocol(object): + def __init__(self, debug=False): + self.__movement = False + self.__mutex = threading.Lock() + self.__command_buffer_table = {} + self.log = setup_logging(name=f"{__name__}.{self.__class__.__name__}", debug=debug) def _process_data_command(self, args): if not args: @@ -118,32 +126,21 @@ def _encode_int16(cls, data): def _decode_int16(cls, data): return struct.unpack(">h", data)[0] - -class MyAgv(SerialStreamProtocol, CommandProtocol): - - def __init__(self, comport, baudrate=115200, timeout=0.1, debug=False): - super().__init__(comport, baudrate, timeout) - self.__movement = False - self.__command_buffer_table = {} - self.__mutex = threading.Lock() - self.log = setup_logging(name=self.__class__.__name__, debug=debug) - self._command_read_thread = threading.Thread(target=self._read_command_buffer_thread, daemon=True) - self._command_read_thread.start() - - @classmethod - def __is_complete_command(cls, command): - return sum(command[2:-1]) & 0xff == command[-1] and len(command) > 5 - - def _read_command_buffer(self): + def _read_command_buffer(self, timeout=1, conditional=None): previous_frame = b"" is_record = False - commands = b"\xfe\xfe" + commands = b"" - while True: - current_frame = self.read(1) + start_time = time.time() + while time.time() - start_time < timeout: + current_frame = self.read() + if current_frame == b'': + time.sleep(0.001) + continue if current_frame == b"\xfe" and previous_frame == b"\xfe" and is_record is False: is_record = True + commands += b"\xfe\xfe" continue previous_frame = current_frame @@ -151,46 +148,36 @@ def _read_command_buffer(self): continue commands += current_frame - if sum(commands[2:-1]) & 0xff == commands[-1] and len(commands) > 5: + + cond_res = True if conditional is None else conditional(commands) + if sum(commands[2:-1]) & 0xff == commands[-1] and cond_res: break + else: + commands = b"" return commands - def _read_command_buffer_thread(self): - while True: - command_buffers = self._read_command_buffer() - if self.__is_complete_command(command_buffers): - self.log.info(f"write: {' '.join(f'{x:02x}' for x in command_buffers)}") - genre = tuple(command_buffers[2:4]) - if genre == (128, 128): - genre = ProtocolCode.GET_MCU_INFO.value - self.__command_buffer_table[genre] = (time.perf_counter(), command_buffers) - time.sleep(0.008) - def _compose_complete_command(self, genre: ProtocolCode, params): # packing command command_args = self._process_data_command(params) command_args = self._flatten(command_args) - command = [*ProtocolCode.HEADER.value] - if isinstance(genre.value, tuple): - command.extend(genre.value) + command = [*ProtocolCode.HEADER] + if isinstance(genre, tuple): + command.extend(genre) else: - command.append(genre.value) + command.append(genre) command.extend(command_args) command.append(sum(command[2:]) & 0xff) return command - def _parse_reply_instruction(self, genre: ProtocolCode): # unpacking command - timestamp, reply_data = self.__command_buffer_table.get(genre.value, (time.perf_counter(), [])) - if not reply_data: + def _parse_reply_instruction(self, genre, reply_data): # unpacking command + if len(reply_data) == 0: return None - self.log.info(f"read : {' '.join(f'{x:02x}' for x in reply_data)}") if genre == ProtocolCode.GET_FIRMWARE_VERSION: return self._float(reply_data[4], 1) + elif genre == ProtocolCode.GET_MCU_INFO: - if len(reply_data) < 30: - return None index = 0 res = [] datas = reply_data[2:][:-1] # header and footer frames are not counted @@ -231,17 +218,38 @@ def _parse_reply_instruction(self, genre: ProtocolCode): # unpacking command return res return reply_data[4] - def _merge(self, genre: ProtocolCode, *args, has_reply=False, in_buffer=False): - if in_buffer is False: - real_command = self._compose_complete_command(genre, args) - self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") - with self.__mutex: + def _merge(self, genre, *args, has_reply=False): + with self.__mutex: + self.clear() + if genre not in (ProtocolCode.GET_MCU_INFO,): + real_command = self._compose_complete_command(genre, args) + self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") self.write(real_command) if has_reply is False: return None - time.sleep(0.1) - return self._parse_reply_instruction(genre) + for _ in range(8): + reply_data = self._read_command_buffer(conditional=lambda x: len(x) > 5, timeout=1) + if len(reply_data) == 0: + time.sleep(0.01) + continue + + if reply_data[2] == genre[0] and reply_data[3] == genre[1]: + break + + self.log.info(f"-read: {' '.join(f'{x:02x}' for x in reply_data)}") + time.sleep(0.01) + + else: + reply_data = b"" + else: + reply_data = self._read_command_buffer(conditional=lambda x: len(x) in (45, 29), timeout=1) + + self.log.info(f"_read: {' '.join(f'{x:02x}' for x in reply_data)}") + return self._parse_reply_instruction(genre, reply_data) + + +class MyAGVCommandApi(MyAGVCommandProtocolApi): def set_led(self, mode, r, g, b): """Set up LED lights @@ -367,8 +375,8 @@ def counterclockwise_rotation(self, speed: int, timeout=5): def stop(self): """stop-motion""" - self.__movement = False self._merge(ProtocolCode.UNDEFINED, 128, 128, 128) + self.__movement = False def get_mcu_info(self): """ @@ -394,7 +402,7 @@ def get_mcu_info(self): 20-24: stall state 1 - stalled, 0 - normal 24-28: encoder status 1 - normal, 0 - abnormal """ - return self._merge(ProtocolCode.GET_MCU_INFO, has_reply=True, in_buffer=True) + return self._merge(ProtocolCode.GET_MCU_INFO, has_reply=True) def restore(self): """Motor stall recovery""" @@ -426,3 +434,32 @@ def get_firmware_version(self): def get_modified_version(self): """Get modified version number""" return self._merge(ProtocolCode.GET_MODIFIED_VERSION, has_reply=True) + + +class MyAgv(MyAGVCommandApi): + + def __init__(self, comport, baudrate=115200, timeout=0.1, debug=False): + super().__init__(debug=debug) + self._serial_port = setup_serial_connect(comport, baudrate, timeout) + + def write(self, command): + self._serial_port.write(bytearray(command)) + self._serial_port.flush() + + def read(self, size=1): + return self._serial_port.read(size) + + def close(self): + if self._serial_port.is_open: + self._serial_port.close() + + def open(self): + if not self._serial_port.is_open: + self._serial_port.open() + + def is_open(self): + return self._serial_port.is_open + + def clear(self): + self._serial_port.reset_output_buffer() + self._serial_port.flush() From 999666d5561e75677491362c97728a67c170b303 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 29 May 2025 14:22:25 +0800 Subject: [PATCH 24/57] feat(myagvpro): add myagvpro api --- pymycobot/__init__.py | 2 + pymycobot/myagv.py | 128 ++-------- pymycobot/myagvapi.py | 135 +++++++++++ pymycobot/myagvpro.py | 530 ++++++++++++++++++++++++++++++++++++++++++ 4 files changed, 680 insertions(+), 115 deletions(-) create mode 100644 pymycobot/myagvapi.py create mode 100644 pymycobot/myagvpro.py diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index f7a27131..e0c08b66 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -28,6 +28,7 @@ from pymycobot.elephantrobot import ElephantRobot from pymycobot.mercury import Mercury from pymycobot.myagv import MyAgv +from pymycobot.myagvpro import MyAGVPro from pymycobot.myarmsocket import MyArmSocket from pymycobot.mecharmsocket import MechArmSocket # from pymycobot.mycobotpro630 import Phoenix @@ -70,6 +71,7 @@ "ElephantRobot", "Mercury", "MyAgv", + "MyAGVPro", "MechArmSocket", "MyArmSocket", "MercurySocket", diff --git a/pymycobot/myagv.py b/pymycobot/myagv.py index ddf984c5..3f45c990 100644 --- a/pymycobot/myagv.py +++ b/pymycobot/myagv.py @@ -1,43 +1,9 @@ -# -*- coding: utf-8 -*- +#!/usr/bin/env python +# -*- coding: UTF-8 -*- import threading -import serial import time -import struct -import logging -import logging.handlers - - -def setup_logging(name: str = __name__, debug: bool = False) -> logging.Logger: - debug_formatter = logging.Formatter( - fmt="%(asctime)s.%(msecs)06d %(levelname).4s [%(name)s] %(message)s", - datefmt="%H:%M:%S", - ) - logger = logging.getLogger(name) - stream_handler = logging.StreamHandler() - stream_handler.setFormatter(debug_formatter) - if debug is True: - logger.addHandler(stream_handler) - logger.setLevel(logging.INFO) # 100M日志 - file_handler = logging.handlers.RotatingFileHandler( - filename="python_debug.log", maxBytes=100 * 1024 * 1024, backupCount=1 - ) - file_handler.setFormatter(debug_formatter) - logger.addHandler(file_handler) - - else: - logger.setLevel(logging.DEBUG) - - return logger - - -def setup_serial_connect(port, baudrate, timeout=None): - serial_api = serial.Serial() - serial_api.port = port - serial_api.baudrate = baudrate - serial_api.timeout = timeout - serial_api.rts = False - serial_api.open() - return serial_api + +from .myagvapi import CommunicationProtocol, Utils, setup_serial_connect, setup_logging class ProtocolCode: @@ -53,79 +19,13 @@ class ProtocolCode: UNDEFINED = () -class CommunicationProtocol(object): - def write(self, command): - raise NotImplementedError - - def read(self, size=1): - raise NotImplementedError - - def close(self): - raise NotImplementedError - - def open(self): - raise NotImplementedError - - def is_open(self): - raise NotImplementedError - - def clear(self): - raise NotImplementedError - - class MyAGVCommandProtocolApi(CommunicationProtocol): def __init__(self, debug=False): self.__movement = False self.__mutex = threading.Lock() - self.__command_buffer_table = {} self.log = setup_logging(name=f"{__name__}.{self.__class__.__name__}", debug=debug) - def _process_data_command(self, args): - if not args: - return [] - - processed_args = [] - for index in range(len(args)): - if isinstance(args[index], list): - data = self._encode_int16(args[index]) - processed_args.extend(data) - else: - processed_args.append(args[index]) - - return processed_args - - def _flatten(self, datas): - flat_list = [] - for item in datas: - if not isinstance(item, list): - flat_list.append(item) - else: - flat_list.extend(self._flatten(item)) - return flat_list - - @classmethod - def _float(cls, number, decimal=2): - return round(number / 10 ** decimal, 2) - - @classmethod - def _encode_int16(cls, data): - if isinstance(data, int): - return [ - ord(i) if isinstance(i, str) else i - for i in list(struct.pack(">h", data)) - ] - else: - res = [] - for v in data: - t = cls._encode_int16(v) - res.extend(t) - return res - - @classmethod - def _decode_int16(cls, data): - return struct.unpack(">h", data)[0] - def _read_command_buffer(self, timeout=1, conditional=None): previous_frame = b"" is_record = False @@ -157,8 +57,8 @@ def _read_command_buffer(self, timeout=1, conditional=None): return commands def _compose_complete_command(self, genre: ProtocolCode, params): # packing command - command_args = self._process_data_command(params) - command_args = self._flatten(command_args) + command_args = Utils.process_data_command(params) + command_args = Utils.flatten(command_args) command = [*ProtocolCode.HEADER] if isinstance(genre, tuple): @@ -175,7 +75,7 @@ def _parse_reply_instruction(self, genre, reply_data): # unpacking command return None if genre == ProtocolCode.GET_FIRMWARE_VERSION: - return self._float(reply_data[4], 1) + return Utils.float(reply_data[4], 1) elif genre == ProtocolCode.GET_MCU_INFO: index = 0 @@ -187,8 +87,8 @@ def _parse_reply_instruction(self, genre, reply_data): # unpacking command index += 1 elif index in range(3, 15, 2): - data = self._decode_int16(datas[index:index + 2]) - res.append(self._float(data, 2)) + data = Utils.decode_int16(datas[index:index + 2]) + res.append(Utils.float(data, 2)) index += 2 elif index == 15: @@ -202,11 +102,11 @@ def _parse_reply_instruction(self, genre, reply_data): # unpacking command index += 1 elif index in range(18, 26, 2): - res.append(self._float(self._decode_int16(datas[index:index + 2]), 3)) + res.append(Utils.float(Utils.decode_int16(datas[index:index + 2]), 3)) index += 2 elif index in range(26, 32, 2): - res.append(self._float(self._decode_int16(datas[index:index + 2]), 3)) + res.append(Utils.float(Utils.decode_int16(datas[index:index + 2]), 3)) index += 2 elif index in range(32, 42, 1): @@ -237,7 +137,6 @@ def _merge(self, genre, *args, has_reply=False): if reply_data[2] == genre[0] and reply_data[3] == genre[1]: break - self.log.info(f"-read: {' '.join(f'{x:02x}' for x in reply_data)}") time.sleep(0.01) else: @@ -245,7 +144,7 @@ def _merge(self, genre, *args, has_reply=False): else: reply_data = self._read_command_buffer(conditional=lambda x: len(x) in (45, 29), timeout=1) - self.log.info(f"_read: {' '.join(f'{x:02x}' for x in reply_data)}") + self.log.info(f" read: {' '.join(f'{x:02x}' for x in reply_data)}") return self._parse_reply_instruction(genre, reply_data) @@ -444,7 +343,6 @@ def __init__(self, comport, baudrate=115200, timeout=0.1, debug=False): def write(self, command): self._serial_port.write(bytearray(command)) - self._serial_port.flush() def read(self, size=1): return self._serial_port.read(size) @@ -462,4 +360,4 @@ def is_open(self): def clear(self): self._serial_port.reset_output_buffer() - self._serial_port.flush() + self._serial_port.reset_input_buffer() diff --git a/pymycobot/myagvapi.py b/pymycobot/myagvapi.py new file mode 100644 index 00000000..7a38c4d1 --- /dev/null +++ b/pymycobot/myagvapi.py @@ -0,0 +1,135 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import serial +import struct +import logging +import logging.handlers + + +def setup_logging(name: str = __name__, debug: bool = False) -> logging.Logger: + debug_formatter = logging.Formatter( + fmt="%(asctime)s.%(msecs)06d %(levelname).4s [%(name)s] %(message)s", + datefmt="%H:%M:%S", + ) + logger = logging.getLogger(name) + stream_handler = logging.StreamHandler() + stream_handler.setFormatter(debug_formatter) + if debug is True: + logger.addHandler(stream_handler) + logger.setLevel(logging.INFO) # 100M日志 + file_handler = logging.handlers.RotatingFileHandler( + filename="python_debug.log", maxBytes=100 * 1024 * 1024, backupCount=1 + ) + file_handler.setFormatter(debug_formatter) + logger.addHandler(file_handler) + + else: + logger.setLevel(logging.DEBUG) + + return logger + + +def setup_serial_connect(port, baudrate, timeout=None): + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout + serial_api.rts = False + serial_api.open() + return serial_api + + +class CommunicationProtocol(object): + def write(self, command): + raise NotImplementedError + + def read(self, size=1): + raise NotImplementedError + + def close(self): + raise NotImplementedError + + def open(self): + raise NotImplementedError + + def is_open(self): + raise NotImplementedError + + def clear(self): + raise NotImplementedError + + +class Utils: + @classmethod + def process_data_command(cls, args): + if not args: + return [] + + processed_args = [] + for index in range(len(args)): + if isinstance(args[index], list): + data = cls.encode_int16(args[index]) + processed_args.extend(data) + else: + processed_args.append(args[index]) + + return cls.flatten(processed_args) + + @classmethod + def flatten(cls, datas): + flat_list = [] + for item in datas: + if not isinstance(item, list): + flat_list.append(item) + else: + flat_list.extend(cls.flatten(item)) + return flat_list + + @classmethod + def float(cls, number, decimal=2): + return round(number / 10 ** decimal, 2) + + @classmethod + def encode_int16(cls, data): + if isinstance(data, int): + return [ + ord(i) if isinstance(i, str) else i + for i in list(struct.pack(">h", data)) + ] + else: + res = [] + for v in data: + t = cls.encode_int16(v) + res.extend(t) + return res + + @classmethod + def decode_int16(cls, data): + return struct.unpack(">h", data)[0] + + @classmethod + def crc16_check(cls, command): + crc = 0xffff + for index in range(len(command)): + crc ^= command[index] + for _ in range(8): + if crc & 1 == 1: + crc >>= 1 + crc ^= 0xA001 + else: + crc >>= 1 + if crc > 0x7FFF: + crc_res = list(struct.pack(">H", crc)) + else: + crc_res = cls.encode_int16(crc) + + for i in range(2): + if isinstance(crc_res[i], str): + crc_res[i] = ord(crc_res[i]) + return crc_res + + @classmethod + def get_bits(cls, data): + reverse_bins = reversed(bin(data)[2:]) + rank = [i for i, e in enumerate(reverse_bins) if e != '0'] + return rank diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py new file mode 100644 index 00000000..f5ec24a0 --- /dev/null +++ b/pymycobot/myagvpro.py @@ -0,0 +1,530 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import threading +import time +import enum + +from .myagvapi import CommunicationProtocol, Utils, setup_serial_connect, setup_logging + + +class ProtocolCode(enum.Enum): + # System & Product Information + GET_MODIFY_VERSION = 0x01 + GET_SYSTEM_VERSION = 0x02 + POWER_ON = 0x10 + POWER_ON_ONLY = 0x19 + POWER_OFF = 0x11 + IS_POWER_ON = 0x12 + + # Motion control + AGV_MOTION_CONTROL = 0x21 + AGV_STOP_MOVING = 0x22 + SET_AUTO_REPORT_STATE = 0x23 + GET_AUTO_REPORT_STATE = 0x24 + GET_AUTO_REPORT_MESSAGE = 0x25 + + # aided + SET_MOTOR_ENABLED = 0x30 + GET_MOTOR_STATUS = 0x31 + SET_COMMUNICATION_MODE = 0x32 + GET_COMMUNICATION_MODE = 0x33 + SET_LED_COLOR = 0x34 + + GET_MOTOR_TEMPERATURE = 0x35 + GET_MOTOR_SPEEDS = 0x36 + GET_MOTOR_TORQUES = 0x37 + GET_MOTOR_ENABLE_STATUS = 0x38 + + def equal(self, other): + return self.value == other.value + + +READ_INTERFACE_INSTRUCTION_SET = ( + ProtocolCode.GET_AUTO_REPORT_MESSAGE, + ProtocolCode.GET_SYSTEM_VERSION, + ProtocolCode.IS_POWER_ON, + ProtocolCode.GET_MOTOR_STATUS, + ProtocolCode.GET_MOTOR_ENABLE_STATUS, + ProtocolCode.GET_MOTOR_SPEEDS, + ProtocolCode.GET_MOTOR_TORQUES, + ProtocolCode.GET_MOTOR_TEMPERATURE, + ProtocolCode.GET_COMMUNICATION_MODE, + ProtocolCode.GET_AUTO_REPORT_STATE, + ProtocolCode.GET_MODIFY_VERSION +) + + +class MyAGVProCommandProtocolApi(CommunicationProtocol): + + def __init__(self, debug=False, save_serial_log=False): + self.__mutex = threading.Lock() + self.__save_serial_log = save_serial_log + self.__serial_buffer = [] + self.log = setup_logging(name=f"{__name__}.{self.__class__.__name__}", debug=debug) + + def _merge(self, genre, *args): + with self.__mutex: + self.clear() + if not ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): + real_command = self._combination(genre, args) + self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") + self.write(real_command) + + for _ in range(10): + reply_data = self._read_command_buffer( + conditional=lambda x: len(x) == 14 and x[3] == genre.value, timeout=0.1 + ) + + if len(reply_data) == 0: + continue + + self.log.info(f" read: {' '.join(f'{x:02x}' for x in reply_data)}") + if reply_data[3] == genre.value: + break + else: + reply_data = None + + if self.__save_serial_log is True: + with open("serial.log", "a+") as f: + f.write(" ".join(map(str, self.__serial_buffer))) + f.write("\n") + self.__serial_buffer.clear() + + decode_respond = self._instruction_decoding(genre, reply_data) + return self._parsing_data(genre, decode_respond) + + @classmethod + def _filter(cls, data, target): + for index in range(len(data) - 1, -1, -1): + if data[index] != target: + return data[:index + 1] + return data + + @classmethod + def _instruction_decoding(cls, genre, reply_data): + if not reply_data: + return None + + index = 4 if genre in READ_INTERFACE_INSTRUCTION_SET else 5 + respond_body = reply_data[index: -2] + + if genre in ( + ProtocolCode.GET_MOTOR_TEMPERATURE, + ProtocolCode.GET_MOTOR_SPEEDS, + ProtocolCode.GET_MOTOR_TORQUES, + ProtocolCode.GET_MOTOR_STATUS, + ): + respond = [] + for i in range(0, len(respond_body), 2): + data = Utils.decode_int16(respond_body[i:i + 2]) + respond.append(data) + return respond + return respond_body + + @classmethod + def _parsing_data(cls, genre, reply_data: bytearray): + if not reply_data: + return None + + if ProtocolCode.GET_SYSTEM_VERSION.equal(genre): + return reply_data[0] / 10 + + if genre in (ProtocolCode.GET_MOTOR_TEMPERATURE, ProtocolCode.GET_MOTOR_SPEEDS, ProtocolCode.GET_MOTOR_TORQUES): + return list(data / 10 for data in reply_data) + + if ProtocolCode.GET_MOTOR_STATUS.equal(genre): + respond = [] + for item in reply_data: + if item == 0: + respond.append(0) + continue + + rank = Utils.get_bits(item) + respond.append(rank) + return respond + + if ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): + respond = [] + for index, data in enumerate(reply_data): + if index < 3: + respond.append(round(data / 100, 2)) + elif index in (3, 4): + if data == 0: + rank = data + else: + rank = Utils.get_bits(data) + respond.append(rank) + elif index == 5: + respond.append(round(data / 10, 1)) + elif index == 6: + respond.append(data) + return respond + + if genre in (ProtocolCode.GET_MOTOR_ENABLE_STATUS, ): + return list(cls._filter(reply_data, 0x00)) + + return reply_data[0] + + @classmethod + def _combination(cls, genre, params): + command_args = Utils.process_data_command(params) + while len(command_args) < 8: + command_args.append(0x00) + command = bytearray([0xfe, 0xfe, 0x0b, genre.value]) + command.extend(command_args) + crc16_check_code = Utils.crc16_check(command) + + command.extend(crc16_check_code) + return command + + def _read_command_buffer(self, timeout=1.0, conditional=None): + previous_frame = b"" + is_record = False + commands = b"" + + start_time = time.time() + while time.time() - start_time < timeout: + current_frame = self.read() + + if self.__save_serial_log is True: + print(current_frame) + self.__serial_buffer.append(current_frame) + + if current_frame == b'': + time.sleep(0.001) + continue + + if current_frame == b"\xfe" and previous_frame == b"\xfe" and is_record is False: + is_record = True + commands += b"\xfe\xfe" + continue + + previous_frame = current_frame + if is_record is False: + continue + + commands += current_frame + + cond_res = True if conditional is None else conditional(commands) + if Utils.crc16_check(commands[:-2]) == list(commands[-2:]) and cond_res: + break + else: + commands = b"" + return commands + + +class MyAGVProCommandApi(MyAGVProCommandProtocolApi): + + def get_system_version(self): + """Obtain the major firmware version number + + Returns: + float: version + """ + return self._merge(ProtocolCode.GET_SYSTEM_VERSION) + + def get_modify_version(self): + """Obtain the minor firmware version number + + Returns: + int: version + """ + return self._merge(ProtocolCode.GET_MODIFY_VERSION) + + def power_on(self): + """Turn on the robot + + Returns: + int: Power-on result, 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.POWER_ON) + + def power_on_only(self): + """Turn on the robot, but not start the control program + + Returns: + int: Power-on result only, 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.POWER_ON_ONLY) + + def power_off(self): + """Turn off the robot + + Returns: + int: Power-off result only, 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.POWER_OFF) + + def is_power_on(self): + """Check if the robot is powered on + + Returns: + int: power state, 1: Power-on, 0: Power-off + """ + return self._merge(ProtocolCode.IS_POWER_ON) + + def move_forward(self, speed): + """Pan the robot forward + + Args: + speed(float): 0 ~ 1.5 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1.5: + raise ValueError("Speed must be between 0 and 1.5") + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) + + def move_backward(self, speed): + """Pan the robot backward + + Args: + speed(float): 0 ~ 1.5 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1.5: + raise ValueError("Speed must be between 0 and 1.5") + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) + + def move_left_lateral(self, speed): + """Pan the robot left + + Args: + speed(float): 0 ~ 1 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1: + raise ValueError("Speed must be between 0 and 1") + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) + + def move_right_lateral(self, speed): + """Pan the robot right + + Args: + speed(float): 0 ~ 1 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1: + raise ValueError("Speed must be between 0 and 1") + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) + + def turn_left(self, speed): + """Rotate to the left + + Args: + speed: + + Returns: + int: 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) + + def turn_right(self, speed): + """Rotate to the right + + Args: + speed: + + Returns: + int: 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) + + def stop(self): + """Stop moving + + Returns: + int: 1: Success, 0: Failed + """ + return self._merge(ProtocolCode.AGV_STOP_MOVING) + + def set_auto_report_state(self, state): + """Set the auto-report state + + Args: + state(int): 0: Close, 1: Open + + Returns: + int: 1: Success, 0: Failed + """ + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return self._merge(ProtocolCode.SET_AUTO_REPORT_STATE, state) + + def get_auto_report_state(self): + """Get the auto-report state + + Returns: + int: 0: Close, 1: Open + """ + return self._merge(ProtocolCode.GET_AUTO_REPORT_STATE) + + def get_auto_report_message(self): + """Get the auto-report message + Returns: + list[int | list[int] | float]: + 0 - (float)rx + 1 - (float)ry + 2 - (float)rw + 3 - (list[int])Machine status + 4 - (list[int])Motor information + 5 - (float)Battery voltage + 6 - (int)Motor enable status 0: Enabled, 1: Disabled + """ + return self._merge(ProtocolCode.GET_AUTO_REPORT_MESSAGE) + + def set_motor_enable(self, motor_id, state): + """Enable or disable the motor + + Args: + motor_id(int): + 1: Left upper motor + 2: Right upper motor + 3: Left lower motor + 4: Right lower motor + 254: All motors + state(bool): + 0: Disable + 1: Enable + Returns: + int: 1: Success, 0: Failed + """ + if motor_id not in (1, 2, 3, 4, 254): + raise ValueError("Motor ID must be 0 or 1") + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return self._merge(ProtocolCode.SET_MOTOR_ENABLED, motor_id, state) + + def get_motor_status(self): + """Get the motor status + + Returns: + list[int]: Motor status + 0: normal + any: error code + """ + return self._merge(ProtocolCode.GET_MOTOR_STATUS) + + def get_motor_temps(self): + """Get the motor temperature + + Returns: + list[float]: Motor temperature + """ + return self._merge(ProtocolCode.GET_MOTOR_TEMPERATURE) + + def get_motor_speeds(self): + """Get the motor speeds + + Returns: + list[float]: Motor speeds + """ + return self._merge(ProtocolCode.GET_MOTOR_SPEEDS) + + def get_motor_torques(self): + """Get the motor torques + + Returns: + list[float]: Motor torques + """ + return self._merge(ProtocolCode.GET_MOTOR_TORQUES) + + def get_motor_enable_status(self): + """Get the motor enabled status + Returns: + list[int]: Motor enabled status + 0: Disable + 1: Enable + """ + return self._merge(ProtocolCode.GET_MOTOR_ENABLE_STATUS) + + def set_communication_state(self, state): + """Set the communication state + + Args: + state(int): + 0: Serial communication + 1: Socket communication + 2: Bluetooth communication + + Returns: + int: 1: Success, 0: Failed + """ + if state not in (0, 1, 2): + raise ValueError("State must be 0, 1 or 2") + + return self._merge(ProtocolCode.SET_COMMUNICATION_MODE, state) + + def get_communication_state(self): + """Get the communication state + + Returns: + int: communication state + 0: Serial communication, + 1: Socket communication, + 2: Bluetooth communication + """ + return self._merge(ProtocolCode.GET_COMMUNICATION_MODE) + + def set_led_color(self, position, brightness, color): + """Set the LED color + + Args: + position(int): + 0: Left LED + 1: Right LED + brightness(int): 0 - 255 + color(tuple(int, int, int)): RGB color + + Returns: + int: 1: Success, 0: Failed + """ + if position not in (0, 1): + raise ValueError("Position must be 0 or 1") + + if not 0 <= brightness <= 255: + raise ValueError("Brightness must be between 0 and 255") + + if any(not 0 <= c <= 255 for c in color): + raise ValueError("Color must be between 0 and 255") + + return self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) + + +class MyAGVPro(MyAGVProCommandApi): + + def __init__(self, port, baudrate=1000000, timeout=0.1, debug=False, save_serial_log=False): + super().__init__(debug=debug, save_serial_log=save_serial_log) + self._serial = setup_serial_connect(port=port, baudrate=baudrate, timeout=timeout) + + def write(self, command): + return self._serial.write(command) + + def read(self, size=1): + return self._serial.read(size) + + def close(self): + if self._serial.is_open: + self._serial.close() + + def open(self): + if not self._serial.is_open: + self._serial.open() + + def is_open(self): + return self._serial.is_open + + def clear(self): + self._serial.reset_input_buffer() + self._serial.reset_output_buffer() From 06ce263aa165806d532a0c78a0404de0d7eb416d Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 5 Jun 2025 10:47:27 +0800 Subject: [PATCH 25/57] fix(ConveyorApi):Fix the problem that no data is returned --- pymycobot/conveyor_api.py | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/pymycobot/conveyor_api.py b/pymycobot/conveyor_api.py index d55d6236..7a9c3aba 100644 --- a/pymycobot/conveyor_api.py +++ b/pymycobot/conveyor_api.py @@ -2,7 +2,18 @@ import threading import time import struct -from serial import Serial +import serial + + +def setup_serial_connect(port, baudrate, timeout=None): + serial_api = serial.Serial() + serial_api.port = port + serial_api.baudrate = baudrate + serial_api.timeout = timeout + serial_api.rts = False + serial_api.dtr = False + serial_api.open() + return serial_api class CommandGenre(object): @@ -40,7 +51,7 @@ def get_params(self): return self.__params[0] if self.__length == 1 else self.__params def __str__(self): - return " ".join(map(lambda bit: hex(bit).upper(), self.to_bytes())) + return ' '.join(f'{x:02x}' for x in self.to_bytes()) def __bytes__(self): return self.to_bytes() @@ -69,7 +80,6 @@ def unpack_args(cls, *parameters): bits_pack_list.extend(list(pair)) else: bits_pack_list.clear() - print(bits_pack_list) return bits_pack_list @classmethod @@ -100,9 +110,7 @@ def __init__(self, comport, baudrate, timeout=0.5): self._comport = comport self._baudrate = baudrate self._timeout = timeout - self._serial_port = Serial(port=comport, baudrate=baudrate, timeout=timeout) - self._serial_port.rts = True - self._serial_port.dtr = True + self._serial_port = setup_serial_connect(port=comport, baudrate=baudrate, timeout=timeout) def open(self): if self._serial_port.is_open is False: From ec385ec4a3c8cc7fe8e2c714d0708f791e82d37e Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 11:48:30 +0800 Subject: [PATCH 26/57] feat(MyAGVPro): Adapt to Bluetooth and socket TCP communication modes --- docs/MYAGVPro_zh.md | 210 +++++++++++++++ docs/MyAGVPro_en.md | 210 +++++++++++++++ pymycobot/__init__.py | 4 + pymycobot/myagvapi.py | 5 + pymycobot/myagvpro.py | 316 +++++++++++++++++----- pymycobot/myagvpro_bluetooth.py | 450 ++++++++++++++++++++++++++++++++ pymycobot/myagvpro_socket.py | 40 +++ requirements.txt | 1 + 8 files changed, 1169 insertions(+), 67 deletions(-) create mode 100644 docs/MYAGVPro_zh.md create mode 100644 docs/MyAGVPro_en.md create mode 100644 pymycobot/myagvpro_bluetooth.py create mode 100644 pymycobot/myagvpro_socket.py diff --git a/docs/MYAGVPro_zh.md b/docs/MYAGVPro_zh.md new file mode 100644 index 00000000..6c1c6fb8 --- /dev/null +++ b/docs/MYAGVPro_zh.md @@ -0,0 +1,210 @@ +# class MyAGVPro() + +### 1. ϵͳ & ƷϢ + +#### def get_system_version(self) -> None: +- **:** ȡ̼汾 +- **ֵ:** + - **float: version** + +#### def get_modify_version(self) -> None: +- **:** ȡι̼汾 +- **ֵ:** + - **int: version** + +#### def power_on(self) -> None: +- **:** +- **ֵ:** + - **int: , 1: ɹ, 0: ʧ** + +#### def power_on_only(self) -> None: +- **:** ˣƳ +- **ֵ:** + - **int: , 1: ɹ, 0: ʧ** + +#### def power_off(self) -> None: +- **:** رջ +- **ֵ:** + - **int: رս, 1: ɹ, 0: ʧ** + +#### def is_power_on(self) -> None: +- **:** Ƿѿ +- **ֵ:** + - **int: Դ״̬, 1: , 0: ر** + +### 2. ˶ + +#### def move_backward(self, speed) -> None: +- **:** ƽƻ +- **:** + - **speed(float): 0 ~ 1.5 m/s** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def move_forward(self, speed) -> None: +- **:** ƽƻǰ +- **:** + - **speed(float): 0 ~ 1.5 m/s** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def move_left_lateral(self, speed) -> None: +- **:** ƽƻ +- **:** + - **speed(float): 0 ~ 1 m/s** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def move_right_lateral(self, speed) -> None: +- **:** ƽƻ +- **:** + - **speed(float): 0 ~ 1 m/s** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def turn_left(self, speed) -> None: +- **:** ת +- **:** + - **speed:** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def turn_right(self, speed) -> None: +- **:** ת +- **:** + - **speed:** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def stop(self) -> None: +- **:** ֹͣƶ +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def set_auto_report_state(self, state) -> None: +- **:** Զ״̬ +- **:** + - **state(int): 0: ر, 1: ** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def get_auto_report_state(self) -> None: +- **:** ȡԶ״̬ +- **ֵ:** + - **int: 0: ر, 1: ** + +#### def get_auto_report_message(self) -> None: +- **:** ȡԶϢ +- **ֵ:** + - **list[int | list[int] | float]:** + - **0 - (float)rx** + - **1 - (float)ry** + - **2 - (float)rw** + - **3 - (list[int])״̬** + - **4 - (list[int])Ϣ** + - **5 - (float)صѹ** + - **6 - (int)ʹ״̬ 0: , 1: ** + +### 3. + +#### def get_motor_enable_status(self) -> None: +- **:** ȡʹ״̬ +- **ֵ:** + - **list[int]: ʹ״̬** + - **0: ** + - **1: ** + +#### def get_motor_status(self) -> None: +- **:** ȡ״̬ +- **ֵ:** + - **list[int]: ״̬** + - **0: ** + - **any: ** + +#### def get_motor_temps(self) -> None: +- **:** ȡ¶ +- **ֵ:** + - **list[float]: ¶** + +#### def get_motor_speeds(self) -> None: +- **:** ȡٶ +- **ֵ:** + - **list[float]: ٶ** + +#### def get_motor_torques(self) -> None: +- **:** ȡŤ +- **ֵ:** + - **list[float]: Ť** + +#### def set_communication_state(self, state) -> None: +- **:** ͨѶ״̬ +- **:** + - **state(int):** + - **0: ͨѶ (Ĭ)** + - **1: Socket ͨѶ** + - **2: ͨѶ ( MAC ַдļͶ˵㣬Ȼ󷵻ص״̬)** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def get_communication_state(self) -> None: +- **:** ȡͨѶ״̬ +- **ֵ:** + - **int: ͨѶ״̬** + - **0: ͨѶ,** + - **1: Socket ͨѶ,** + - **2: ͨѶ** + +#### def set_led_color(self, position, brightness, color) -> None: +- **:** LED ɫ +- **:** + - **position(int):** + - **0: LED** + - **1: Ҳ LED** + - **brightness(int): 0 - 255** + - **color(tuple(int, int, int)): RGB ɫ** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +#### def get_motor_loss_count(self) -> None: +- **:** ȡ +- **ֵ:** + - **list[int]: ** + +### 4. IO + +#### def get_pin_input(self, pin) -> None: +- **:** ȡ IO +- **:** + - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** +- **ֵ:** + - **int: 0: ͵ƽ, 1: ߵƽ, -1: û** + +#### def set_pin_output(self, pin, state) -> None: +- **:** IO +- **:** + - **pin(int): 1 - 6** + - **state(int): 0: ͵ƽ, 1: ߵƽ** +- **ֵ:** + - **int: 1: ɹ, 0: ʧ** + +### 5. WiFi & + +#### def get_wifi_ip_port(self) -> None: +- **:** ȡ wi-fi ip Ͷ˿ +- **ֵ:** + - **tuple(str, int): wi-fi ip, wi-fi ˿** + +#### def get_wifi_account(self) -> None: +- **:** ȡ wi-fi ˺ +- **ֵ:** + - **tuple(str, str): wi-fi ˺, wi-fi ** + +#### def get_bluetooth_address(self) -> None: +- **:** ȡ MAC ַ +- **ֵ:** + - **str: MAC ַ** + +#### def get_bluetooth_uuid(self) -> None: +- **:** ȡ uuid +- **ֵ:** + - **tuple(str, str, str): , uuid, uuid** diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md new file mode 100644 index 00000000..6cfdd945 --- /dev/null +++ b/docs/MyAGVPro_en.md @@ -0,0 +1,210 @@ +# class MyAGVPro() + +### 1. System & Product Information + +#### def get_system_version(self) -> None: +- **function:** Obtain the major firmware version number +- **Return value:** + - **float: version** + +#### def get_modify_version(self) -> None: +- **function:** Obtain the minor firmware version number +- **Return value:** + - **int: version** + +#### def power_on(self) -> None: +- **function:** Turn on the robot +- **Return value:** + - **int: Power-on result, 1: Success, 0: Failed** + +#### def power_on_only(self) -> None: +- **function:** Turn on the robot, but not start the control program +- **Return value:** + - **int: Power-on result only, 1: Success, 0: Failed** + +#### def power_off(self) -> None: +- **function:** Turn off the robot +- **Return value:** + - **int: Power-off result only, 1: Success, 0: Failed** + +#### def is_power_on(self) -> None: +- **function:** Check if the robot is powered on +- **Return value:** + - **int: power state, 1: Power-on, 0: Power-off** + +### 2. Motion control + +#### def move_backward(self, speed) -> None: +- **function:** Pan the robot backward +- **parameter:** + - **speed(float): 0 ~ 1.5 m/s** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def move_forward(self, speed) -> None: +- **function:** Pan the robot forward +- **parameter:** + - **speed(float): 0 ~ 1.5 m/s** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def move_left_lateral(self, speed) -> None: +- **function:** Pan the robot left +- **parameter:** + - **speed(float): 0 ~ 1 m/s** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def move_right_lateral(self, speed) -> None: +- **function:** Pan the robot right +- **parameter:** + - **speed(float): 0 ~ 1 m/s** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def turn_left(self, speed) -> None: +- **function:** Rotate to the left +- **parameter:** + - **speed:** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def turn_right(self, speed) -> None: +- **function:** Rotate to the right +- **parameter:** + - **speed:** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def stop(self) -> None: +- **function:** Stop moving +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def set_auto_report_state(self, state) -> None: +- **function:** Set the auto-report state +- **parameter:** + - **state(int): 0: Close, 1: Open** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def get_auto_report_state(self) -> None: +- **function:** Get the auto-report state +- **Return value:** + - **int: 0: Close, 1: Open** + +#### def get_auto_report_message(self) -> None: +- **function:** Get the auto-report message +- **Return value:** + - **list[int | list[int] | float]:** + - **0 - (float)rx** + - **1 - (float)ry** + - **2 - (float)rw** + - **3 - (list[int])Machine status** + - **4 - (list[int])Motor information** + - **5 - (float)Battery voltage** + - **6 - (int)Motor enable status 0: Enabled, 1: Disabled** + +### 3. Motor assisted + +#### def get_motor_enable_status(self) -> None: +- **function:** Get the motor enabled status +- **Return value:** + - **list[int]: Motor enabled status** + - **0: Disable** + - **1: Enable** + +#### def get_motor_status(self) -> None: +- **function:** Get the motor status +- **Return value:** + - **list[int]: Motor status** + - **0: normal** + - **any: error code** + +#### def get_motor_temps(self) -> None: +- **function:** Get the motor temperature +- **Return value:** + - **list[float]: Motor temperature** + +#### def get_motor_speeds(self) -> None: +- **function:** Get the motor speeds +- **Return value:** + - **list[float]: Motor speeds** + +#### def get_motor_torques(self) -> None: +- **function:** Get the motor torques +- **Return value:** + - **list[float]: Motor torques** + +#### def set_communication_state(self, state) -> None: +- **function:** Set the communication state +- **parameter:** + - **state(int):** + - **0: Serial communication (default)** + - **1: Socket communication** + - **2: Bluetooth communication (Write the MAC address to the file and the endpoint, and then return to the state)** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def get_communication_state(self) -> None: +- **function:** Get the communication state +- **Return value:** + - **int: communication state** + - **0: Serial communication,** + - **1: Socket communication,** + - **2: Bluetooth communication** + +#### def set_led_color(self, position, brightness, color) -> None: +- **function:** Set the LED color +- **parameter:** + - **position(int):** + - **0: Left LED** + - **1: Right LED** + - **brightness(int): 0 - 255** + - **color(tuple(int, int, int)): RGB color** +- **Return value:** + - **int: 1: Success, 0: Failed** + +#### def get_motor_loss_count(self) -> None: +- **function:** Get the motor loss count +- **Return value:** + - **list[int]: Motor loss count** + +### 4. IO Control + +#### def get_pin_input(self, pin) -> None: +- **function:** Get the input IO +- **parameter:** + - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** +- **Return value:** + - **int: 0: Low, 1: High, -1: There is no such pin** + +#### def set_pin_output(self, pin, state) -> None: +- **function:** Set the output IO +- **parameter:** + - **pin(int): 1 - 6** + - **state(int): 0: Low, 1: High** +- **Return value:** + - **int: 1: Success, 0: Failed** + +### 5. WiFi & Bluetooth + +#### def get_wifi_ip_port(self) -> None: +- **function:** Get the wi-fi ip and port +- **Return value:** + - **tuple(str, int): wi-fi ip, wi-fi port** + +#### def get_wifi_account(self) -> None: +- **function:** Get the wi-fi account +- **Return value:** + - **tuple(str, str): wi-fi account, wi-fi password** + +#### def get_bluetooth_address(self) -> None: +- **function:** Get the bluetooth MAC address +- **Return value:** + - **str: bluetooth MAC address** + +#### def get_bluetooth_uuid(self) -> None: +- **function:** Get the bluetooth uuid +- **Return value:** + - **tuple(str, str, str): bluetooth name, service uuid, characteristic uuid** \ No newline at end of file diff --git a/pymycobot/__init__.py b/pymycobot/__init__.py index 5eb91f3d..9d33b0af 100644 --- a/pymycobot/__init__.py +++ b/pymycobot/__init__.py @@ -29,6 +29,8 @@ from pymycobot.mercury import Mercury from pymycobot.myagv import MyAgv from pymycobot.myagvpro import MyAGVPro +from pymycobot.myagvpro_socket import MyAGVProSocket +from pymycobot.myagvpro_bluetooth import MyAGVProBluetooth from pymycobot.myarmsocket import MyArmSocket from pymycobot.mecharmsocket import MechArmSocket # from pymycobot.mycobotpro630 import Phoenix @@ -72,6 +74,8 @@ "Mercury", "MyAgv", "MyAGVPro", + "MyAGVProSocket", + "MyAGVProBluetooth", "MechArmSocket", "MyArmSocket", "MercurySocket", diff --git a/pymycobot/myagvapi.py b/pymycobot/myagvapi.py index 7a38c4d1..fec6d2ca 100644 --- a/pymycobot/myagvapi.py +++ b/pymycobot/myagvapi.py @@ -128,6 +128,11 @@ def crc16_check(cls, command): crc_res[i] = ord(crc_res[i]) return crc_res + @classmethod + def crc16_check_bytes(cls, command): + data = cls.crc16_check(command) + return bytes(bytearray(data)) + @classmethod def get_bits(cls, data): reverse_bins = reversed(bin(data)[2:]) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index f5ec24a0..1f387410 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -1,5 +1,6 @@ #!/usr/bin/env python # -*- coding: UTF-8 -*- +import re import threading import time import enum @@ -14,7 +15,7 @@ class ProtocolCode(enum.Enum): POWER_ON = 0x10 POWER_ON_ONLY = 0x19 POWER_OFF = 0x11 - IS_POWER_ON = 0x12 + GET_POWER_STATE = 0x12 # Motion control AGV_MOTION_CONTROL = 0x21 @@ -34,64 +35,123 @@ class ProtocolCode(enum.Enum): GET_MOTOR_SPEEDS = 0x36 GET_MOTOR_TORQUES = 0x37 GET_MOTOR_ENABLE_STATUS = 0x38 + GET_MOTOR_LOSS_COUNT = 0x39 + + SET_OUTPUT_IO = 0x40 + GET_INPUT_IO = 0x41 + + SET_LED_MODE = 0x3A + + GET_WIFI_ACCOUNT = 0x50 + GET_WIFI_IP_PORT = 0x51 + GET_BLUETOOTH_UUID = 0x52 + GET_BLUETOOTH_ADDRESS = 0x53 def equal(self, other): return self.value == other.value -READ_INTERFACE_INSTRUCTION_SET = ( - ProtocolCode.GET_AUTO_REPORT_MESSAGE, - ProtocolCode.GET_SYSTEM_VERSION, - ProtocolCode.IS_POWER_ON, - ProtocolCode.GET_MOTOR_STATUS, - ProtocolCode.GET_MOTOR_ENABLE_STATUS, - ProtocolCode.GET_MOTOR_SPEEDS, - ProtocolCode.GET_MOTOR_TORQUES, - ProtocolCode.GET_MOTOR_TEMPERATURE, - ProtocolCode.GET_COMMUNICATION_MODE, - ProtocolCode.GET_AUTO_REPORT_STATE, - ProtocolCode.GET_MODIFY_VERSION +PLAINTEXT_REPLY_PROTOCOL_CODE = ( + ProtocolCode.GET_WIFI_ACCOUNT, + ProtocolCode.GET_WIFI_IP_PORT, + ProtocolCode.GET_BLUETOOTH_UUID, + ProtocolCode.GET_BLUETOOTH_ADDRESS ) class MyAGVProCommandProtocolApi(CommunicationProtocol): + genre_timeout_table = { + ProtocolCode.POWER_ON: 2.1 + } def __init__(self, debug=False, save_serial_log=False): - self.__mutex = threading.Lock() - self.__save_serial_log = save_serial_log - self.__serial_buffer = [] + self._mutex = threading.Lock() + self._save_serial_log = save_serial_log + self._data_buffer = [] + self._serial_filename = "serial.log" + self._communication_mode = 0 self.log = setup_logging(name=f"{__name__}.{self.__class__.__name__}", debug=debug) - def _merge(self, genre, *args): - with self.__mutex: - self.clear() - if not ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): - real_command = self._combination(genre, args) - self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") - self.write(real_command) + def _save_buffer_data(self, data, to_local=False): + if self._save_serial_log is False: + return + + self._data_buffer.append(data) + + if to_local is True: + self._save_file(self._serial_filename, " ".join(map(str, self._data_buffer)) + "\n") + self._data_buffer.clear() - for _ in range(10): - reply_data = self._read_command_buffer( - conditional=lambda x: len(x) == 14 and x[3] == genre.value, timeout=0.1 - ) + @staticmethod + def _save_file(filename, data): + with open(filename, "a+") as f: + f.write(data) + def _match_protocol_data(self, genre, timeout=0.1): + is_save_mac_addr = False + for _ in range(10): + if ProtocolCode.SET_COMMUNICATION_MODE.equal(genre) and self._communication_mode == 2: + data = self._read_plaintext_data(timeout=timeout) + if len(data) == 0: + continue + + if is_save_mac_addr is False: + mac_addr = self._parsing_data(ProtocolCode.GET_BLUETOOTH_ADDRESS, data.decode('utf-8')) + info = f"MyAGVPro Bluetooth MAC Address: {mac_addr}" + self._save_file("AGVPro_BLUETOOTH_MAC_ADDR", info) + is_save_mac_addr = True + print(info) + + reply_data = self._read_protocol_data(timeout=timeout) if len(reply_data) == 0: continue - self.log.info(f" read: {' '.join(f'{x:02x}' for x in reply_data)}") - if reply_data[3] == genre.value: - break + break + + if genre in PLAINTEXT_REPLY_PROTOCOL_CODE: + reply_data = self._read_plaintext_data(timeout=timeout) else: - reply_data = None + reply_data = self._read_protocol_data(timeout=timeout) - if self.__save_serial_log is True: - with open("serial.log", "a+") as f: - f.write(" ".join(map(str, self.__serial_buffer))) - f.write("\n") - self.__serial_buffer.clear() + if len(reply_data) == 0: + continue + + self.log.info(f" read: {' '.join(f'{x:02x}' for x in reply_data)}") + break + else: + reply_data = None + return reply_data + + def _read_plaintext_data(self, timeout=0.1): + reply_data = self._read_command_buffer( + start_flag_caller=lambda: b'AGVPro:', + end_flag_caller=lambda cmds: b'\r\n', + timeout=timeout + ) + return reply_data + + def _read_protocol_data(self, timeout=0.1): + reply_data = self._read_command_buffer( + start_flag_caller=lambda: b'\xfe\xfe', + end_flag_caller=lambda cmds: Utils.crc16_check_bytes(cmds[:-2]), + timeout=timeout + ) + return reply_data + + def _merge(self, genre, *args): + with self._mutex: + self.clear() + timeout = self.genre_timeout_table.get(genre, 0.1) + if not ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): + real_command = self._combination(genre, args) + self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") + self.write(real_command) + reply_data = self._match_protocol_data(genre, timeout) decode_respond = self._instruction_decoding(genre, reply_data) - return self._parsing_data(genre, decode_respond) + data = self._parsing_data(genre, decode_respond) + self._save_buffer_data(b'', to_local=True) + return data @classmethod def _filter(cls, data, target): @@ -105,14 +165,16 @@ def _instruction_decoding(cls, genre, reply_data): if not reply_data: return None - index = 4 if genre in READ_INTERFACE_INSTRUCTION_SET else 5 - respond_body = reply_data[index: -2] + respond_body = reply_data[4: -2] + if genre in PLAINTEXT_REPLY_PROTOCOL_CODE: + respond_body = reply_data.decode("utf-8") if genre in ( ProtocolCode.GET_MOTOR_TEMPERATURE, ProtocolCode.GET_MOTOR_SPEEDS, ProtocolCode.GET_MOTOR_TORQUES, ProtocolCode.GET_MOTOR_STATUS, + ProtocolCode.GET_MOTOR_LOSS_COUNT ): respond = [] for i in range(0, len(respond_body), 2): @@ -122,16 +184,40 @@ def _instruction_decoding(cls, genre, reply_data): return respond_body @classmethod - def _parsing_data(cls, genre, reply_data: bytearray): + def _parsing_data(cls, genre, reply_data): if not reply_data: return None if ProtocolCode.GET_SYSTEM_VERSION.equal(genre): return reply_data[0] / 10 - if genre in (ProtocolCode.GET_MOTOR_TEMPERATURE, ProtocolCode.GET_MOTOR_SPEEDS, ProtocolCode.GET_MOTOR_TORQUES): + if ProtocolCode.GET_MOTOR_TEMPERATURE.equal(genre): return list(data / 10 for data in reply_data) + if genre in (ProtocolCode.GET_MOTOR_SPEEDS, ProtocolCode.GET_MOTOR_TORQUES): + return list(data / 100 for data in reply_data) + + if ProtocolCode.GET_MOTOR_LOSS_COUNT.equal(genre): + return list(reply_data) + + if ProtocolCode.GET_WIFI_ACCOUNT.equal(genre): + data = re.findall(r'AGVPro:WIFI:S:(.*);P:(.*);', reply_data) + return data[0] if len(data) == 1 else None + + if ProtocolCode.GET_WIFI_IP_PORT.equal(genre): + data = re.findall(r'AGVPro:WIFI:IP:(.*);PORT:(.*);', reply_data) + if len(data) == 0: + return None + return data[0][0], int(data[0][1]) + + if ProtocolCode.GET_BLUETOOTH_UUID.equal(genre): + data = re.findall(r'AGVPro:BLE::Name:(.*);Service_UUID:(.*);CHAR_UUID:(.*);', reply_data) + return data[0] if len(data) == 1 else None + + if ProtocolCode.GET_BLUETOOTH_ADDRESS.equal(genre): + data = re.findall(r'AGVPro:BLE:MAC:(.*)', reply_data) + return data[0] if len(data) == 1 else None + if ProtocolCode.GET_MOTOR_STATUS.equal(genre): respond = [] for item in reply_data: @@ -160,8 +246,13 @@ def _parsing_data(cls, genre, reply_data: bytearray): respond.append(data) return respond - if genre in (ProtocolCode.GET_MOTOR_ENABLE_STATUS, ): - return list(cls._filter(reply_data, 0x00)) + if ProtocolCode.GET_MOTOR_ENABLE_STATUS.equal(genre): + return list(reply_data[:4]) + + if ProtocolCode.GET_INPUT_IO.equal(genre): + if reply_data[0] == 255: + return -1 + return reply_data[1] return reply_data[0] @@ -177,40 +268,41 @@ def _combination(cls, genre, params): command.extend(crc16_check_code) return command - def _read_command_buffer(self, timeout=1.0, conditional=None): - previous_frame = b"" - is_record = False - commands = b"" - + def _read_by_timeout(self, timeout=1.0): start_time = time.time() while time.time() - start_time < timeout: - current_frame = self.read() + data = self.read(1) + if len(data) == 0: + continue - if self.__save_serial_log is True: - print(current_frame) - self.__serial_buffer.append(current_frame) + yield data - if current_frame == b'': - time.sleep(0.001) - continue + self._save_buffer_data(data) + + def _read_command_buffer(self, start_flag_caller, end_flag_caller, timeout=1.0): + channel_buffer = b"" + real_command = b"" + is_record = False - if current_frame == b"\xfe" and previous_frame == b"\xfe" and is_record is False: + for data in self._read_by_timeout(timeout): + channel_buffer += data + + start_flag = start_flag_caller() + if channel_buffer.endswith(start_flag) and is_record is False: + real_command = start_flag is_record = True - commands += b"\xfe\xfe" continue - previous_frame = current_frame if is_record is False: continue - commands += current_frame - - cond_res = True if conditional is None else conditional(commands) - if Utils.crc16_check(commands[:-2]) == list(commands[-2:]) and cond_res: + real_command += data + end_flag = end_flag_caller(real_command) + if real_command.endswith(end_flag): break else: - commands = b"" - return commands + real_command = b"" + return real_command class MyAGVProCommandApi(MyAGVProCommandProtocolApi): @@ -261,7 +353,7 @@ def is_power_on(self): Returns: int: power state, 1: Power-on, 0: Power-off """ - return self._merge(ProtocolCode.IS_POWER_ON) + return self._merge(ProtocolCode.GET_POWER_STATE) def move_forward(self, speed): """Pan the robot forward @@ -449,14 +541,22 @@ def get_motor_enable_status(self): """ return self._merge(ProtocolCode.GET_MOTOR_ENABLE_STATUS) + def get_motor_loss_count(self): + """Get the motor loss count + + Returns: + list[int]: Motor loss count + """ + return self._merge(ProtocolCode.GET_MOTOR_LOSS_COUNT) + def set_communication_state(self, state): """Set the communication state Args: state(int): - 0: Serial communication + 0: Serial communication (default) 1: Socket communication - 2: Bluetooth communication + 2: Bluetooth communication (Write the MAC address to the file and the endpoint, and then return to the state) Returns: int: 1: Success, 0: Failed @@ -464,6 +564,7 @@ def set_communication_state(self, state): if state not in (0, 1, 2): raise ValueError("State must be 0, 1 or 2") + self._communication_mode = state return self._merge(ProtocolCode.SET_COMMUNICATION_MODE, state) def get_communication_state(self): @@ -501,12 +602,93 @@ def set_led_color(self, position, brightness, color): return self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) + def set_led_mode(self, mode): + """Set the LED mode + + Args: + mode(int): + 0: Battery level(default) + 1: DIY + + Returns: + int: 1: Success, 0: Failed + """ + if mode not in (0, 1): + raise ValueError("Mode must be 0 or 1") + return self._merge(ProtocolCode.SET_LED_MODE, mode) + + def set_pin_output(self, pin, state): + """Set the output IO + + Args: + pin(int): 1 - 6 + state(int): 0: Low, 1: High + + Returns: + int: 1: Success, 0: Failed + """ + if not 1 <= pin <= 6: + raise ValueError("Pin must be between 1 and 6") + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return self._merge(ProtocolCode.SET_OUTPUT_IO, pin, state) + + def get_pin_input(self, pin): + """Get the input IO + + Args: + pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254 + + Returns: + int: 0: Low, 1: High, -1: There is no such pin + """ + supported_pins = [1, 2, 3, 4, 5, 6, 7, 8, 254] + if pin not in supported_pins: + raise ValueError(f"Pin must be in {supported_pins}") + return self._merge(ProtocolCode.GET_INPUT_IO, pin) + + def get_wifi_account(self): + """Get the wi-fi account + + Returns: + tuple(str, str): wi-fi account, wi-fi password + """ + return self._merge(ProtocolCode.GET_WIFI_ACCOUNT) + + def get_wifi_ip_port(self): + """Get the wi-fi ip and port + Returns: + tuple(str, int): wi-fi ip, wi-fi port + """ + return self._merge(ProtocolCode.GET_WIFI_IP_PORT) + + def get_bluetooth_uuid(self): + """Get the bluetooth uuid + + Returns: + tuple(str, str, str): bluetooth name, service uuid, characteristic uuid + """ + + return self._merge(ProtocolCode.GET_BLUETOOTH_UUID) + + def get_bluetooth_address(self): + """Get the bluetooth MAC address + + Returns: + str: bluetooth MAC address + """ + + return self._merge(ProtocolCode.GET_BLUETOOTH_ADDRESS) + class MyAGVPro(MyAGVProCommandApi): def __init__(self, port, baudrate=1000000, timeout=0.1, debug=False, save_serial_log=False): super().__init__(debug=debug, save_serial_log=save_serial_log) self._serial = setup_serial_connect(port=port, baudrate=baudrate, timeout=timeout) + self._serial_filename = 'agvpro_serial_serial.log' def write(self, command): return self._serial.write(command) diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py new file mode 100644 index 00000000..2852d849 --- /dev/null +++ b/pymycobot/myagvpro_bluetooth.py @@ -0,0 +1,450 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +from .myagvpro import MyAGVProCommandProtocolApi, ProtocolCode, PLAINTEXT_REPLY_PROTOCOL_CODE +from bleak import BleakClient + + +class MyAGVProCommandApi(MyAGVProCommandProtocolApi): + + async def _match_protocol_data(self, genre, timeout=0.1): + for _ in range(20): + reply_data = await self.read() + + if len(reply_data) == 0: + continue + + self._save_buffer_data(data=reply_data, to_local=True) + + if genre in PLAINTEXT_REPLY_PROTOCOL_CODE: + if not reply_data.startswith(b"AGVPro:"): + continue + else: + if reply_data[3] != genre.value: + continue + + self.log.info(f" read: {' '.join(f'{x:02x}' for x in reply_data)}") + break + else: + reply_data = None + return reply_data + + async def _merge(self, genre, *args): + with self._mutex: + timeout = self.genre_timeout_table.get(genre, 0.1) + if not ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): + real_command = self._combination(genre, args) + self.log.info(f"write: {' '.join(f'{x:02x}' for x in real_command)}") + await self.write(real_command) + + reply_data = await self._match_protocol_data(genre, timeout) + decode_respond = self._instruction_decoding(genre, reply_data) + return self._parsing_data(genre, decode_respond) + + async def get_system_version(self): + """Obtain the major firmware version number + + Returns: + float: version + """ + return await self._merge(ProtocolCode.GET_SYSTEM_VERSION) + + async def get_modify_version(self): + """Obtain the minor firmware version number + + Returns: + int: version + """ + return await self._merge(ProtocolCode.GET_MODIFY_VERSION) + + async def power_on(self): + """Turn on the robot + + Returns: + int: Power-on result, 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.POWER_ON) + + async def power_on_only(self): + """Turn on the robot, but not start the control program + + Returns: + int: Power-on result only, 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.POWER_ON_ONLY) + + async def power_off(self): + """Turn off the robot + + Returns: + int: Power-off result only, 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.POWER_OFF) + + async def is_power_on(self): + """Check if the robot is powered on + + Returns: + int: power state, 1: Power-on, 0: Power-off + """ + return await self._merge(ProtocolCode.GET_POWER_STATE) + + async def move_forward(self, speed): + """Pan the robot forward + + Args: + speed(float): 0 ~ 1.5 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1.5: + raise ValueError("Speed must be between 0 and 1.5") + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) + + async def move_backward(self, speed): + """Pan the robot backward + + Args: + speed(float): 0 ~ 1.5 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1.5: + raise ValueError("Speed must be between 0 and 1.5") + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) + + async def move_left_lateral(self, speed): + """Pan the robot left + + Args: + speed(float): 0 ~ 1 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1: + raise ValueError("Speed must be between 0 and 1") + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) + + async def move_right_lateral(self, speed): + """Pan the robot right + + Args: + speed(float): 0 ~ 1 m/s + + Returns: + int: 1: Success, 0: Failed + """ + if not 0 <= speed <= 1: + raise ValueError("Speed must be between 0 and 1") + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) + + async def turn_left(self, speed): + """Rotate to the left + + Args: + speed: + + Returns: + int: 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) + + async def turn_right(self, speed): + """Rotate to the right + + Args: + speed: + + Returns: + int: 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) + + async def stop(self): + """Stop moving + + Returns: + int: 1: Success, 0: Failed + """ + return await self._merge(ProtocolCode.AGV_STOP_MOVING) + + async def set_auto_report_state(self, state): + """Set the auto-report state + + Args: + state(int): 0: Close, 1: Open + + Returns: + int: 1: Success, 0: Failed + """ + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return await self._merge(ProtocolCode.SET_AUTO_REPORT_STATE, state) + + async def get_auto_report_state(self): + """Get the auto-report state + + Returns: + int: 0: Close, 1: Open + """ + return await self._merge(ProtocolCode.GET_AUTO_REPORT_STATE) + + async def get_auto_report_message(self): + """Get the auto-report message + Returns: + list[int | list[int] | float]: + 0 - (float)rx + 1 - (float)ry + 2 - (float)rw + 3 - (list[int])Machine status + 4 - (list[int])Motor information + 5 - (float)Battery voltage + 6 - (int)Motor enable status 0: Enabled, 1: Disabled + """ + return await self._merge(ProtocolCode.GET_AUTO_REPORT_MESSAGE) + + async def set_motor_enable(self, motor_id, state): + """Enable or disable the motor + + Args: + motor_id(int): + 1: Left upper motor + 2: Right upper motor + 3: Left lower motor + 4: Right lower motor + 254: All motors + state(bool): + 0: Disable + 1: Enable + Returns: + int: 1: Success, 0: Failed + """ + if motor_id not in (1, 2, 3, 4, 254): + raise ValueError("Motor ID must be 0 or 1") + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return await self._merge(ProtocolCode.SET_MOTOR_ENABLED, motor_id, state) + + async def get_motor_status(self): + """Get the motor status + + Returns: + list[int]: Motor status + 0: normal + any: error code + """ + return await self._merge(ProtocolCode.GET_MOTOR_STATUS) + + async def get_motor_temps(self): + """Get the motor temperature + + Returns: + list[float]: Motor temperature + """ + return await self._merge(ProtocolCode.GET_MOTOR_TEMPERATURE) + + async def get_motor_speeds(self): + """Get the motor speeds + + Returns: + list[float]: Motor speeds + """ + return await self._merge(ProtocolCode.GET_MOTOR_SPEEDS) + + async def get_motor_torques(self): + """Get the motor torques + + Returns: + list[float]: Motor torques + """ + return await self._merge(ProtocolCode.GET_MOTOR_TORQUES) + + async def get_motor_enable_status(self): + """Get the motor enabled status + Returns: + list[int]: Motor enabled status + 0: Disable + 1: Enable + """ + return await self._merge(ProtocolCode.GET_MOTOR_ENABLE_STATUS) + + async def get_motor_loss_count(self): + """Get the motor loss count + + Returns: + list[int]: Motor loss count + """ + return await self._merge(ProtocolCode.GET_MOTOR_LOSS_COUNT) + + async def set_communication_state(self, state): + """Set the communication state + + Args: + state(int): + 0: Serial communication (default) + 1: Socket communication + 2: Bluetooth communication (Write the MAC address to the file and the endpoint, and then return to the state) + + Returns: + int: 1: Success, 0: Failed + """ + if state not in (0, 1, 2): + raise ValueError("State must be 0, 1 or 2") + self._communication_mode = state + return await self._merge(ProtocolCode.SET_COMMUNICATION_MODE, state) + + async def get_communication_state(self): + """Get the communication state + + Returns: + int: communication state + 0: Serial communication, + 1: Socket communication, + 2: Bluetooth communication + """ + return await self._merge(ProtocolCode.GET_COMMUNICATION_MODE) + + async def set_led_color(self, position, brightness, color): + """Set the LED color + + Args: + position(int): + 0: Left LED + 1: Right LED + brightness(int): 0 - 255 + color(tuple(int, int, int)): RGB color + + Returns: + int: 1: Success, 0: Failed + """ + if position not in (0, 1): + raise ValueError("Position must be 0 or 1") + + if not 0 <= brightness <= 255: + raise ValueError("Brightness must be between 0 and 255") + + if any(not 0 <= c <= 255 for c in color): + raise ValueError("Color must be between 0 and 255") + + return await self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) + + async def set_led_mode(self, mode): + """Set the LED mode + + Args: + mode(int): + 0: Battery level(default) + 1: DIY + + Returns: + int: 1: Success, 0: Failed + """ + if mode not in (0, 1): + raise ValueError("Mode must be 0 or 1") + return await self._merge(ProtocolCode.SET_LED_MODE, mode) + + async def set_pin_output(self, pin, state): + """Set the output IO + + Args: + pin(int): 1 - 6 + state(int): 0: Low, 1: High + + Returns: + int: 1: Success, 0: Failed + """ + if not 1 <= pin <= 6: + raise ValueError("Pin must be between 1 and 6") + + if state not in (0, 1): + raise ValueError("State must be 0 or 1") + + return await self._merge(ProtocolCode.SET_OUTPUT_IO, pin, state) + + async def get_pin_input(self, pin): + """Get the input IO + + Args: + pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254 + + Returns: + int: 0: Low, 1: High, -1: There is no such pin + """ + supported_pins = [1, 2, 3, 4, 5, 6, 7, 8, 254] + if pin not in supported_pins: + raise ValueError(f"Pin must be in {supported_pins}") + return await self._merge(ProtocolCode.GET_INPUT_IO, pin) + + async def get_wifi_account(self): + """Get the wi-fi account + + Returns: + tuple(str, str): wi-fi account, wi-fi password + """ + return await self._merge(ProtocolCode.GET_WIFI_ACCOUNT) + + async def get_wifi_ip_port(self): + """Get the wi-fi ip and port + Returns: + tuple(str, int): wi-fi ip, wi-fi port + """ + return await self._merge(ProtocolCode.GET_WIFI_IP_PORT) + + async def get_bluetooth_uuid(self): + """Get the bluetooth uuid + + Returns: + tuple(str, str, str): bluetooth name, service uuid, characteristic uuid + """ + + return await self._merge(ProtocolCode.GET_BLUETOOTH_UUID) + + async def get_bluetooth_address(self): + """Get the bluetooth MAC address + + Returns: + str: bluetooth MAC address + """ + + return await self._merge(ProtocolCode.GET_BLUETOOTH_ADDRESS) + + +class MyAGVProBluetooth(MyAGVProCommandApi): + def __init__(self, address, service_uuid, char_uuid, debug=False, save_serial_log=False): + super().__init__(debug=debug, save_serial_log=save_serial_log) + self._bluetooth = BleakClient(address, timeout=10) + self._address = address + self._char_uuid = char_uuid + self._service_uuid = service_uuid + self._serial_filename = 'agvpro_bluetooth_serial.log' + self._communication_mode = 2 + + # Async Context managers + async def __aenter__(self): + await self.connect() + return self + + async def __aexit__(self, *args, **kwargs): + await self.disconnect() + + async def read(self, size=1): + return await self._bluetooth.read_gatt_char(self._char_uuid, size=size) + + async def write(self, data): + return await self._bluetooth.write_gatt_char(self._char_uuid, data) + + async def connect(self): + await self._bluetooth.connect() + + async def disconnect(self): + await self._bluetooth.disconnect() + + async def is_connected(self): + return self._bluetooth.is_connected + diff --git a/pymycobot/myagvpro_socket.py b/pymycobot/myagvpro_socket.py new file mode 100644 index 00000000..ea992ad1 --- /dev/null +++ b/pymycobot/myagvpro_socket.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import socket +from pymycobot.myagvpro import MyAGVProCommandApi + + +def setup_socket_connect(host, port, timeout=0.1): + socket_api = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + socket_api.settimeout(timeout) + socket_api.connect((host, port)) + return socket_api + + +class MyAGVProSocket(MyAGVProCommandApi): + def __init__(self, host, port, debug=False, save_serial_log=False): + super().__init__(debug=debug, save_serial_log=save_serial_log) + self._socket = setup_socket_connect(host=host, port=port) + self._serial_filename = 'agvpro_socket_serial.log' + self._communication_mode = 1 + + def __exit__(self, exc_type, exc_val, exc_tb): + self.close() + + def __enter__(self): + return self + + def write(self, command): + return self._socket.send(command) + + def read(self, size=1): + try: + return self._socket.recv(size) + except socket.timeout: + return b'' + + def close(self): + self._socket.close() + + def clear(self): + pass diff --git a/requirements.txt b/requirements.txt index 5cbeabd1..51114d83 100644 --- a/requirements.txt +++ b/requirements.txt @@ -5,3 +5,4 @@ flake8 opencv-python numpy crc +bleak~=0.22.3 \ No newline at end of file From b78075cdcd8353a00bf87d2bba949fd37e21dd46 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 13:33:27 +0800 Subject: [PATCH 27/57] docs(MyAGVPro): Format the document --- docs/MYAGVPro_zh.md | 62 ++++++++++++++++++++++----------------------- docs/MyAGVPro_en.md | 62 ++++++++++++++++++++++----------------------- 2 files changed, 62 insertions(+), 62 deletions(-) diff --git a/docs/MYAGVPro_zh.md b/docs/MYAGVPro_zh.md index 6c1c6fb8..5eb3d7d8 100644 --- a/docs/MYAGVPro_zh.md +++ b/docs/MYAGVPro_zh.md @@ -2,98 +2,98 @@ ### 1. ϵͳ & ƷϢ -#### def get_system_version(self) -> None: +#### get_system_version(): - **:** ȡ̼汾 - **ֵ:** - **float: version** -#### def get_modify_version(self) -> None: +#### get_modify_version(): - **:** ȡι̼汾 - **ֵ:** - **int: version** -#### def power_on(self) -> None: +#### power_on(): - **:** - **ֵ:** - **int: , 1: ɹ, 0: ʧ** -#### def power_on_only(self) -> None: +#### power_on_only(): - **:** ˣƳ - **ֵ:** - **int: , 1: ɹ, 0: ʧ** -#### def power_off(self) -> None: +#### power_off(): - **:** رջ - **ֵ:** - **int: رս, 1: ɹ, 0: ʧ** -#### def is_power_on(self) -> None: +#### is_power_on(): - **:** Ƿѿ - **ֵ:** - **int: Դ״̬, 1: , 0: ر** ### 2. ˶ -#### def move_backward(self, speed) -> None: +#### move_backward(speed): - **:** ƽƻ - **:** - **speed(float): 0 ~ 1.5 m/s** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def move_forward(self, speed) -> None: +#### move_forward(speed): - **:** ƽƻǰ - **:** - **speed(float): 0 ~ 1.5 m/s** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def move_left_lateral(self, speed) -> None: +#### move_left_lateral(speed): - **:** ƽƻ - **:** - **speed(float): 0 ~ 1 m/s** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def move_right_lateral(self, speed) -> None: +#### move_right_lateral(speed): - **:** ƽƻ - **:** - **speed(float): 0 ~ 1 m/s** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def turn_left(self, speed) -> None: +#### turn_left(speed): - **:** ת - **:** - **speed:** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def turn_right(self, speed) -> None: +#### turn_right(speed): - **:** ת - **:** - **speed:** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def stop(self) -> None: +#### stop(): - **:** ֹͣƶ - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def set_auto_report_state(self, state) -> None: +#### set_auto_report_state(state): - **:** Զ״̬ - **:** - **state(int): 0: ر, 1: ** - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def get_auto_report_state(self) -> None: +#### get_auto_report_state(): - **:** ȡԶ״̬ - **ֵ:** - **int: 0: ر, 1: ** -#### def get_auto_report_message(self) -> None: +#### get_auto_report_message(): - **:** ȡԶϢ - **ֵ:** - **list[int | list[int] | float]:** @@ -107,36 +107,36 @@ ### 3. -#### def get_motor_enable_status(self) -> None: +#### get_motor_enable_status(): - **:** ȡʹ״̬ - **ֵ:** - **list[int]: ʹ״̬** - **0: ** - **1: ** -#### def get_motor_status(self) -> None: +#### get_motor_status(): - **:** ȡ״̬ - **ֵ:** - **list[int]: ״̬** - **0: ** - **any: ** -#### def get_motor_temps(self) -> None: +#### get_motor_temps(): - **:** ȡ¶ - **ֵ:** - **list[float]: ¶** -#### def get_motor_speeds(self) -> None: +#### get_motor_speeds(): - **:** ȡٶ - **ֵ:** - **list[float]: ٶ** -#### def get_motor_torques(self) -> None: +#### get_motor_torques(): - **:** ȡŤ - **ֵ:** - **list[float]: Ť** -#### def set_communication_state(self, state) -> None: +#### set_communication_state(state): - **:** ͨѶ״̬ - **:** - **state(int):** @@ -146,7 +146,7 @@ - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def get_communication_state(self) -> None: +#### get_communication_state(): - **:** ȡͨѶ״̬ - **ֵ:** - **int: ͨѶ״̬** @@ -154,7 +154,7 @@ - **1: Socket ͨѶ,** - **2: ͨѶ** -#### def set_led_color(self, position, brightness, color) -> None: +#### set_led_color(position, brightness, color): - **:** LED ɫ - **:** - **position(int):** @@ -165,21 +165,21 @@ - **ֵ:** - **int: 1: ɹ, 0: ʧ** -#### def get_motor_loss_count(self) -> None: +#### get_motor_loss_count(): - **:** ȡ - **ֵ:** - **list[int]: ** ### 4. IO -#### def get_pin_input(self, pin) -> None: +#### get_pin_input(pin): - **:** ȡ IO - **:** - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** - **ֵ:** - **int: 0: ͵ƽ, 1: ߵƽ, -1: û** -#### def set_pin_output(self, pin, state) -> None: +#### set_pin_output(pin, state): - **:** IO - **:** - **pin(int): 1 - 6** @@ -189,22 +189,22 @@ ### 5. WiFi & -#### def get_wifi_ip_port(self) -> None: +#### get_wifi_ip_port(): - **:** ȡ wi-fi ip Ͷ˿ - **ֵ:** - **tuple(str, int): wi-fi ip, wi-fi ˿** -#### def get_wifi_account(self) -> None: +#### get_wifi_account(): - **:** ȡ wi-fi ˺ - **ֵ:** - **tuple(str, str): wi-fi ˺, wi-fi ** -#### def get_bluetooth_address(self) -> None: +#### get_bluetooth_address(): - **:** ȡ MAC ַ - **ֵ:** - **str: MAC ַ** -#### def get_bluetooth_uuid(self) -> None: +#### get_bluetooth_uuid(): - **:** ȡ uuid - **ֵ:** - **tuple(str, str, str): , uuid, uuid** diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index 6cfdd945..8b0e2d2b 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -2,98 +2,98 @@ ### 1. System & Product Information -#### def get_system_version(self) -> None: +#### get_system_version(): - **function:** Obtain the major firmware version number - **Return value:** - **float: version** -#### def get_modify_version(self) -> None: +#### get_modify_version(): - **function:** Obtain the minor firmware version number - **Return value:** - **int: version** -#### def power_on(self) -> None: +#### power_on(): - **function:** Turn on the robot - **Return value:** - **int: Power-on result, 1: Success, 0: Failed** -#### def power_on_only(self) -> None: +#### power_on_only(): - **function:** Turn on the robot, but not start the control program - **Return value:** - **int: Power-on result only, 1: Success, 0: Failed** -#### def power_off(self) -> None: +#### power_off(): - **function:** Turn off the robot - **Return value:** - **int: Power-off result only, 1: Success, 0: Failed** -#### def is_power_on(self) -> None: +#### is_power_on(): - **function:** Check if the robot is powered on - **Return value:** - **int: power state, 1: Power-on, 0: Power-off** ### 2. Motion control -#### def move_backward(self, speed) -> None: +#### move_backward(speed): - **function:** Pan the robot backward - **parameter:** - **speed(float): 0 ~ 1.5 m/s** - **Return value:** - **int: 1: Success, 0: Failed** -#### def move_forward(self, speed) -> None: +#### move_forward(speed): - **function:** Pan the robot forward - **parameter:** - **speed(float): 0 ~ 1.5 m/s** - **Return value:** - **int: 1: Success, 0: Failed** -#### def move_left_lateral(self, speed) -> None: +#### move_left_lateral(speed): - **function:** Pan the robot left - **parameter:** - **speed(float): 0 ~ 1 m/s** - **Return value:** - **int: 1: Success, 0: Failed** -#### def move_right_lateral(self, speed) -> None: +#### move_right_lateral(speed): - **function:** Pan the robot right - **parameter:** - **speed(float): 0 ~ 1 m/s** - **Return value:** - **int: 1: Success, 0: Failed** -#### def turn_left(self, speed) -> None: +#### turn_left(speed): - **function:** Rotate to the left - **parameter:** - **speed:** - **Return value:** - **int: 1: Success, 0: Failed** -#### def turn_right(self, speed) -> None: +#### turn_right(speed): - **function:** Rotate to the right - **parameter:** - **speed:** - **Return value:** - **int: 1: Success, 0: Failed** -#### def stop(self) -> None: +#### stop(): - **function:** Stop moving - **Return value:** - **int: 1: Success, 0: Failed** -#### def set_auto_report_state(self, state) -> None: +#### set_auto_report_state(state): - **function:** Set the auto-report state - **parameter:** - **state(int): 0: Close, 1: Open** - **Return value:** - **int: 1: Success, 0: Failed** -#### def get_auto_report_state(self) -> None: +#### get_auto_report_state(): - **function:** Get the auto-report state - **Return value:** - **int: 0: Close, 1: Open** -#### def get_auto_report_message(self) -> None: +#### get_auto_report_message(): - **function:** Get the auto-report message - **Return value:** - **list[int | list[int] | float]:** @@ -107,36 +107,36 @@ ### 3. Motor assisted -#### def get_motor_enable_status(self) -> None: +#### get_motor_enable_status(): - **function:** Get the motor enabled status - **Return value:** - **list[int]: Motor enabled status** - **0: Disable** - **1: Enable** -#### def get_motor_status(self) -> None: +#### get_motor_status(): - **function:** Get the motor status - **Return value:** - **list[int]: Motor status** - **0: normal** - **any: error code** -#### def get_motor_temps(self) -> None: +#### get_motor_temps(): - **function:** Get the motor temperature - **Return value:** - **list[float]: Motor temperature** -#### def get_motor_speeds(self) -> None: +#### get_motor_speeds(): - **function:** Get the motor speeds - **Return value:** - **list[float]: Motor speeds** -#### def get_motor_torques(self) -> None: +#### get_motor_torques(): - **function:** Get the motor torques - **Return value:** - **list[float]: Motor torques** -#### def set_communication_state(self, state) -> None: +#### set_communication_state(state): - **function:** Set the communication state - **parameter:** - **state(int):** @@ -146,7 +146,7 @@ - **Return value:** - **int: 1: Success, 0: Failed** -#### def get_communication_state(self) -> None: +#### get_communication_state(): - **function:** Get the communication state - **Return value:** - **int: communication state** @@ -154,7 +154,7 @@ - **1: Socket communication,** - **2: Bluetooth communication** -#### def set_led_color(self, position, brightness, color) -> None: +#### set_led_color(position, brightness, color): - **function:** Set the LED color - **parameter:** - **position(int):** @@ -165,21 +165,21 @@ - **Return value:** - **int: 1: Success, 0: Failed** -#### def get_motor_loss_count(self) -> None: +#### get_motor_loss_count(): - **function:** Get the motor loss count - **Return value:** - **list[int]: Motor loss count** ### 4. IO Control -#### def get_pin_input(self, pin) -> None: +#### get_pin_input(pin): - **function:** Get the input IO - **parameter:** - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** - **Return value:** - **int: 0: Low, 1: High, -1: There is no such pin** -#### def set_pin_output(self, pin, state) -> None: +#### set_pin_output(pin, state): - **function:** Set the output IO - **parameter:** - **pin(int): 1 - 6** @@ -189,22 +189,22 @@ ### 5. WiFi & Bluetooth -#### def get_wifi_ip_port(self) -> None: +#### get_wifi_ip_port(): - **function:** Get the wi-fi ip and port - **Return value:** - **tuple(str, int): wi-fi ip, wi-fi port** -#### def get_wifi_account(self) -> None: +#### get_wifi_account(): - **function:** Get the wi-fi account - **Return value:** - **tuple(str, str): wi-fi account, wi-fi password** -#### def get_bluetooth_address(self) -> None: +#### get_bluetooth_address(): - **function:** Get the bluetooth MAC address - **Return value:** - **str: bluetooth MAC address** -#### def get_bluetooth_uuid(self) -> None: +#### get_bluetooth_uuid(): - **function:** Get the bluetooth uuid - **Return value:** - **tuple(str, str, str): bluetooth name, service uuid, characteristic uuid** \ No newline at end of file From 74d35b6c16ca326ac6abc02c33b7bc98012bea22 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 13:56:14 +0800 Subject: [PATCH 28/57] docs(MyAGVPro): Documentation to increase use cases --- docs/MYAGVPro_zh.md | 28 ++++++++++++++++++++++++++++ docs/MyAGVPro_en.md | 32 +++++++++++++++++++++++++++++++- 2 files changed, 59 insertions(+), 1 deletion(-) diff --git a/docs/MYAGVPro_zh.md b/docs/MYAGVPro_zh.md index 5eb3d7d8..b5a4b024 100644 --- a/docs/MYAGVPro_zh.md +++ b/docs/MYAGVPro_zh.md @@ -208,3 +208,31 @@ - **:** ȡ uuid - **ֵ:** - **tuple(str, str, str): , uuid, uuid** + +### 6. ʹð +#### 6.1 ȡ AGVPro ϵͳ汾 +```python +from pymycobot import MyAGVPro +# ʼ AGVPro +agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) +# ȡϵͳ汾 +version = agv_pro.get_system_version() +print(version) +``` +#### 6.2 AGVPro0.5m/sٶǰƶ3 +```python +import time +from pymycobot import MyAGVPro + +# ʼ AGVPro +agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) + +# agv_pro 0.5m/s ٶǰƶ +agv_pro.move_forward(0.5) + +# ˯ 3 +time.sleep(3) + +# ֹͣƶ +agv_pro.stop() +``` \ No newline at end of file diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index 8b0e2d2b..b8a83efd 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -207,4 +207,34 @@ #### get_bluetooth_uuid(): - **function:** Get the bluetooth uuid - **Return value:** - - **tuple(str, str, str): bluetooth name, service uuid, characteristic uuid** \ No newline at end of file + - **tuple(str, str, str): bluetooth name, service uuid, characteristic uuid** + +### 6. Use Cases: +#### 6.1 Get the system version number of AGVPro +```python +from pymycobot import MyAGVPro + +# Initialize the AGVPro object +agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) + +# Obtain the system version number +version = agv_pro.get_system_version() +print(version) +``` +#### 6.2 Control AGVPro to move forward at a speed of 0.5ms for 3 seconds +```python +import time +from pymycobot import MyAGVPro + +# Initialize the AGVPro object +agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) + +# The control AGVPro moves forward at a speed of 0.5ms +agv_pro.move_forward(0.5) + +# Sleep for 3 seconds +time.sleep(3) + +# Stop moving +agv_pro.stop() +``` \ No newline at end of file From 5803ad123857e330d6f7bcb7e6830e8147d2072f Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 14:00:00 +0800 Subject: [PATCH 29/57] docs(MyAGVPro): rename MyAGVPro_zh.md --- docs/{MYAGVPro_zh.md => MyAGVPro_zh.md} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename docs/{MYAGVPro_zh.md => MyAGVPro_zh.md} (100%) diff --git a/docs/MYAGVPro_zh.md b/docs/MyAGVPro_zh.md similarity index 100% rename from docs/MYAGVPro_zh.md rename to docs/MyAGVPro_zh.md From 714d5210da424fdb50c7fd362f64fbc4fc46ff44 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 14:17:36 +0800 Subject: [PATCH 30/57] docs(MyAGVPro): Update the serial port --- docs/MyAGVPro_en.md | 4 ++-- docs/MyAGVPro_zh.md | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index b8a83efd..ca4c5eca 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -215,7 +215,7 @@ from pymycobot import MyAGVPro # Initialize the AGVPro object -agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) +agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) # Obtain the system version number version = agv_pro.get_system_version() @@ -227,7 +227,7 @@ import time from pymycobot import MyAGVPro # Initialize the AGVPro object -agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) +agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) # The control AGVPro moves forward at a speed of 0.5ms agv_pro.move_forward(0.5) diff --git a/docs/MyAGVPro_zh.md b/docs/MyAGVPro_zh.md index b5a4b024..d5b4a389 100644 --- a/docs/MyAGVPro_zh.md +++ b/docs/MyAGVPro_zh.md @@ -214,7 +214,7 @@ ```python from pymycobot import MyAGVPro # ʼ AGVPro -agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) +agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) # ȡϵͳ汾 version = agv_pro.get_system_version() print(version) @@ -225,7 +225,7 @@ import time from pymycobot import MyAGVPro # ʼ AGVPro -agv_pro = MyAGVPro("COM3", baudrate=1000000, debug=True) +agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) # agv_pro 0.5m/s ٶǰƶ agv_pro.move_forward(0.5) From 2d995ff46995d169a8bd15c2ac5c11b8778263e3 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 15:38:53 +0800 Subject: [PATCH 31/57] fix(MyArmM): Correction of joint limit and motor code value range --- pymycobot/error.py | 2 +- pymycobot/robot_info.py | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/pymycobot/error.py b/pymycobot/error.py index 3696e64a..d3f984b3 100644 --- a/pymycobot/error.py +++ b/pymycobot/error.py @@ -1371,7 +1371,7 @@ def calibration_parameters(**kwargs): f"encoder value not right, should be {min_encoder} ~ {max_encoder}, but received {v}") if (2048 - value[1]) + (2048 - value[2]) != 0: - raise ValueError("The 2 and 3 servos must be inverse") + raise ValueError("The 2 and 3 servo encoder values must be reversed") elif parameter == "speed": check_value_type(parameter, value_type, TypeError, int) diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 50a3c98e..818df89d 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -339,10 +339,10 @@ class RobotLimit: "MyArmM": { "joint_id": [1, 2, 3, 4, 5, 6, 7], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], - "angles_min": [-165, -80, -100, -160, -90, -180, -118], - "angles_max": [165, 100, 80, 160, 120, 180, 2], - "encoders_min": [137, 1163, 1035, 1013, 248, 979, 220, 706], - "encoders_max": [4004, 2945, 3079, 3026, 3724, 2994, 3704, 2048] + "angles_min": [-170, -83, -90, -155, -91, -153, -118], + "angles_max": [170, 83, 84, 153, 88, 153, 2], + "encoders_min": [114, 1200, 1200, 1024, 286, 1013, 307, 706], + "encoders_max": [3981, 2991, 2991, 3002, 3788, 3048, 3788, 2068] }, "MyArmMControl": { "joint_id": [1, 2, 3, 4, 5, 6], From 92db07b59be7df9b0bc1341af7e4b205d3b77520 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 18:12:06 +0800 Subject: [PATCH 32/57] feat(MyAGVPro): Add get_emergency_stop_state api --- docs/MyAGVPro_en.md | 9 ++++- docs/MyAGVPro_zh.md | 9 ++++- pymycobot/myagvpro.py | 69 ++++++++++++++++++++++++--------- pymycobot/myagvpro_bluetooth.py | 57 ++++++++++++++++++++------- 4 files changed, 106 insertions(+), 38 deletions(-) diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index ca4c5eca..3bb0be0e 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -160,8 +160,8 @@ - **position(int):** - **0: Left LED** - **1: Right LED** - - **brightness(int): 0 - 255** - **color(tuple(int, int, int)): RGB color** + - **brightness(int): 0 - 255(default 255)** - **Return value:** - **int: 1: Success, 0: Failed** @@ -175,7 +175,7 @@ #### get_pin_input(pin): - **function:** Get the input IO - **parameter:** - - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** + - **pin(int): 1 - 6** - **Return value:** - **int: 0: Low, 1: High, -1: There is no such pin** @@ -187,6 +187,11 @@ - **Return value:** - **int: 1: Success, 0: Failed** +#### get_emergency_stop_state() +- **function:** Get the emergency stop state +- **Return value:** + - **int: 0: Release, 1: Press** + ### 5. WiFi & Bluetooth #### get_wifi_ip_port(): diff --git a/docs/MyAGVPro_zh.md b/docs/MyAGVPro_zh.md index d5b4a389..6d40719f 100644 --- a/docs/MyAGVPro_zh.md +++ b/docs/MyAGVPro_zh.md @@ -160,8 +160,8 @@ - **position(int):** - **0: LED** - **1: Ҳ LED** - - **brightness(int): 0 - 255** - **color(tuple(int, int, int)): RGB ɫ** + - **brightness(int): 0 - 255 (Ĭ255)** - **ֵ:** - **int: 1: ɹ, 0: ʧ** @@ -175,7 +175,7 @@ #### get_pin_input(pin): - **:** ȡ IO - **:** - - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** + - **pin(int): 1 - 6** - **ֵ:** - **int: 0: ͵ƽ, 1: ߵƽ, -1: û** @@ -187,6 +187,11 @@ - **ֵ:** - **int: 1: ɹ, 0: ʧ** +#### get_emergency_stop_state() +- **:** ȡͣ״̬ +- **ֵ:** + - **int: 0: ɿ, 1: ** + ### 5. WiFi & #### get_wifi_ip_port(): diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 1f387410..70fbc7ba 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -1,5 +1,6 @@ #!/usr/bin/env python # -*- coding: UTF-8 -*- +import decimal import re import threading import time @@ -82,6 +83,10 @@ def _save_buffer_data(self, data, to_local=False): self._save_file(self._serial_filename, " ".join(map(str, self._data_buffer)) + "\n") self._data_buffer.clear() + @staticmethod + def get_significant_bit(number): + return -decimal.Decimal(str(number)).as_tuple().exponent + @staticmethod def _save_file(filename, data): with open(filename, "a+") as f: @@ -359,52 +364,64 @@ def move_forward(self, speed): """Pan the robot forward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) def move_backward(self, speed): """Pan the robot backward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) def move_left_lateral(self, speed): """Pan the robot left Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00 m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.01 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) def move_right_lateral(self, speed): """Pan the robot right Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.00 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) def turn_left(self, speed): @@ -416,6 +433,8 @@ def turn_left(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) def turn_right(self, speed): @@ -427,6 +446,8 @@ def turn_right(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) def stop(self): @@ -578,15 +599,15 @@ def get_communication_state(self): """ return self._merge(ProtocolCode.GET_COMMUNICATION_MODE) - def set_led_color(self, position, brightness, color): + def set_led_color(self, position, color, brightness=255): """Set the LED color Args: position(int): 0: Left LED 1: Right LED - brightness(int): 0 - 255 color(tuple(int, int, int)): RGB color + brightness(int): 0 - 255 (default: 255) Returns: int: 1: Success, 0: Failed @@ -597,7 +618,10 @@ def set_led_color(self, position, brightness, color): if not 0 <= brightness <= 255: raise ValueError("Brightness must be between 0 and 255") - if any(not 0 <= c <= 255 for c in color): + if len(color) != 3: + raise ValueError("Color must be a tuple of 3 values") + + if any(map(lambda c: not 0 <= c <= 255, color)): raise ValueError("Color must be between 0 and 255") return self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) @@ -639,16 +663,23 @@ def get_pin_input(self, pin): """Get the input IO Args: - pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254 + pin(int): 1 - 6 Returns: int: 0: Low, 1: High, -1: There is no such pin """ - supported_pins = [1, 2, 3, 4, 5, 6, 7, 8, 254] - if pin not in supported_pins: - raise ValueError(f"Pin must be in {supported_pins}") + if not 1 <= pin <= 6: + raise ValueError("Pin must be between 1 and 6") return self._merge(ProtocolCode.GET_INPUT_IO, pin) + def get_emergency_stop_state(self): + """Get the emergency stop state + + Returns: + int: 0: Release, 1: Press + """ + return self._merge(ProtocolCode.GET_INPUT_IO, 254) + def get_wifi_account(self): """Get the wi-fi account diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index 2852d849..da724233 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -92,52 +92,64 @@ async def move_forward(self, speed): """Pan the robot forward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) async def move_backward(self, speed): """Pan the robot backward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) async def move_left_lateral(self, speed): """Pan the robot left Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00 m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.01 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) async def move_right_lateral(self, speed): """Pan the robot right Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.00 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) async def turn_left(self, speed): @@ -149,6 +161,8 @@ async def turn_left(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) async def turn_right(self, speed): @@ -160,6 +174,8 @@ async def turn_right(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) async def stop(self): @@ -310,15 +326,15 @@ async def get_communication_state(self): """ return await self._merge(ProtocolCode.GET_COMMUNICATION_MODE) - async def set_led_color(self, position, brightness, color): + async def set_led_color(self, position, color, brightness=255): """Set the LED color Args: position(int): 0: Left LED 1: Right LED - brightness(int): 0 - 255 color(tuple(int, int, int)): RGB color + brightness(int): 0 - 255 (default: 255) Returns: int: 1: Success, 0: Failed @@ -329,7 +345,10 @@ async def set_led_color(self, position, brightness, color): if not 0 <= brightness <= 255: raise ValueError("Brightness must be between 0 and 255") - if any(not 0 <= c <= 255 for c in color): + if len(color) != 3: + raise ValueError("Color must be a tuple of 3 values") + + if any(map(lambda c: not 0 <= c <= 255, color)): raise ValueError("Color must be between 0 and 255") return await self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) @@ -381,6 +400,14 @@ async def get_pin_input(self, pin): raise ValueError(f"Pin must be in {supported_pins}") return await self._merge(ProtocolCode.GET_INPUT_IO, pin) + def get_emergency_stop_state(self): + """Get the emergency stop state + + Returns: + int: 0: Release, 1: Press + """ + return self._merge(ProtocolCode.GET_INPUT_IO, 254) + async def get_wifi_account(self): """Get the wi-fi account From aae9d2b7781c3d81d3623e7b8df54e6e2779ee9c Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 18:33:06 +0800 Subject: [PATCH 33/57] feat(MyAGVPro): Add get_emergency_stop_state api --- docs/MyAGVPro_en.md | 9 ++++- docs/MyAGVPro_zh.md | 9 ++++- pymycobot/myagvpro.py | 69 ++++++++++++++++++++++++--------- pymycobot/myagvpro_bluetooth.py | 57 ++++++++++++++++++++------- 4 files changed, 106 insertions(+), 38 deletions(-) diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index ca4c5eca..3bb0be0e 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -160,8 +160,8 @@ - **position(int):** - **0: Left LED** - **1: Right LED** - - **brightness(int): 0 - 255** - **color(tuple(int, int, int)): RGB color** + - **brightness(int): 0 - 255(default 255)** - **Return value:** - **int: 1: Success, 0: Failed** @@ -175,7 +175,7 @@ #### get_pin_input(pin): - **function:** Get the input IO - **parameter:** - - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** + - **pin(int): 1 - 6** - **Return value:** - **int: 0: Low, 1: High, -1: There is no such pin** @@ -187,6 +187,11 @@ - **Return value:** - **int: 1: Success, 0: Failed** +#### get_emergency_stop_state() +- **function:** Get the emergency stop state +- **Return value:** + - **int: 0: Release, 1: Press** + ### 5. WiFi & Bluetooth #### get_wifi_ip_port(): diff --git a/docs/MyAGVPro_zh.md b/docs/MyAGVPro_zh.md index d5b4a389..6d40719f 100644 --- a/docs/MyAGVPro_zh.md +++ b/docs/MyAGVPro_zh.md @@ -160,8 +160,8 @@ - **position(int):** - **0: LED** - **1: Ҳ LED** - - **brightness(int): 0 - 255** - **color(tuple(int, int, int)): RGB ɫ** + - **brightness(int): 0 - 255 (Ĭ255)** - **ֵ:** - **int: 1: ɹ, 0: ʧ** @@ -175,7 +175,7 @@ #### get_pin_input(pin): - **:** ȡ IO - **:** - - **pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254** + - **pin(int): 1 - 6** - **ֵ:** - **int: 0: ͵ƽ, 1: ߵƽ, -1: û** @@ -187,6 +187,11 @@ - **ֵ:** - **int: 1: ɹ, 0: ʧ** +#### get_emergency_stop_state() +- **:** ȡͣ״̬ +- **ֵ:** + - **int: 0: ɿ, 1: ** + ### 5. WiFi & #### get_wifi_ip_port(): diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 1f387410..70fbc7ba 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -1,5 +1,6 @@ #!/usr/bin/env python # -*- coding: UTF-8 -*- +import decimal import re import threading import time @@ -82,6 +83,10 @@ def _save_buffer_data(self, data, to_local=False): self._save_file(self._serial_filename, " ".join(map(str, self._data_buffer)) + "\n") self._data_buffer.clear() + @staticmethod + def get_significant_bit(number): + return -decimal.Decimal(str(number)).as_tuple().exponent + @staticmethod def _save_file(filename, data): with open(filename, "a+") as f: @@ -359,52 +364,64 @@ def move_forward(self, speed): """Pan the robot forward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) def move_backward(self, speed): """Pan the robot backward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) def move_left_lateral(self, speed): """Pan the robot left Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00 m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.01 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) def move_right_lateral(self, speed): """Pan the robot right Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.00 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) def turn_left(self, speed): @@ -416,6 +433,8 @@ def turn_left(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) def turn_right(self, speed): @@ -427,6 +446,8 @@ def turn_right(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) def stop(self): @@ -578,15 +599,15 @@ def get_communication_state(self): """ return self._merge(ProtocolCode.GET_COMMUNICATION_MODE) - def set_led_color(self, position, brightness, color): + def set_led_color(self, position, color, brightness=255): """Set the LED color Args: position(int): 0: Left LED 1: Right LED - brightness(int): 0 - 255 color(tuple(int, int, int)): RGB color + brightness(int): 0 - 255 (default: 255) Returns: int: 1: Success, 0: Failed @@ -597,7 +618,10 @@ def set_led_color(self, position, brightness, color): if not 0 <= brightness <= 255: raise ValueError("Brightness must be between 0 and 255") - if any(not 0 <= c <= 255 for c in color): + if len(color) != 3: + raise ValueError("Color must be a tuple of 3 values") + + if any(map(lambda c: not 0 <= c <= 255, color)): raise ValueError("Color must be between 0 and 255") return self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) @@ -639,16 +663,23 @@ def get_pin_input(self, pin): """Get the input IO Args: - pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254 + pin(int): 1 - 6 Returns: int: 0: Low, 1: High, -1: There is no such pin """ - supported_pins = [1, 2, 3, 4, 5, 6, 7, 8, 254] - if pin not in supported_pins: - raise ValueError(f"Pin must be in {supported_pins}") + if not 1 <= pin <= 6: + raise ValueError("Pin must be between 1 and 6") return self._merge(ProtocolCode.GET_INPUT_IO, pin) + def get_emergency_stop_state(self): + """Get the emergency stop state + + Returns: + int: 0: Release, 1: Press + """ + return self._merge(ProtocolCode.GET_INPUT_IO, 254) + def get_wifi_account(self): """Get the wi-fi account diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index 2852d849..da724233 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -92,52 +92,64 @@ async def move_forward(self, speed): """Pan the robot forward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * 1), 0x00]) async def move_backward(self, speed): """Pan the robot backward Args: - speed(float): 0 ~ 1.5 m/s + speed(float): 0.01 ~ 1.50m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1.5: - raise ValueError("Speed must be between 0 and 1.5") + if not 0.01 <= speed <= 1.50: + raise ValueError("Speed must be between 0.01 and 1.50") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) async def move_left_lateral(self, speed): """Pan the robot left Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00 m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.01 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) async def move_right_lateral(self, speed): """Pan the robot right Args: - speed(float): 0 ~ 1 m/s + speed(float): 0.01 ~ 1.00m/s Returns: int: 1: Success, 0: Failed """ - if not 0 <= speed <= 1: - raise ValueError("Speed must be between 0 and 1") + if not 0.01 <= speed <= 1.00: + raise ValueError("Speed must be between 0.00 and 1.00") + + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) async def turn_left(self, speed): @@ -149,6 +161,8 @@ async def turn_left(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * -1), 0x00]) async def turn_right(self, speed): @@ -160,6 +174,8 @@ async def turn_right(self, speed): Returns: int: 1: Success, 0: Failed """ + if self.get_significant_bit(speed) > 2: + raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) async def stop(self): @@ -310,15 +326,15 @@ async def get_communication_state(self): """ return await self._merge(ProtocolCode.GET_COMMUNICATION_MODE) - async def set_led_color(self, position, brightness, color): + async def set_led_color(self, position, color, brightness=255): """Set the LED color Args: position(int): 0: Left LED 1: Right LED - brightness(int): 0 - 255 color(tuple(int, int, int)): RGB color + brightness(int): 0 - 255 (default: 255) Returns: int: 1: Success, 0: Failed @@ -329,7 +345,10 @@ async def set_led_color(self, position, brightness, color): if not 0 <= brightness <= 255: raise ValueError("Brightness must be between 0 and 255") - if any(not 0 <= c <= 255 for c in color): + if len(color) != 3: + raise ValueError("Color must be a tuple of 3 values") + + if any(map(lambda c: not 0 <= c <= 255, color)): raise ValueError("Color must be between 0 and 255") return await self._merge(ProtocolCode.SET_LED_COLOR, position, brightness, *color) @@ -381,6 +400,14 @@ async def get_pin_input(self, pin): raise ValueError(f"Pin must be in {supported_pins}") return await self._merge(ProtocolCode.GET_INPUT_IO, pin) + def get_emergency_stop_state(self): + """Get the emergency stop state + + Returns: + int: 0: Release, 1: Press + """ + return self._merge(ProtocolCode.GET_INPUT_IO, 254) + async def get_wifi_account(self): """Get the wi-fi account From 02b1c0c925800f4affd29423a277fcd07e1316bc Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 6 Jun 2025 19:06:59 +0800 Subject: [PATCH 34/57] refactor(MyAGVPro): rename get_emergency_stop_state to get_estop_state --- docs/MyAGVPro_en.md | 2 +- docs/MyAGVPro_zh.md | 318 ++++++++++++++++++-------------- pymycobot/myagvpro.py | 2 +- pymycobot/myagvpro_bluetooth.py | 2 +- 4 files changed, 181 insertions(+), 143 deletions(-) diff --git a/docs/MyAGVPro_en.md b/docs/MyAGVPro_en.md index 3bb0be0e..41b03742 100644 --- a/docs/MyAGVPro_en.md +++ b/docs/MyAGVPro_en.md @@ -187,7 +187,7 @@ - **Return value:** - **int: 1: Success, 0: Failed** -#### get_emergency_stop_state() +#### get_estop_state() - **function:** Get the emergency stop state - **Return value:** - **int: 0: Release, 1: Press** diff --git a/docs/MyAGVPro_zh.md b/docs/MyAGVPro_zh.md index 6d40719f..f786d53b 100644 --- a/docs/MyAGVPro_zh.md +++ b/docs/MyAGVPro_zh.md @@ -1,243 +1,281 @@ # class MyAGVPro() -### 1. ϵͳ & ƷϢ +### 1. 系统 & 产品信息 #### get_system_version(): -- **:** ȡ̼汾 -- **ֵ:** + +- **功能:** 获取主固件版本号 +- **返回值:** - **float: version** #### get_modify_version(): -- **:** ȡι̼汾 -- **ֵ:** + +- **功能:** 获取次固件版本号 +- **返回值:** - **int: version** #### power_on(): -- **:** -- **ֵ:** - - **int: , 1: ɹ, 0: ʧ** + +- **功能:** 开启机器人 +- **返回值:** + - **int: 开机结果, 1: 成功, 0: 失败** #### power_on_only(): -- **:** ˣƳ -- **ֵ:** - - **int: , 1: ɹ, 0: ʧ** + +- **功能:** 开启机器人,但不启动控制程序 +- **返回值:** + - **int: 仅开机结果, 1: 成功, 0: 失败** #### power_off(): -- **:** رջ -- **ֵ:** - - **int: رս, 1: ɹ, 0: ʧ** + +- **功能:** 关闭机器人 +- **返回值:** + - **int: 仅关机结果, 1: 成功, 0: 失败** #### is_power_on(): -- **:** Ƿѿ -- **ֵ:** - - **int: Դ״̬, 1: , 0: ر** -### 2. ˶ +- **功能:** 检查机器人是否已开机 +- **返回值:** + - **int: 电源状态, 1: 开机, 0: 关机** + +### 2. 运动控制 #### move_backward(speed): -- **:** ƽƻ -- **:** + +- **功能:** 平移机器人向后 +- **参数:** - **speed(float): 0 ~ 1.5 m/s** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### move_forward(speed): -- **:** ƽƻǰ -- **:** + +- **功能:** 平移机器人向前 +- **参数:** - **speed(float): 0 ~ 1.5 m/s** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### move_left_lateral(speed): -- **:** ƽƻ -- **:** + +- **功能:** 平移机器人向左 +- **参数:** - **speed(float): 0 ~ 1 m/s** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### move_right_lateral(speed): -- **:** ƽƻ -- **:** + +- **功能:** 平移机器人向右 +- **参数:** - **speed(float): 0 ~ 1 m/s** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### turn_left(speed): -- **:** ת -- **:** + +- **功能:** 向左旋转 +- **参数:** - **speed:** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### turn_right(speed): -- **:** ת -- **:** + +- **功能:** 向右旋转 +- **参数:** - **speed:** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### stop(): -- **:** ֹͣƶ -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** + +- **功能:** 停止移动 +- **返回值:** + - **int: 1: 成功, 0: 失败** #### set_auto_report_state(state): -- **:** Զ״̬ -- **:** - - **state(int): 0: ر, 1: ** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** + +- **功能:** 设置自动报告状态 +- **参数:** + - **state(int): 0: 关闭, 1: 开启** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### get_auto_report_state(): -- **:** ȡԶ״̬ -- **ֵ:** - - **int: 0: ر, 1: ** + +- **功能:** 获取自动报告状态 +- **返回值:** + - **int: 0: 关闭, 1: 开启** #### get_auto_report_message(): -- **:** ȡԶϢ -- **ֵ:** + +- **功能:** 获取自动报告消息 +- **返回值:** - **list[int | list[int] | float]:** - **0 - (float)rx** - **1 - (float)ry** - **2 - (float)rw** - - **3 - (list[int])״̬** - - **4 - (list[int])Ϣ** - - **5 - (float)صѹ** - - **6 - (int)ʹ״̬ 0: , 1: ** + - **3 - (list[int])机器状态** + - **4 - (list[int])电机信息** + - **5 - (float)电池电压** + - **6 - (int)电机使能状态 0: 使能, 1: 禁用** -### 3. +### 3. 电机辅助 #### get_motor_enable_status(): -- **:** ȡʹ״̬ -- **ֵ:** - - **list[int]: ʹ״̬** - - **0: ** - - **1: ** + +- **功能:** 获取电机使能状态 +- **返回值:** + - **list[int]: 电机使能状态** + - **0: 禁用** + - **1: 使能** #### get_motor_status(): -- **:** ȡ״̬ -- **ֵ:** - - **list[int]: ״̬** - - **0: ** - - **any: ** + +- **功能:** 获取电机状态 +- **返回值:** + - **list[int]: 电机状态** + - **0: 正常** + - **any: 错误代码** #### get_motor_temps(): -- **:** ȡ¶ -- **ֵ:** - - **list[float]: ¶** + +- **功能:** 获取电机温度 +- **返回值:** + - **list[float]: 电机温度** #### get_motor_speeds(): -- **:** ȡٶ -- **ֵ:** - - **list[float]: ٶ** + +- **功能:** 获取电机速度 +- **返回值:** + - **list[float]: 电机速度** #### get_motor_torques(): -- **:** ȡŤ -- **ֵ:** - - **list[float]: Ť** + +- **功能:** 获取电机扭矩 +- **返回值:** + - **list[float]: 电机扭矩** #### set_communication_state(state): -- **:** ͨѶ״̬ -- **:** + +- **功能:** 设置通讯状态 +- **参数:** - **state(int):** - - **0: ͨѶ (Ĭ)** - - **1: Socket ͨѶ** - - **2: ͨѶ ( MAC ַдļͶ˵㣬Ȼ󷵻ص״̬)** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** + - **0: 串口通讯 (默认)** + - **1: Socket 通讯** + - **2: 蓝牙通讯 (将MAC地址写入文件和端点,然后返回状态)** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### get_communication_state(): -- **:** ȡͨѶ״̬ -- **ֵ:** - - **int: ͨѶ״̬** - - **0: ͨѶ,** - - **1: Socket ͨѶ,** - - **2: ͨѶ** + +- **功能:** 获取通讯状态 +- **返回值:** + - **int: 通讯状态** + - **0: 串口通讯,** + - **1: Socket 通讯,** + - **2: 蓝牙通讯** #### set_led_color(position, brightness, color): -- **:** LED ɫ -- **:** + +- **功能:** 设置LED颜色 +- **参数:** - **position(int):** - - **0: LED** - - **1: Ҳ LED** - - **color(tuple(int, int, int)): RGB ɫ** - - **brightness(int): 0 - 255 (Ĭ255)** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** + - **0: 左侧LED** + - **1: 右侧LED** + - **color(tuple(int, int, int)): RGB 颜色** + - **brightness(int): 0 - 255(默认 255)** +- **返回值:** + - **int: 1: 成功, 0: 失败** #### get_motor_loss_count(): -- **:** ȡ -- **ֵ:** - - **list[int]: ** -### 4. IO +- **功能:** 获取电机丢步计数 +- **返回值:** + - **list[int]: 电机丢步计数** + +### 4. IO 控制 #### get_pin_input(pin): -- **:** ȡ IO -- **:** + +- **功能:** 获取输入IO +- **参数:** - **pin(int): 1 - 6** -- **ֵ:** - - **int: 0: ͵ƽ, 1: ߵƽ, -1: û** +- **返回值:** + - **int: 0: 低电平, 1: 高电平, -1: 没有这个引脚** #### set_pin_output(pin, state): -- **:** IO -- **:** + +- **功能:** 设置输出IO +- **参数:** - **pin(int): 1 - 6** - - **state(int): 0: ͵ƽ, 1: ߵƽ** -- **ֵ:** - - **int: 1: ɹ, 0: ʧ** + - **state(int): 0: 低电平, 1: 高电平** +- **返回值:** + - **int: 1: 成功, 0: 失败** + +#### get_estop_state() -#### get_emergency_stop_state() -- **:** ȡͣ״̬ -- **ֵ:** - - **int: 0: ɿ, 1: ** - -### 5. WiFi & +- **功能:** 获取急停状态 +- **返回值:** + - **int: 0: 释放, 1: 按下** + +### 5. WiFi & 蓝牙 #### get_wifi_ip_port(): -- **:** ȡ wi-fi ip Ͷ˿ -- **ֵ:** - - **tuple(str, int): wi-fi ip, wi-fi ˿** + +- **功能:** 获取wi-fi ip和端口 +- **返回值:** + - **tuple(str, int): wi-fi ip, wi-fi 端口** #### get_wifi_account(): -- **:** ȡ wi-fi ˺ -- **ֵ:** - - **tuple(str, str): wi-fi ˺, wi-fi ** + +- **功能:** 获取wi-fi 账号 +- **返回值:** + - **tuple(str, str): wi-fi 账号, wi-fi 密码** #### get_bluetooth_address(): -- **:** ȡ MAC ַ -- **ֵ:** - - **str: MAC ַ** + +- **功能:** 获取蓝牙MAC地址 +- **返回值:** + - **str: 蓝牙MAC地址** #### get_bluetooth_uuid(): -- **:** ȡ uuid -- **ֵ:** - - **tuple(str, str, str): , uuid, uuid** -### 6. ʹð -#### 6.1 ȡ AGVPro ϵͳ汾 +- **功能:** 获取蓝牙uuid +- **返回值:** + - **tuple(str, str, str): 蓝牙名称, 服务uuid, 特征uuid** + +### 6. 使用案例: + +#### 6.1 获取AGVPro的系统版本号 + ```python from pymycobot import MyAGVPro -# ʼ AGVPro + +# 初始化 AGVPro 对象 agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) -# ȡϵͳ汾 + +# 获取系统版本号 version = agv_pro.get_system_version() print(version) ``` -#### 6.2 AGVPro0.5m/sٶǰƶ3 + +#### 6.2 控制AGVPro以0.5ms的速度前进3秒 + ```python import time from pymycobot import MyAGVPro -# ʼ AGVPro +# 初始化 AGVPro 对象 agv_pro = MyAGVPro("/dev/ttyTHS1", baudrate=1000000, debug=True) -# agv_pro 0.5m/s ٶǰƶ +# 控制 AGVPro 以 0.5ms 的速度前进 agv_pro.move_forward(0.5) -# ˯ 3 +# 睡眠 3 秒 time.sleep(3) -# ֹͣƶ +# 停止移动 agv_pro.stop() ``` \ No newline at end of file diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 70fbc7ba..7636020f 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -672,7 +672,7 @@ def get_pin_input(self, pin): raise ValueError("Pin must be between 1 and 6") return self._merge(ProtocolCode.GET_INPUT_IO, pin) - def get_emergency_stop_state(self): + def get_estop_state(self): """Get the emergency stop state Returns: diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index da724233..00a698d2 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -400,7 +400,7 @@ async def get_pin_input(self, pin): raise ValueError(f"Pin must be in {supported_pins}") return await self._merge(ProtocolCode.GET_INPUT_IO, pin) - def get_emergency_stop_state(self): + def get_estop_state(self): """Get the emergency stop state Returns: From 936c57764952c6288fac3c9b45f2265fd7fd0760 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 12 Jun 2025 17:14:40 +0800 Subject: [PATCH 35/57] feat(MyAgv): Added setting/reading automatic report status interface --- pymycobot/myagv.py | 31 +++++++++++++++++++++++++++---- 1 file changed, 27 insertions(+), 4 deletions(-) diff --git a/pymycobot/myagv.py b/pymycobot/myagv.py index 3f45c990..227a54a2 100644 --- a/pymycobot/myagv.py +++ b/pymycobot/myagv.py @@ -11,12 +11,14 @@ class ProtocolCode: RESTORE = (0x01, 0x00) SET_LED = (0x01, 0x02) SET_LED_MODE = (0x01, 0x0A) + SET_MOTION_CONTROL = (0x01, 0x0B) GET_FIRMWARE_VERSION = (0x01, 0x03) GET_MODIFIED_VERSION = (0x01, 0x09) SET_GYRO_STATE = (0x01, 0x07) + SET_AUTO_REPORT_STATE = (0x01, 0x0c) + GET_AUTO_REPORT_STATE = (0x01, 0x0d) GET_GYRO_STATE = (0x01, 0x08) - GET_MCU_INFO = (0x01, 0x0B) - UNDEFINED = () + GET_MCU_INFO = () class MyAGVCommandProtocolApi(CommunicationProtocol): @@ -190,7 +192,7 @@ def __basic_move_control(self, *genre, timeout: int = 5): while time.time() - t < timeout: if self.__movement is False: break - self._merge(ProtocolCode.UNDEFINED, *genre) + self._merge(ProtocolCode.SET_MOTION_CONTROL, *genre) time.sleep(0.1) self.stop() @@ -274,7 +276,7 @@ def counterclockwise_rotation(self, speed: int, timeout=5): def stop(self): """stop-motion""" - self._merge(ProtocolCode.UNDEFINED, 128, 128, 128) + self._merge(ProtocolCode.SET_MOTION_CONTROL, 128, 128, 128) self.__movement = False def get_mcu_info(self): @@ -334,6 +336,27 @@ def get_modified_version(self): """Get modified version number""" return self._merge(ProtocolCode.GET_MODIFIED_VERSION, has_reply=True) + def set_auto_report_state(self, state): + """Set the state of automatic reporting + + Args: + state (int): 1 - open. 0 - close. Defaults to 0. + """ + if state not in (0, 1): + raise ValueError("state must be 0 or 1") + + self._merge(ProtocolCode.SET_AUTO_REPORT_STATE, state) + + def get_auto_report_state(self): + """Get the state of automatic reporting + + Return: + 1 - open + 0 - close + """ + + return self._merge(ProtocolCode.GET_AUTO_REPORT_STATE, has_reply=True) + class MyAgv(MyAGVCommandApi): From ba45e4a07d3e0cbe456b0fc42130d36c73e7f15c Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 16 Jun 2025 15:10:40 +0800 Subject: [PATCH 36/57] fix(M750):Updated M750 Swing Limit --- pymycobot/robot_info.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/pymycobot/robot_info.py b/pymycobot/robot_info.py index 818df89d..43cc584f 100644 --- a/pymycobot/robot_info.py +++ b/pymycobot/robot_info.py @@ -339,8 +339,8 @@ class RobotLimit: "MyArmM": { "joint_id": [1, 2, 3, 4, 5, 6, 7], "servo_id": [1, 2, 3, 4, 5, 6, 7, 8], - "angles_min": [-170, -83, -90, -155, -91, -153, -118], - "angles_max": [170, 83, 84, 153, 88, 153, 2], + "angles_min": [-165, -60, -90, -150, -91, -150, -118], + "angles_max": [165, 95, 75, 150, 88, 150, 2], "encoders_min": [114, 1200, 1200, 1024, 286, 1013, 307, 706], "encoders_max": [3981, 2991, 2991, 3002, 3788, 3048, 3788, 2068] }, From 3687c441881580234c8d2345c8f40a00ab4cc53b Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 30 Jun 2025 18:57:58 +0800 Subject: [PATCH 37/57] fix(MyAGVPro): The issue that Bluetooth address matching fails is fixed --- pymycobot/myagvpro.py | 30 ++++++++++++++++++++++++++++-- 1 file changed, 28 insertions(+), 2 deletions(-) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 7636020f..84fa2ee0 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -49,7 +49,10 @@ class ProtocolCode(enum.Enum): GET_BLUETOOTH_ADDRESS = 0x53 def equal(self, other): - return self.value == other.value + if isinstance(other, ProtocolCode): + return self.value == other.value + else: + return self.value == other PLAINTEXT_REPLY_PROTOCOL_CODE = ( @@ -117,6 +120,8 @@ def _match_protocol_data(self, genre, timeout=0.1): reply_data = self._read_plaintext_data(timeout=timeout) else: reply_data = self._read_protocol_data(timeout=timeout) + if not genre.equal(reply_data[3]): # check genre + continue if len(reply_data) == 0: continue @@ -220,7 +225,7 @@ def _parsing_data(cls, genre, reply_data): return data[0] if len(data) == 1 else None if ProtocolCode.GET_BLUETOOTH_ADDRESS.equal(genre): - data = re.findall(r'AGVPro:BLE:MAC:(.*)', reply_data) + data = re.findall(r'AGVPro:BLE:MAC:(.*);\r\n', reply_data) return data[0] if len(data) == 1 else None if ProtocolCode.GET_MOTOR_STATUS.equal(genre): @@ -360,6 +365,26 @@ def is_power_on(self): """ return self._merge(ProtocolCode.GET_POWER_STATE) + def _basic_move(self, vertical_speed=0.0, horizontal_speed=0.0, rotate_speed=0.0): + """ Basic moving control + + Args: + vertical_speed: +-0.01 ~ +-1.50m/s + horizontal_speed: +-0.01 ~ +-1.00m/s + rotate_speed: + + Returns: + + """ + return self._merge( + ProtocolCode.AGV_MOTION_CONTROL, + [ + int(vertical_speed * 100), + int(horizontal_speed * 100), + int(rotate_speed * 100) + ] + ) + def move_forward(self, speed): """Pan the robot forward @@ -390,6 +415,7 @@ def move_backward(self, speed): if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [int(speed * 100 * -1)]) def move_left_lateral(self, speed): From 59e75f479c20a4f7c5c350d0d58f9fbe5c49bbb6 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 3 Jul 2025 13:44:50 +0800 Subject: [PATCH 38/57] feat(myagvpro): add get_robot_status api --- pymycobot/myagvpro.py | 86 ++++++++++++++++++++++++++++++--- pymycobot/myagvpro_bluetooth.py | 24 ++++++++- 2 files changed, 103 insertions(+), 7 deletions(-) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 84fa2ee0..1ab63df4 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -1,6 +1,7 @@ #!/usr/bin/env python # -*- coding: UTF-8 -*- import decimal +import locale import re import threading import time @@ -8,11 +9,14 @@ from .myagvapi import CommunicationProtocol, Utils, setup_serial_connect, setup_logging +LOCAL_LANGUAGE_CODE, _ = locale.getdefaultlocale() + class ProtocolCode(enum.Enum): # System & Product Information GET_MODIFY_VERSION = 0x01 GET_SYSTEM_VERSION = 0x02 + GET_ROBOT_STATUS = 0x05 POWER_ON = 0x10 POWER_ON_ONLY = 0x19 POWER_OFF = 0x11 @@ -67,6 +71,26 @@ class MyAGVProCommandProtocolApi(CommunicationProtocol): genre_timeout_table = { ProtocolCode.POWER_ON: 2.1 } + language_prompt_tips = { + "en_US": { + ProtocolCode.POWER_ON: { + 1: "[Power-on Tips]: Power on success", + 2: "[Power-on Tips]: Emergency stop triggered", + 3: "[Power-on Tips]: The battery is too low", + 4: "[Power-on Tips]: CAN initialization is abnormal", + 5: "[Power-on Tips]: Motor initialization exception" + } + }, + "zh_CN": { + ProtocolCode.POWER_ON: { + 0: "[上电提示]: 上电成功", + 2: "[上电提示]: 紧急触发", + 3: "[上电提示]: 电量过低", + 4: "[上电提示]: CAN初始化异常", + 5: "[上电提示]: 电机初始化异常" + } + } + } def __init__(self, debug=False, save_serial_log=False): self._mutex = threading.Lock() @@ -86,6 +110,19 @@ def _save_buffer_data(self, data, to_local=False): self._save_file(self._serial_filename, " ".join(map(str, self._data_buffer)) + "\n") self._data_buffer.clear() + def _prompt(self, genre, code): + default_prompt_tips = self.language_prompt_tips.get("en_US") + code_prompt_tips = self.language_prompt_tips.get(LOCAL_LANGUAGE_CODE, default_prompt_tips) + prompt_tips = code_prompt_tips.get(genre, None) + if prompt_tips is None: + return + + tips = prompt_tips.get(code, None) + if tips is None: + return + + print(tips) + @staticmethod def get_significant_bit(number): return -decimal.Decimal(str(number)).as_tuple().exponent @@ -97,7 +134,7 @@ def _save_file(filename, data): def _match_protocol_data(self, genre, timeout=0.1): is_save_mac_addr = False - for _ in range(10): + for _ in range(5): if ProtocolCode.SET_COMMUNICATION_MODE.equal(genre) and self._communication_mode == 2: data = self._read_plaintext_data(timeout=timeout) if len(data) == 0: @@ -120,7 +157,8 @@ def _match_protocol_data(self, genre, timeout=0.1): reply_data = self._read_plaintext_data(timeout=timeout) else: reply_data = self._read_protocol_data(timeout=timeout) - if not genre.equal(reply_data[3]): # check genre + + if reply_data and not genre.equal(reply_data[3]): # check genre continue if len(reply_data) == 0: @@ -160,6 +198,7 @@ def _merge(self, genre, *args): reply_data = self._match_protocol_data(genre, timeout) decode_respond = self._instruction_decoding(genre, reply_data) data = self._parsing_data(genre, decode_respond) + self._prompt(genre, data) self._save_buffer_data(b'', to_local=True) return data @@ -239,6 +278,15 @@ def _parsing_data(cls, genre, reply_data): respond.append(rank) return respond + if ProtocolCode.GET_ROBOT_STATUS.equal(genre): + machine_status = reply_data[0] + if machine_status != 0: + machine_status = Utils.get_bits(machine_status) + + battery_voltage = round(reply_data[1] / 10, 2) + + return machine_status, battery_voltage + if ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): respond = [] for index, data in enumerate(reply_data): @@ -333,11 +381,33 @@ def get_modify_version(self): """ return self._merge(ProtocolCode.GET_MODIFY_VERSION) + def get_robot_status(self): + """Obtain the machine status, and support the acquisition in the case of power failure + + Returns: + tuple: (list[int] | int, float) + 0 - list[int] | int: machine status,Normally 0 + 0 - (int)Emergency stop status + 1 - (int)Power status + 2 - (int)Front bumper strip + 3 - (int)Rear bumper strip + 4 - (int)Motor No. 1 connection status + 5 - (int)Motor No. 2 connection status + 6 - (int)Motor No. 3 connection status + 7 - (int)Motor No. 4 connection status + """ + return self._merge(ProtocolCode.GET_ROBOT_STATUS) + def power_on(self): """Turn on the robot Returns: - int: Power-on result, 1: Success, 0: Failed + int: Power-on result + 1 - Success + 2 - Emergency stop triggered + 3 - The battery is too low + 4 - CAN initialization is abnormal + 5 - Motor initialization exception """ return self._merge(ProtocolCode.POWER_ON) @@ -374,7 +444,7 @@ def _basic_move(self, vertical_speed=0.0, horizontal_speed=0.0, rotate_speed=0.0 rotate_speed: Returns: - + int: 1: Success, 0: Failed """ return self._merge( ProtocolCode.AGV_MOTION_CONTROL, @@ -514,8 +584,12 @@ def get_auto_report_message(self): 0 - (float)rx 1 - (float)ry 2 - (float)rw - 3 - (list[int])Machine status - 4 - (list[int])Motor information + 3 - (list[int] | int)Machine status, 0 in normal cases and a list in abnormal cases + 0 - (int)Emergency stop status + 1 - (int)Power status + 2 - (int)Front bumper strip + 3 - (int)Rear bumper strip + 4 - (list[int] | int)Motor information, It is 0 when it is normal, and returns the motor number list when it is abnormal 5 - (float)Battery voltage 6 - (int)Motor enable status 0: Enabled, 1: Disabled """ diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index 790c070c..18667046 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -55,11 +55,33 @@ async def get_modify_version(self): """ return await self._merge(ProtocolCode.GET_MODIFY_VERSION) + async def get_robot_status(self): + """Obtain the machine status, and support the acquisition in the case of power failure + + Returns: + tuple: (list[int] | int, float) + 0 - list[int] | int: machine status,Normally 0 + 0 - (int)Emergency stop status + 1 - (int)Power status + 2 - (int)Front bumper strip + 3 - (int)Rear bumper strip + 4 - (int)Motor No. 1 connection status + 5 - (int)Motor No. 2 connection status + 6 - (int)Motor No. 3 connection status + 7 - (int)Motor No. 4 connection status + """ + return await self._merge(ProtocolCode.GET_ROBOT_STATUS) + async def power_on(self): """Turn on the robot Returns: - int: Power-on result, 1: Success, 0: Failed + int: Power-on result + 1 - Success + 2 - Emergency stop triggered + 3 - The battery is too low + 4 - CAN initialization is abnormal + 5 - Motor initialization exception """ return await self._merge(ProtocolCode.POWER_ON) From f2749ba6d32918ddbc2b9c9510fe98fbf706032b Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 3 Jul 2025 15:51:34 +0800 Subject: [PATCH 39/57] feat(demo):Add myAGVPro composite kit handle control case --- demo/myAGVPro_Composite_Kit/README.md | 72 ++++++ demo/myAGVPro_Composite_Kit/README_zh.md | 62 +++++ .../agvpro_handle_control.png | Bin 0 -> 176144 bytes demo/myAGVPro_Composite_Kit/composite_kit.py | 236 ++++++++++++++++++ demo/myAGVPro_Composite_Kit/core/__init__.py | 44 ++++ .../myAGVPro_Composite_Kit/core/controller.py | 153 ++++++++++++ demo/myAGVPro_Composite_Kit/core/drive.py | 129 ++++++++++ demo/myAGVPro_Composite_Kit/core/joystick.py | 202 +++++++++++++++ demo/myAGVPro_Composite_Kit/main.py | 63 +++++ demo/myAGVPro_Composite_Kit/requirements.txt | 1 + 10 files changed, 962 insertions(+) create mode 100644 demo/myAGVPro_Composite_Kit/README.md create mode 100644 demo/myAGVPro_Composite_Kit/README_zh.md create mode 100644 demo/myAGVPro_Composite_Kit/agvpro_handle_control.png create mode 100644 demo/myAGVPro_Composite_Kit/composite_kit.py create mode 100644 demo/myAGVPro_Composite_Kit/core/__init__.py create mode 100644 demo/myAGVPro_Composite_Kit/core/controller.py create mode 100644 demo/myAGVPro_Composite_Kit/core/drive.py create mode 100644 demo/myAGVPro_Composite_Kit/core/joystick.py create mode 100644 demo/myAGVPro_Composite_Kit/main.py create mode 100644 demo/myAGVPro_Composite_Kit/requirements.txt diff --git a/demo/myAGVPro_Composite_Kit/README.md b/demo/myAGVPro_Composite_Kit/README.md new file mode 100644 index 00000000..abe03519 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/README.md @@ -0,0 +1,72 @@ +# myAGVPro Composite Kit Handle Control Case + +- [简体中文](./README_zh.md) +- [English](./README.md) + +## Program description + +**The handle function of the myAGVPro composite kit is shown below:** +![](./agvpro_handle_control.png) + +**Note:** + +1. Before starting the program, you need to connect the handle to myAGVPro and turn on the handle. +2. The `myArmM750` robot arm does not support suction pumps, and the program will prompt when using it + +**Kit Usage** + +For the use of composite kits, please visit the following link: + +- myAGVPro+MyArmM750: [Home storage training](https://docs.elephantrobotics.com/docs/myAGV_Pro_en/7-ExamplesRobotsUsing/7.1-MyArmM750.html) +- myAGVPro+MyCobot320: [Warehouse cargo handling](https://docs.elephantrobotics.com/docs/myAGV_Pro_en/7-ExamplesRobotsUsing/7.2-MyCobot320.html) +- myAGVPro+MyCobotPro630: [MCU door opening training](https://docs.elephantrobotics.com/docs/myAGV_Pro_en/7-ExamplesRobotsUsing/7.3-MyCobotPro630.html) + +## Run the program + +1. Clone the repository to the myAGVPro system + ```shell + git clone https://github.com/elephantrobotics/pymycobot.git + ``` +2. Enter the repository directory + ```shell + cd pymycobot/demo/myAGVPro_Composite_Kit + ``` +3. Install dependencies + ```shell + pip install -r requirement.txt + ``` +4. Select the robot model + + To select the robot model, you need to configure the values ​​of `COMPOSITE_KIT_TYPE` and `COMPOSITE_KIT_COMPORT`. + `COMPOSITE_KIT_TYPE` + indicates the currently selected robot. The modified value needs to match the actual robot model, otherwise the robot + cannot be controlled normally. The current optional robot arm parameters and models are as follows: + + | Parameters | Robot arm model | + |-----------------|-----------------| + | `MyCobotPro630` | MyCobot Pro630 | + | `MyCobot320` | MyCobot320 M5 | + | `MyArmM750` | MyArm M750 | + | `Undefined` | / | + + When `COMPOSITE_KIT_TYPE = Undefined`, it means that the robot arm is not used. At this time, the handle cannot + control the robot arm and is only valid for MyAGVPro. + + `COMPOSITE_KIT_COMPORT` represents the serial port number of the robot arm. The serial port number needs to be + modified according to the actual connected robot arm. Configuration is required when the selected robot arm + is `myArmM750` or `MyCobot320`. + + When the selected robot arm is `MyCobotPro630`, no configuration is required, because the control of `MyCobot Pro630` + uses TCP protocol instead of serial port protocol. The values ​​of `COMPOSITE_KIT_HOST` and `COMPOSITE_KIT_PORT` need + to be configured. + + `COMPOSITE_KIT_HOST` indicates the IP address of the robot, and `COMPOSITE_KIT_PORT` indicates the port number of the + robot. The default value is `5001`, which needs to be modified according to the actual connected robot. + The IP address and port number of the robot can be viewed through the built-in software `roboflow`. Note that the + robot should be in the same LAN as MyAGVPro at this time. + +5. Run the program + +```shell +python main.py +``` diff --git a/demo/myAGVPro_Composite_Kit/README_zh.md b/demo/myAGVPro_Composite_Kit/README_zh.md new file mode 100644 index 00000000..db359583 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/README_zh.md @@ -0,0 +1,62 @@ +# myAGVPro复合套件手柄控制案例 + +- [简体中文](./README_zh.md) +- [English](./README.md) + +## 程序说明 + +**myAGVPro复合套件的手柄功能如下图所示:** +![](./agvpro_handle_control.png) + +**注意:** + +1. 在启动程序之前,您需要将手柄连接到 myAGVPro 并打开手柄。 +2. `myArmM750`机械臂不支持吸泵,使用时程序会提示 + +**套件使用:** +复合套件使用请访问以下链接 + +- myAGVPro+MyArmM750 [家居收纳训练](https://docs.elephantrobotics.com/docs/myAGV_Pro_cn/7-ExamplesRobotsUsing/7.1-MyArmM750.html) +- myAGVPro+MyCobot320 [仓储货物搬运](https://docs.elephantrobotics.com/docs/myAGV_Pro_cn/7-ExamplesRobotsUsing/7.2-MyCobot320.html) +- myAGVPro+MyCobotPro630 [MCU开门训练](https://docs.elephantrobotics.com/docs/myAGV_Pro_cn/7-ExamplesRobotsUsing/7.3-MyCobotPro630.html) + +## 程序运行 + +1. 克隆仓库到本地 + ```shell + git clone https://github.com/elephantrobotics/pymycobot.git + ``` +2. 进入仓库目录 + ```shell + cd pymycobot/demo/myAGVPro_Composite_Kit + ``` +3. 安装依赖 + ```shell + pip install -r requirement.txt + ``` +4. 选择机械臂型号 + + 选择机械臂型号, 需要配置`COMPOSITE_KIT_TYPE`和`COMPOSITE_KIT_COMPORT`的值。 + `COMPOSITE_KIT_TYPE` + 表示当前选择的机械臂,修改的值需要与实际上的机械臂型号匹配,否则无法正常控制机械臂。当前可选机械臂参数及型号如下所示: + + | 参数 | 机械臂型号 | + |-----------------|----------------| + | `MyCobotPro630` | MyCobot Pro630 | + | `MyCobot320` | MyCobot320 M5 | + | `MyArmM750` | MyArm M750 | + | `Undefined` | / | + + 当`COMPOSITE_KIT_TYPE = Undefined`时,表示不使用机械臂,此时手柄无法对机械臂进行控制,只对MyAGVPro有效。 + `COMPOSITE_KIT_COMPORT`代表机械臂的串口号,需要根据实际连接的机械臂修改串口号。 选择的机械臂为`myArmM750`或`MyCobot320` + 时需要配置。 + 当选择的机械臂为`MyCobotPro630`时不需要配置, 因为控制`MyCobot Pro630` + 使用的是TCP协议,而不是串口协议。需要配置`COMPOSITE_KIT_HOST`和`COMPOSITE_KIT_PORT`的值。 + `COMPOSITE_KIT_HOST`表示机械臂的IP地址,`COMPOSITE_KIT_PORT`表示机械臂的端口号,默认为`5001`, 需要根据实际连接的机械臂进行修改。 + 可以通过内置软件`roboflow`查看机械臂的IP地址和端口号。注意,此时机械臂应该和MyAGVPro在同一个局域网内。 + +5. 运行程序 + ```shell + python main.py + ``` + diff --git a/demo/myAGVPro_Composite_Kit/agvpro_handle_control.png b/demo/myAGVPro_Composite_Kit/agvpro_handle_control.png new file mode 100644 index 0000000000000000000000000000000000000000..f9f89a5c8c1d8302885010ad5244c4b66869ec5b GIT binary patch literal 176144 zcmeFZ^;?_W5;hvVMGHk+q*!r>;ts{#U4v7c;-pZVLXqI^?!`)x;sn=SM6yh%&z`H)*D&fm4-^_1g^PRia0mjuX+HAg+{BtBn zJX@su_IUXJ^P%|xeVpKb-^cv_@Bcq)56!%X%chP&-=iONW1^33uX+8i*TPO$gK?7V z+LwLyD|FNlkaYpEf$2L1Da7gCQCUZGq2b6)srNdpsA*EkJ^xEw!w!h-z* zq&(@<-kXb|s-Qo{JA2YA5)WVDj29tCZolWyrjdVgzs-6qYkDE>?l3qgh|%P)&%%rVSNq?-VIbk!~jrD9rapRb#@+I%%2=@kD z;z%sOIqT_lZo<$yCK%R_jV_=~LJZKK=GYUXx0q456uQU;!gmiY1{jHpf79(Gd`ujv zMQn4v+ZeIFE*@!%9}Y~2im`hAWC@l(Vt-|SVT-YVn?f+n(XTl1Fkv<#y*j_eYIuWu z+3#$m_su){9UCcr)IY)9#`nEknbt^S5ji9d;xih2 z{d|L6YS;pVuug(33?4}U(JDcp*-LzU&Dy6>(!>CcDF0j>OQZ9xCvyrV!B4FAqI?M| zw~E+CV0k4WS`8Ph@mFx!!k(r-Y^-C5i{c>u-bp1MOLSMg(qT+Rrp4{?Y(-T5KFtz$ z7qLyEhl!qkKngj5=);rV`A>R_e|ry@>po&pK~CGVTr@s1Vf4~Fn}BcnjZ|V(G6&@X zd?WmSx1%6sS>E_q@4wc4AMrwi?6CH6`Rk2V3&D*uGL$I`2S#J=eKkc?22A|Lo7ekI zi$*bz!bw$CwUbSJ*TKE7xx?qp1KMvN1ORT8y$JBca7`r}C|dis()f*dCL z5<>b0Xl&x9pO!U5Mv6V$6%_?cGbC#(M`)*BK#al00{2Wt^(SYt`^2378+SL8Y_blD z?M=s{SB6bAI2Vas{MNPPm&i&S8H>SCOdF1?gS=~7Sv@p=yn>sa0>QBGVppCqcxK+N z{O2|eT$ao~vSdq~3sMi3=O@(l$q}$>18j$($QdMF2xcZs@qX`^FlhOWXXa0F<5=4V z3Gp@K5#497C$gCue4hPBJCq@!RzPvJ|Dk#}EqFqQ0;yXHWuU*mrEzf-eYkdBakxas{~I9;3Hv{3ToZ2yLu7|rAWT=jgK7el%y z;o7!~#5Tan?O;;CRuP1^_I><@haw?dT4;FUNg=RBkug}tsdv8*VnT0u@15EdqhIQA zuyZ&7HjxrlC~R+FY#%!yL;#lmcL8x)CW>N8+?+_JL&btwIbI89v-CR6|A-}ID8(fI z(YqH~uJGKWkWpMmMC~!<6p^0jg7=tl#cJ;9bQx9tf{(m5L(F@QVk$Z@Z?y_dw;uOC z$!&N1*l6&#c+zT%I{1p;WaWUzJ6~GYcFT#NYXujKuUowyyvK@`P`MElD;|XY}Ch5YC>e^CJaRKL@Dk)f`VeS zo}`b!EeayA*ALeM%j)n;x6~yNo|u>284Kk8SLJVF=evxR9q*N)?(baBJBCnHmjg2L z)e2T;>SQCGIX#hg1YTjFGcrvSmp8<2y#;sWH|hR%j^M)EQwM`sk3w+eedh6Xve@G5 za?3vxnE=oIFrOgkKQ6^hA*0Mh%z0 zA1&j5!YSr?tKC<)S@#^o#es!o0HaGh>dbc{!qw>9Z0B0?1sJl3dGX>5-$TUSPJ)9f z&K0UK-BD0bW-$LE1q$4(41*_Sqe-#NSB3mj;^G82MqnqIO1vD1bQOM@t4wiSF4K=J z9+?J0cSsT$^`rnZM`h)!`qU6;r8VhB!a+X=oqNdwrr zAnM`A`5`(SnRNf(t0KCiK;eKYlcSzSL}hQD;y`XQA7EJjlPb9;U$)7y#X_bi= z_y5=w9$V`18(Ntx@a52l;FuC4<}IOP8^_v&oob-LKC8ZM!1Z%|oUnZgeh$C?1v)XE z0>|nr75DbCaya0dx4evEfTODj`nZ7sJ?PITL;hF4XZ`6h zr||O=mqQ%R4t#)3YpN;{j7x6{KBby}6OQVDF)=)q#-9#8z2f7$pZ^1oa5)Av$R#m@ z+CBEP^l1aN=*TLOrSL;r%vH!*}(PM?DgUK&It56)F4lQ`LpEZ;wJN+>9_OeQ;d zqWG&OWG4Dw#eyqBzVSr7hbK8G%{-f@DHnM@2G(Tob! zj6hX1|7eH{MP`zd1J(!_IBNb^MovR~o_-6Jky!GGs9_?ORBxjk(r-aEDW>P6>a(12 z6=n49Kd$obw3fliFOz=UN$=(CJVEYfkC>TLHMp2Mb#;=8(f`{;Q$R&DZ+>#-6oRHX zuY9af)o{ZRjB2f-;mg>nN|NljZYMPakpIoGuHthtM?)r$ZOp=lfP*N>`TfLCPXP`0 z>jF-%b5B_jc$bLgjCJ{)3Dw6dPQ&LGCgT8w20mzEl;*PP@)a_B$E z<$$Lmf%qtc^ZnYg9)G#wOb)!QRl>i5u);NtnpAxqI1`>Du5S(6k2{%U-;am zFKCE#5zK%_VW+rbKQolF>a)~Zpjojk%Xqz1_w)Pj*;3+TDHtApmUAN*`H}MfZ+HbT zY`n~PhQ>RnR!Dto?R1Npg`cE;`{j~sgh^hev5wj}PM6NtI3h+7`)`flEtc#?coq># z7J`BT1~Zbi8X66S))W7X2RFPjVB>wo-u zXCRl!r(52wyE`jC&MX6;n2dG4OST%vGF9>?hx;o!D!b4Wfuza|{iMqEaRPo`nJs6U zr|N`OLZ?hco}YH2^Ay*qF*rzG11gqWjJFpNg|DN2wj}#dKat3-0vzLeJtoAhHNR*n zNy?UW?%gOE_D79`XCgqRIF;xryl(y}WXEyElcOYn4{?j4ft$-c0>xb)$=BmbpXK?{ zbuHr;e;Oj|?o_-2f|8yYhI_>PZjpVe;9MniJRcKJ>-_NXY>}b)Lto&gFZ7~eLa~C5 za}x==N{^Lc(tB?OCyC%F#CjH{$@rRD0X&-N_pbCCEW-59+Zk3CaL^y}(Xf8>-4 z-DK0~{eugPKfEait?pVi&E2}|YA3ur&Cr{Fi%wNHSx=dbpk@*N!NwB!oR*qG$y%ha@!syQbfe$|gO(Ttl5 z&G{6Wn|jhjj?!fl0sn6h?AQw7F_DYW@o4;~`qe_&sY@oN2*kgApIjP!>j7ozi0~+w zhLjc%iOZm?J=}zGja1dM+yWCL&LY#u-mH?0T{*otvQ|$O;x1KYp2W)qN6ts zMx@@4+RGUTV@ui}qU9kN))&P#>IGqSDu5V?q!mWkW+UG;{ck*?>_jGRdOdX@e-#5& zEk))q5&Rw+*YOl(4PhW8K;ovzBdzHLFn+7t$M{Z-*t(w7pyX-7`i70-_`fBgCI+&5 zrEV=1kCrd^A8}9c07p0VUM|FcK~n@V53h?(O{&8@f`!zkaFv0ux6Xh2Gk5WUtWJZH z`e`&?nvf4-!}%vPb*lQo90ZyB7^(&?Nz zMO)&kvv)MkL*AI9l;pOM+-VV4=^r9@$KA&rZ|FF!zvzSXsd=>2$5WdF(`MPE<1Q1Q-HvAwqg0ajgp7#An_+*VcM?n6Qu1K2gi`VFL zuwT_&PF@USDP6Qs0s4|Uf}C=@k|J@UPLC^y{bsL;KN}BSi9q?$V(=xXxLe_r?w#e4et@K1o zsCVXw==##Vy|$62V{Vj$oK&Y+dFwJLCub5LZQ#0_0eb4zzJtn(S+-D@{F$%g z+BjuJ0%`kI*e{~?H2$F$=0CsOqW`Xm@E8JQjdDtOQth$h?g752C->s@1JmNu8JWOM zIWGf0J@B?i(ZSl8#e)lIvAJ54K#L_e3PVMDd%ZvZCA?!XBAkI{E5bwiP+cjg3eEWU z9tb1-V&qS0i@25+U-#W3LY1?#zbc&dQ9MyB$fkzYGv243g~+3kovo_Y3snNY%A7r# ztXM6Qb~{a~FF832G zX9$A1xR#_8wpT5YiY2_YB(pr0j%qF|utP916k2dXML{7*zHr3Ec7dXgBR1DOwVNZA z{CUwcpPwmw_(3hGPdKGLwuCs@aBz-+Bq@w@b~vmH^L z31RJ|Ckc|D78EQ15~>1oFuZOS=Gv1?nYXlAgXKn;L7&sj#9Ja~GnEvDe<0SPb=D}%jcV-C44``AIcYI=*0F%9y^#+FE~`In z>~s?}^K&6ztU;wE^bF<%;`2s=k##XpnI;Dz9hwSeDXK4f#4di1Dn|ut=&Mv(ZA!Q7 zeO}%>D~}H!?U?E10LeevFe={$*`-Mol;i8^veTfK2%sxjm$gf*R7Da*a9wr?ml8Xh zfpnGROVoIBFpdYM5+kv#^OQ%u#DECXa|OW20Iz^=OSRPcfjfzxJtBG8gbaH))L$yM z#vp1nR0hqM{m%Z7PE2CoB00zEt2K8JA~u`ngyY&N&5iMlYutQ6z5mE3z|1bnA^}Ga zp;?}&olr#QngS1BGoY+)y!Z9(F@RpBH#2$qpj&!A1_=@wITn>RkBl<&LHKU@l-n}y z+qfxYYo_4yD=oxUFA)OYGY$2EC}2Q>_)!b^R~x%eBLRa0LEx5j-x^Cium&2O+0iDX zsiEFy;10QQIdQQJW(OSFpqQqnBD#Z__xseCI0^Q+diM6?==XagA0&(ZR{SsFm?u{1D%HBnA8mA7LmC?8(=xa4GDDY??N=YYmGmKv(Fw%CLI|W-fB`W;> zs2ak+jl&QKi{Q$Fnd%6*Q62*~co=fuw~uYwXWf=Fd+j@&E^j}|k1$BibJ0Nt<$_pO z5C#G2N%c@kog04J7lg4s^X``r#wOA2o{3z0%`r^W+J3oOY`cHDzFqf_$)=$&q{?s|nZ+|dP9R)8 z3>#o(!fnmKtWdu_?qc1dNey;ymYtgeUNT#LFW5HMD=QKsQo{OFWuf%)sC&BO;eyRt zL>Jt^ToTH3ks*6(vYu4BGJm`tEPu&Wz?T6OHqqqIMgt-mxePD{h{$b?(w(%{RHpB zTcZ-8d+E@%o_6X_(X#01P_0H49aWMDc|14N_+c$$ov!K9h>+wcPp?s#g}b3jS8Vw| zVedikz*Qzuc2(_tc3d|=sKzQaW9=xetoD@$`T{>u(&kLHGn{T z<~49#v#H)9Ggi2+EPrlj{=+5!v-LoCPxa7wADGl~=-hCiTN-8%p8%dZ5s;rj-l=;q zINugXdN63&luYT;@*}1h-K{ubYhIb~$=EC3Ei-%NRdO_K;V)u2GZvp)PV9b+Ie^qU zIabof+{8w}@K7P~P|wi>D-P@#C;0wuMvw5YY{%LbRHa|6TgX^+0M)~m91X)*#K)<; zg|mXSb!hT7=DHkId%$t61WrQoFY#~6X_$QOolZB89^)2T<1LSS&RFjA7zax^`lZ4? zq}yalg)v@K2$i+JqAhtVmJDR1Nifr6z}9uan5cA63#C`Mt1i)!m(*cJuq6?tgM5@b z{d6$DHsh@^O2qnn+gWNXBBPx+aup(41&%)&)X0grFgf!j95`i$)s9-J#KT`48GQ@Dn{* zr?8U_8?`TIcBAZ0V_c5h-Z-EWpN@N_#x^;ctT3%W_I&vcRVxFO75H$LJ^FAG8#th2 z;t!3s4K?vQ3GstLlTWWY9)Ew~ignbT)5Oz-##bIW5v?*!Z8v%HuteVxY=WlU&sn1NvsffI7l*E}skr=`(}S%WNO#yt-^ zdVFw#LD>R#4@P)b5|fR6u9nvb-dW17N_WKe5ISad+$69nP0ofA+g^0+_P>&TH@15>z(N#za5XT+Xa? zFrsQIZX>c9Y>kz(lsQ(u$+H$8W|I@f zS@LC_#VVXsC;Ivs=eYDrRa)68h*c~qmLXw~oo)OyOHwas^}MYDFvSpQaEH?1Y0!?-0 zX0~Z_JXf;LX+>oIn|<<<=c40iqr*H^)3Q%_y;AzSmbHa%_P^ciHu}DNXto-8rPuT! zb3tFP#kKJDN}Ef9Lz_pw!*AF0gN0fRPsbI?+ds_;*uQE^Px7gPJG5nnJW&mqvc@f08EpfBHz+}|szKsdN5^t?<=IT2qXuZ0#PBU`^QJ7bh zR~PPUKv50Mq~k+B=b>e~ju3B1Qfe%kpY;Cwspn#;5014!ahXC!6eDhv=PQIyQy66` zgIw|C!YDSmnVAVDrX9}l^>iZ{(h0_*CH9y6#8!ONBxv1DdEbX?WxXKj3m^L^BLxLY ziF93dh7gopn6`!~e>c+5;j)+RwDXA(P86t!-fIS&rLPRwqw|i5+*bHqeP02ik$ZLi zVE*0aT_0R>u|Egdn<<~EHFyh2X8X9>U^i2C{-VS@14s;wwB1_daTW|`zHTbx!y<*2?+1qyNlTN)G{R*He2Q=DxwuF^)`qwX_(mSdnLs@Th?{DThl8B7G zx)5fUfA|6y8y&H0K=epV6a@}xoEu{n{tgp)(sj;j61+6N#Eo7j=6bE}rS-H5NhK_a zg;6s}%<2ZrkR(>MRsB7O-F4bJhlr{s=Qw8N`Mh+ZA@ko9i*=$gE&jKjbDAf?I3mvX z{as-f$)Y5%kTo zSwkwQK~+*e&XiqtT+cj=_xLV9!IE~}hERXvT~Q!4M>?l46myf^%~S`_hT%{oegD%6 zk**7uLf{I(hjd1IM{^B_(xK2~S}&T4O$4D}ka}@shz7R5Ml?e;{{ZvLXT{*Sp#_W&LJ?Iq>~z+4q9{M*@oR^vD8Zn#pVx%`0*7 z7U|8VJWgWNrwa;Qc_JZ!RsF1Plf%tL+5VTQcW_X0QK}NT*`fA+yuZqvxZ5M@xDL6y z+ZO%!_2-N3PqeiFr{9mqVWQ2B^IH*4xTH>2jzoUH`5+#st;uKZZy@)?BZC5-rm<=9<3Zv=@a&zB0yG$IwNJlq8|W2 zTxNq&=g|y)PN%G(#GkmJ-sVq4l0_q1W9j*(JpEYI=}Z_~dw$k#z%1j>(INCd z9RWe!Fbr;urZTx%6$6-1v_u?6(s-D#3?GC-9mY;d-K733`(OQ@W~=(KN)T_O8UK*` z7&Q`97H!A!G$sdU!kaYK<%7pRA3GAV?>6bMYX*GYH$=M6qAG#FIEuq`BRpqv)=Fng zTWhOpHk>1VNfs55%XSzxi)7Kf=wf;>#7C+>JoF@!TH%wC-a3Vb2!%|QE*RD5d1t~q zoL0Q#TW!+T_~hO(nPLyJ;GzTW%ecB6Ml830X%^pXxO$z!xH@?aiF!==BF-ebFc1`p z$hmtwJDGdLhxm*H@ja@|EI0ehd-cvV3`HQ7L5g%eX5FygF{g#-9k%*x$Mt%Y-tMOT zYxj^x41$u5A9Sb7h;hjV;X+p)amCZn%fm0M6RxuuWlxjsGU8qe0MJn!Ty{Lh1E)xD z%uaG=Z;v`wcnW`}qPPR-gBi9+Oi9F2IUM($GmDio_ZsPdjV#tCDf~57ok`-PQ_;7f z!8X{85Cri&r>8P1c1VsHqrZ+y@O3gHg->1H`+3GiSsi56373r##2>)tx2J1t{1Qoc zQw*KvuMI3swT(T}0+gk^B9Qfja~$;fd5-gh5aq2Y{1zeq1!xG_J#`wk$v{_ z{cs%L6tXA_1NUhA&KD_&bzXplbQ2xo4!BdM}#-MwuoYhz9ej39;YS0M!`Z*ms9wvHt9R(LWVNx02F-L%hKk z3Ya_JoyxQb(}Puo_-E8*5d8xg&tR?v7MHmZLQRcAfIMoQPqed5Ggtc#!luyhfK1{C2< z*kZnrrxQ>B5gVhjXjDPsq8K41i@?=t;BD~oR~Lh<60?= zTMk|W6x7tHqT-Mr^tqs7H9JeN*qMf&S@*TJI1EnG$Ah{DJ!$r@=M6*?0t?kmFxt(7 zI&{g$r4t%Yov(vq6oJ1R;Fq56lG`49H0iwNO~);PUtNaCud+BD*+_}4$zSxi^#RZa zQu*DA6w}`+y;aF#)+kbRVWTC^=5xub& Yb%c;C2sK*!?-4+V7x?-hSW%`3`T(M> zIfiKOj0AC_?f1fY9k1Bf;@cOsUgJNoCFX~JpoK}u*onT5UocaZE}50k88FuEk}o>| z+WzCR27a3tGdd<7{@PyDINWQN`kIho5QJ0#5akluJ~b$ym_B9ebexLX$ovzS#O7Z6 zV}4yaD)VgMA$jjSNhuvVNQVu{emu8L%1=SolRJyi;^v^Kl~oj#olyr-0GOg7Sz^|JD5G7F7+$~PGn1B%;~3=x*bgN>tAi`Nc^TJWwB*oo7`&nW z7;b~0qkU9j;W;|I{qfk>-kz}gI50OuQ@ayL*jfHlDySq<9Y&ta((655zy8|a@zl9T$WriRaHl8uQa zR@(2gH{8Se{8pIb`#48GS%qc@UJUJ#bwsHM9}5d7%uw7kf~AE^htMC1hQzs_pZjMg z%SfFC#f@qpLPMfk8=ZLkuE)V>%d8@5s_!dsD~Hn&mp#x(Ftid4q~|6X<=zsW zgqVb5qR3`QT)4C~axdgTp3E5TxZEI)4X4He&QBFi=Q`dy?acrc1;4b%7eRjJ7MS4r z2eRYYYyOB1<&m5=Ny9r0#Jy&S-M=dqy%#6EyB^fDw>6-lXT&S$Ilg^QaUWNSgYC8S)^xnXvMH-#@_M z1bVKU#EYXWbW-Pf%o=vcg^qMp+v%@Q~$Gx zLZvcC_2T_c*MpI;k{COuh_=KUQj8Hyh|$Ai#A(vc_L3PD8yx^WWxzG*~WzR*fj z>rwmdQo3W57>NynxKtWdb0h$gq0F3hA5A%0$igc#m7&aKFcx?__Vpe?HHwf$dpnDJ zfm>lI=NRSu_g+yln@MR7;YIpd8-TwtJ-^?e-J$eA6AhM*Bm5@T|48t3*1&0KJ3C?U z#SUUkop^a$E>m(id7_m|7~9j7>XGAZ<;$jK_*5^QEhZIiUO)J3)-d+^w9XT`1P7j2 zDWJbU2C~9Ct%ifekHxc}!04BjH&G(24$wB5d?6%ORE+?Bw2~AwuaOLrL$}#sn`~`s z_Vg?+x`f$Gn1g{X-@D8dtAk&)qv7EsLbapUCmX<}W*0s75ZEekqcO8%IM0cATM7Rr zPKMlt&E}dJX#~^0j9v$!bx784lh3;7=i>|52Hk{D;CC)FZ|gWVTdJzduHEMljlPHA zAuVSa_~boFB}AAirLt-iDJPfeQ*4dS_>^3H5Fz+47{2_Oaat# zSo9Tq8XE2#iiRF^n?gblx&af}TO=+!Q)hYt0H>wx$Smz z3|d~@K5b$`+5o?i{lVoiVgc|%%4MhNn_*X`tEl}fCd*u+8$~PUDh~!|($*mqF&X@k z%1|oz{g+ozKxo~cZo)V?$>8ppMQ%~Ws`D#NMB%MUS`k3%rR1vYC%big22xQYbh@2J zH=ThXX?ud6t-%JlDPR#&P0NSC>D&_j_2~uC@kb-v^-4bU*1NGL*alcPLN+PWb{-i zm9dP-dQp$`D8{XP6D)cG5NA2-6W)Y}y)2!cVw0Jzkcnn*dx{>G^r~ z4AB*mXiS;7rkjcJ)yQ224PA2aWbu?w$t>3MZQkc>`cNtpz^^oLIq<%f$JO-l_vx>X z9fvvlC;jbAq7M@gR{u7iU)=1>sQL(PcG=C_@Qau&cY8V=@o<9e=Y_#~Are%?CzV~H ze`c~qdfKBXC}}nX-v-thqLfYYLlK}H&aO6EiLH0PTG;LIyTf;a-LVmInWfIcU1CWHE~SE4Ru(ex=))cvf9AxuY!Mz`3IG^~#d#3M;3C>y|olv>V!J7glP zvwd2Kokmrf2#uGjP={N@GGr2In{hvtEu zI*E!%QO2&s(XbrNcs=1>2ch=N4mN|Z)?uf`N{^#&bH;8X-1ZWgKf5YeSl$e2d5b46 zC_pquFhy};MvPtWMMls^_>@&!O5yddD!f*7{aY)R3A*=YzD~n=qOIL`S0e1<;=Z=) zCjq+ao~M!c!IY3)emTE#`Q?y4@G1XD3t5uTdq^sWsyNnhc+J8D)q(hI*rt_7BXinz zD(~>a%KlA;do-8p6S~b(I`U** z6JMkDo5|CcXaqV%q%80OBM+XGT)epO z*NPf2YBlLNkK=p%--UkwwA!<&GWCWr(hFC$7X5?GwbJT*R&~*29b!q9-&HP!?-~z; zj_Za^8fE$jS(1L{0qfRh!!}3JR=yfI1*-R{n9v1>5e<&#=3DN3%@rVJgm-Zo&t5a2 zFn@9WAkE6k(fUEBnPMcc1 zGf9Lm2=X%IxbY5ntBc;LLl-N?nZuX^YNh}79&AivB z+U*GHR+m;Qu{LoRm@<*x6=NdK#Bv4V*=62mzvygN@v2opTlxHf3CEM2O#t`@rdeKb_BB1)|y;-YKpvnCDOpm_Ki zb!4+YZCH+foj^CBCUwRl5s(U{_roF=QVgSZ z7tIG=AIG%@qOgasMR}TuaDy#Tqbi(Cp={|XH_E>(zsbEDTkM;KF8ulZU1!;A11q_r zSO9KYl07KlV7p3QCabv#?KS(DRfrWSUC9#s)?A5sqGk(ZGKf)Y=02OrpFZ5-$IV`O z)pJU?Nh1;Hfp6##i}{?_oYU64POV6-F=WugrW-Acg1Jl~Z!lJWf>=z$n+{&morY#x zBB-sf3$~|{2_mxPIb!@4nMX@SpU0VC%Fs-IR}+bptaRI*dJa}Q*3V&Y(&{>!2&0HA z#ulZ8;|Mqf$kZn){w4&HvYLRCdI01);WxRBE489m&jh$kQrO)wzk zN4%sP{7Tt9O;Rv8^~{=^H#!DsNm_C-`BN54ER`h&sY7b5$!oNtyR8rrKmPI4FECcQ zF89>p{vRIqEUqhEzD8V7_pF1CkVH>U900NBB- z#^wN#X}Uea8Xnh8XKU*Bm~%dyhN0LqYhNeyKlTlRa_cQehr%{vWJJDZ;@lbbjm*FO zfkre4>Z0~&>6(3G-8l#n#5I$}w%7x?%@{ZPWb9u=-ZG^rw zY=B&vLDsDn&%WC(MCV@)(v>=K6k0;7nTK4xpL&$NA1H9QXBE`nS?BwImnSighWys1 zQBKffB^Cgx&FR_z8cQ%UMT4J(0jZQ*1M^U?M=l%jYF{I6&+m$jGcx@7uOc)S{V{Wg z`2l(%AsdEtfu@-3QE9YRX+-bGdt2CJH<(>-5z{d1Fw54*!J*}N(T>ddRQ*Oj?7&O@ zb0W!npWa#(G>K?i#~wy-a&n&mr&^LIDr4M5<@y`X-k$(FwMbisPrvxUZljM@h#+@R zv3MmeuQ6du+6$)YymvZgz`5z@Gki77d5oeZ+xGwRA$q-U?3B z2@dso;m@Du8;R*~XYE2zOkd0+3cQacKitEc;-lfS~#@ZqCV zc`%&u&AsMxjXz3OWM_|kqeQ}qsyozT(rAOEiRm#6^$3rGa8v2QeJ+!Slfk83!A zU*Wv>ZJp!dJ2WYgVbbR|sU*%PZv)_+Rh1s@B0!h9+txhm$WkeVU2P7UU%{uJ0KB^% z=H7tcMJe7fF?S|JAlxRD9@rX=2$dSydEMuOs{a&N#&TQL_Joc|HKiLB${Z6|@o$$r z=8UQmL_2+${gq-aM3RcGAMSUrIYp&;bIezN`UMmAG*@CY6Zbfil^{jeA6ig6R1!Pf zZ+EAjxKTW6X8AvApuLk~qmPxsf$w)ku=r*pR@76HO40J!9XyQoIc?(8GEZ;6L7s#0@;bUG+Q)Y&~M z4_Y6wS`M>_fIGjuIZX$gjox*3X+J*PXI|`wVSN?xziHX}ET;3_lWa3lLph=Ei^}B5 zrM?PX;jJ6&&1cxxM95OBbmIrq#yhBpd+*hL8g&`R=vlBeGp_egsEJj18Qc+SV+tbH zCdB4cs^lE;HD4BdZ1|U>3;J7kU2n_#Gadz2@pV|qP%rOvJlyQFzNTbYaiQ^FJr!q) zqyb~oL^ZpB?v(x50hVBb|Gk|SUsdWweNyZymF%f%msf?O#{yJDOv(}0GP+8 zcV}aQ8?S`!&!;|wBXInRq%#>qWUY8?GEUwn_YoAn4`Lyhlm|Oy?*D33c}r`+B;Zfuo5AKayGG! z^F+|=B&KxVc-Ic+Ft(c*WG%}K=_dQ4;A`}iw?27HxCAXsRL+xo{GvG0_L5MOV^Z)R zb`z}G1+QZ4LNFU+@Y}+rR=uXUvFT>gZednAz)@g4iA^t7F+LjZ>Q6OJ=k5sPI%g_> z3t>FO7bBd%@@&nf3!ED;cSL0cJa?#)O+3NwyGur7;}Y9|c-hVyP%46f7|{kO2}kvv zBZwf3onm->pZ#zws*VD&^ekgT`6q5(2q6!G$h8>jTngowF8o>txf^bR47s;1`R(#m z2Ch+;ZVZy#=ibnRt1dM1#4vIn**_Y@{LZUluM~-kOJ8q*xJ-Y(KvJy{{L|b`>)T1( z;XlWU63>FI8@}M6#b@@chn?Go1Jos3fY|(EKA+;{xOoozd2LyG@%rlCs6jFB`t*MH zxi42mYkPOU*_ziL1*^BXl_SJ_$- zG70O=udV2B9L^_QY`}61WNz|)@O-z~1hbZNag$k!jC=fP*&a%@&ZH$1@Jtl(zvbUond%ge!y=U`P(V=3E&te&%jtPa zHScwsUuW~%h|_D@a(BiFbbdG|b91RZus7e2kkm!!-;&aPxv&pym>T{1Qn`fsVxQL? zg21}Ruxr=v;gXY^ujJ|UP|vh?^3 zm*dWQDK=@ez=XPlGNPYI&a0~ z7Y(&~a55!DYMbl~*=-q{v9Nf6nO(k~TG8PzuAS#}qAb*`)3WCz(%w0~B{K3W zZ8#cNYrWc`6$a4#KLB4rpuUAD0E`G1*1!KCg{vXbZ}1oyF>baD9z9)p4j3UlwLbOi z)myrE@8JLoICIH2w5|bHty;B~GtM|m8Z>Am|Mg$TxjtPav;n%vkjVJ}Kn6r+23BSk z#bO-Dn&dusuD^+If4Sy`M6t5BDJlZ20IvwX477MYM9+%kXc+g47aU|Ytg6Df$`}mu7D? z!QlZ17~rJfkecIZ4k`|`K~_GXWkcU^MsW^#L(e|gKl1=Ci*#jx%bd5U@7B0+QC}`= zT8Kl~qkB)e`l@T?EeJCnau;P zrcR~*%#1A1if`jj8=ytTJRptjXE?|qdPH;ypaKw>hdF>!V;s;mv*k7oSU6jxfU!^k z1IWO1eBR9qoH5S6}wr27o#9&e8VA5Xel!nrG3zqiu+6;UELdlwDpV_+=im`O|c0utl18YeMLQSA5){ z%fVL4h;&Vv76I4f6m$VCef#!xkuK^I_2u#_T1vx4C&|gpPECPVC+XLJpo?$~9X?V9 z4IY*PuR+qU-yrGTSFQh0>D7Oj^w#OV{RX-wh$BXjYQDh17RfVcLU`$=m%9j8Bi;Xr zC)Sm^b?Zy(*4OEAqm=O^vl%*cNEYD(l>dQbYo2I;W%F%l+Zv=9fHCCv^80c6NUTAG1bB#pmJeAB ztsfB)t($=kX9^wwSIXuqX!!;l7(8TPA~JtoW*O^7pfz{i%`%4sB+eGN;cS{`>isd` z^3CpDQh8ySE%%qr1J-oE^A+mm&s!)9ba?6ZryOLRzUN0WZ|==9{pL)x>xPXFx%154 zM`ZEe;tZ%uEq9Qm#{(FBi{@v_wKE`0uTdJXQr9wWKo`(VQ%m}PQJyWLWp%(W>oawn zrnCT82B?xFUN+x-@EB9jnmlci0#?d&e9APP2XswQNYQdd9rB@z1QZ=Qc9N5toGkSl zG?u0(pDN8;Tp(?4xJd>N87AX({h4~6Q>RVWeN0uTnI>Z=Op-BLuO{mFq$x9`aO^~d zr!g{Ip^M}hZQ9)6qQ^wf=)XmCLST!gg=d|0j*D_d{kf(nsEu@yE(0y>4uc8V1JK3)qkuRcL6BM?_JK&05%9Lijys>8qfX8Ppc-B>i#2P_m zsIrK7vHjoPOYJbIA{3x2u6K4w%VNM3St8^pH2L!lh8RX*_KxgmnFF{`DbN*d-%_Go z>A9uW%|KTv`%h9*o%4;C)Ss*|L5^8(lufHWc?jL z7l08pq2qWYxuChB!Ip16STSu)6B#nktaxN=wmR5ARs>$rG+7#>emESPC?b8Jh$I3D z3^5`(3@z$~EmCt$2X$E-uHps|IG6w)xOaLi|2`67vhk?tV3bq@OZR(Y=vk@Il`_AK zSUHKVuNliQjuj2(&e403vT+O7$yJ-b%E$@K$`FTK|0#S`DON%F$1lv->Lhb z=db6TFHQIS^Y`b+p)3wtc5Rm}U*`I=0bK0gFZ))$fiR15%~ZGtx~6;3)u0wYNU)DHAaRGQ%F+48aA>(`VAZ+J$m((&YioeQ((b?Y>cQ<|M7UAlDBx(YbyxlWp_&^1Eq=15n6{W_d9O_a`>7xJ5? z5bc^cS*A^zDpQN5$|QxsNfQ+|b^at>C*7H5hbDy;u38ISbY{cyQLbnc!U6Wd4A6?tGb>t`6amX&dO$z2h869| z1%y=yx_EO^lFACc@`WuE>nH7}tn3(66C$W(1zji!rsDIG#G76++mYA-2*6>*S&lo< zz9m7IIhrun{d$Wn6qa`Mz%p8whX3x@M37o{RkF7 zW%DxQShU>c(@c@yi1STzG@N$&WpPa@2Z`oIvdr=K0V@f%vcMsAA2SxgRvNI>3@F`i z;~FG@*R0uUdi`eUxdJD}Os{9=nnvT1aSX~0$4eb^mJVm>J;<^JSq6m7o4ZiPFItz5 zc6C^{KVAO(@@T&;0?8a@HtC!_^Wlr@WH*V$ zw$1mWSy`sb04t?-YgRgq5gT3tdN|+|cDkp^`*os^tz{s|1xA z=_&^$RmQTkd@A(O!q<_)7GnLReU+t^rWzhWEz3w(l6>&;%@--c$&^R-HO|GHSKoon zcA_K0p~SJoY}%YnGv{RDOyU6YmR}uDGaMfrGa$sAQ=B3kCv(CKyv%X3`Qyfpcfd7z z)L1DPJywPd9VwkUb(8a3T;iG*0$fD7j{C-m(y&1j>ECa#{uV%s-vb0hK*+bWqVH)% zWo${%-GBskjC9H3%XKKECVZsQ*<4`iuD*b@FL3P>W+hfQ>w3of`wx_0gEpl8aIX?lJc5afl*(4j-qFhqSf=y7#B zmHdKnAdBBPQ-ALa-FDg}oz~wvO@HeQ-RI1rDKcAuZuYe4E($hj5&$(pChKtWoR2j#tV$}&mvPlvM3nH0KHM$xoAr?~ex$xkK4PEj8wfMwcpSg1 zBU|hfU#`4=Qw>spuDD8YjR$b4rL$In0u2QYF1qiGyNvaHdc%l3n#h9iXYXm7`Hk}!j<$YJ8Gwk{usqo!b_ zHh9o*x$fE<Q(h24Dsy%!{BZ zT8D9iDvWs!UQ*jIjWbFFz}9gI0rd9+U-Sv0e;3ypGvG4lvT>JjF9EFL=0n3QwV8~k zfGdKY=y&8YplSxcIW-P!F`aE0=!%1v+lKA288qM2{V-JX0n3?N*PmBB+7&_AJSkkT zIvwq5zxHnZJyCh{%cT!pW~6DibDM!BoVP)jjhp$`(!ai|)~uGT+qcQW#fx0|u`+M4 zW#!(=dwhHvFs0Lzr%uspIl~<*0(QRVHrw56&JW<4s`I93d7-QTT9XtoCQnhYA)2J1 zLOH^y7xuEkAPk!_g~-!X88v#0bn4tyF1+Xx7ulkJ7qDee)u?eaG}vP3AS-2c)ao^8 zER7V}nl(FB&O7gXY1Qf)m(h?WzE-9k5T?&*f;%Ug81iz3x<00$Knhd!d*XzNGF8uS znr=H&ZK>Y7)$?Y{a=k7~bb6WAn-!DQiYCjl36o`o*0sgcX3D(jGh{Z`Sg*A>t1 zJ#O@j!0eg9G2Airc=qgIp1%(BxOY4Q`95A%QLTqAd=^r%mllB{`cz%|R`HuS-_m{) zzZ(b(%2KU`E*=J0J}SvM*3y?1?aD+7+(fZRSKQ%Ewv@B0K<1(v31D`(sDubxX-cXf zWo<_qzRm?-#{yf3ZR7ha4?7CgqzGzx{Bw=NReT%)T)+I~FJ=G!{jSdt&Z>b{9JX>9 z&aMFy)8=rR;Y8Zd3`Y=$jPLgh95~Q9J{*s2agO@;?_bPO8b3Y)uIT$*g)+8~>51xe zPF5#wob>A1U#_~cwF558T4>N!=fnnX8A$?gY{?!NIfl{Oc$`_^A;w7sj4Ub@ZBsn5 zW$PG7+4_J4>oL!^1GoS$<}u_LLIw@XeN)0bQ;+U&pO=(7G%4E^)=&p&QS(8X}^(j~HC(?(gkd|5h5MH%;j%gU3@BY}oHH}1oX znKGO6RiK)s+s@a0E?7Wj&{RZoUevd5zD`fqb!KasS)kW-mX=%kXib`;ur( zP>w0nlx3zfz!fF5p!~Tc8RI5MpT2$N`ZjIll1p1k^A;Dm=7jX|I;qJi&Mewx(J!oN z(^Fi3E}AG3*&*JNWE_yvUF2^MD2lN?i*?Aar*~=Z08S#Pds-jv8UHBbGljMSaR#g?gh?3<4 zTXEw$;NJx~)mrE}lI(@0Lst?wd6v^bJ}gCUog5Cfi=-WPAXieP13M!BI;momwH-;c z%a_5|vBH+ABBESaY2scc+_z%Jjdb_DdPPvn`=6^pR$Qcn=YzQb7tn)KZ=i((YmTJv z#4_I;OU$3ncJv~k@hx)7BGAC`q1lmrPsol*f0XO5zuskF1IloSfUJUoF*?Lyn&7gm z(YFXEvQO{+?jy*joqCouZlsQ)8chl5cVba4=Jo8^SI?1;BLg0@BByT>uw{|1$e{&> zd_cljZ{kGGd$Jp681-9;oLO7fmRVHG--dHF;EEyw%*Q4Bvnfpyivv6|iNN0j`wkb#(BhVT;#$(XM^zvT5azp>Nh#%HYbTZJxi(%z!HnT}*RrX;!#;?V5DcKet`# z_>_Hf>bb9+A9af%$xLouut08}zd)AEzgbqyQ=2_smaxvWDKc~FWSLIXN6QGqsR}G} zil)da1v5}qD!xE2{y2cF1}1Iz3d8UdF9n|_0`vCy=*HTJ9cuBtsz5b zGC0;jl|dHu8t7r@j~fI{!SwprbA|gxpR?(@-jazE}ZY@$69jn(^;d90`t-lIy*8I}UoHaPfIzq z21SX=6_vm##$k5OapYhZ--n)$ZhJW8B%8CGYnZo^DnxnMkw&}9T0FRt&Z|7^C{&Xo zsK@-zmA7aK|7a|_<(uiZzx}NoJb2JK_c$9C*>aAmIz>1uI7~QgNkC~XJQu_4it=mU^K%#yk)Aan* z`BmVWFmZ}>?$lk*JMRJqRdnhnvSq;4pnhXFq$$+ZSGQKDibNfAU4JPoa)xP2i8Bv` zC_K!F`d$G^7S+OtUI9>KWs9Oz)7(0M70WD=#d4sKp#dA)F%Rd|U@Q7P834sd3y+h` zwc=b#jCPd*UGZfZ=!$@rvs9Kw2U`w2blvGXp9CV)=BP1bItO$qTt&?X z8P{|5nj&V5`M@$!ty$9ej@Q!BF0Pe<7iAAKryg_BtrSf8z-3XdT+o#Zy!hBO{kZ5~ z=bHX0c(JZabfI;F`$yTvq31lP6By^my}NnA%`#u_-^xWx<)J+X_UxD0FCD z8aqyAXnC1JGKzw+GJo7uxpU=adGgK&<-x6YD4^+e(qjN!u5TK@Nsr+JR@^uz%9(p1 zpca9bmS0{96it@V1%)zX=t$|`e~9$#-B-GF?;#yKcXiDWyLRj0KBCMwy~qqYY}jyD zkE0hB8L*l>d6FKB=8sVXn|aYOqi2L0YPomW2=#pI9?_?9QqcsNQdl6%^x5$E(q;17 z9lPYGYu3s`x_pP$qb=hm%67Hg`Yd@wfAhQBw#%Dp`-upSE0l?aqh-7T6Dj1UxtAu< z@8!4{*MK4CY_R1+7iP~W*4wyoqrCUtd+s}hm91I_T>w{-e{eKbRhs7UfB9G-(l=g$ z*K$!ODylx{6|XufyGU2$5GOmiDa&$@Q($L1^c-K?Pv%%rGJ~R&BOHgU_%LrJRfh7g zqm6czl`1OAg&l=zQUvv=|G5HNe%7TN%@BOpqDdhUE`W=)Wi#e}x zXAZMTzv7x(!G0k*Ixwa z!cm-{PAQJyMHgQ#G=-{L57=txzQ=_{k0uGhi1c@c{HTz@7l2{Y24>7>eILebIph3R`@I~8pkI9Fs(#(e|KjJlA0c*O#7Qn^tbnEI6XyrFYrt3_@BIxqL z%YoGN2&OD5=9(nxew?M}W0~_YXdJpIJK7b&KKCLO-LkTnhN@_2W)Uiez?TnTn1PoM zT?_%OTQ_cS%?jDp_T!RX=&(pZWYow}?p{+jI4=W2#<_np_1a9)`#wv7{J?E@%I{x# zM}GU{t8)M9ZL)OS44G3fLFSGrl3V92mB(+tU*7)qOY+iz$K4_ zt!@I!fEV@d>8GEr649<&1zlwcTxI}IWr`Q)Wd&SjA>vhG(yLu{RMyayPoyhyZez{C z5~B_3@TMJVbG{X<6uwy1AS*u1TS*n6ysWaKT|BIk&ZoSrMAiHVD*s%cfBtzl%uB#l zydPf)%_@B8`okaoAdfuqh-=Q~zlFy^p@|I+ibcPoXi(I@i*bJ%2NGz*;liQ8a=lG9 zCkUr3a?m2sW86TEX`JPD?b=D5I(6iP6HbuEjZcy@&pcbMx~i32bIrAK@g7ik*;04$tZQih%5m^QPaVUbIM!!$Z$+)5;op_ zT)9h^uF|^owbHk5e?2Fz0YG3*e*^|L^v&i)@DYKC&EpsbS(sff%m9>ixIQ$i(2K?n4}~;%2~rrJ)N;op0$D{SM3ru4y`dn!?RAFEgWCCk0yoXau+(fH~-jfXlb! z<7UjRqdy&i-fXFJ_s<=4{pW#S>vVM7Xt|Xsj;-gSWonvEPbclV0u_K|z~!647nTdU zfUOm)R=VZ%t0D;o0E2P=xNl_Z;~rZX$1G~e{hdS~r}0`Z#*CE(6K2UHn-9qEpMG0@ z^~jIq-lf}R*{Er-sXjFkbyL6>|vh8;H`O3BOxYoPxELbGpS-3`{UWb@qxg2dg+5*tBE8a8N2Nj+PHox|F1g7S&S^2n*4sX(9cx7IamC2x`9ilY$lH!oPmp zuRH+#v(G+r?V(B9fI|;h8TjA`;l$xY#hrZvEt`)MNk@Mi0vsB)^+Cd%8TMz6A&w10 z*2N*hxxo=)eVjI&Q@$HDrl3$Ryzn9iT_>DS$9;gcQKOTjNfSEuD`Yi1N$TsoXc)oP ziFF#t@yFM72{f*|u8oUU#T`TtgPe8NIeHEkORrvi z)S)ZTZE!3jfM6Sg3Lgjz3T!GV{EnW-tb!t9#ZxPOhDO~Z(W z>OK|JoTc`iF`LJA%fOb+bLWuSC&R8QcBP|T?bhtm`I+tgZQS~pmT@eKOcjSN-+(h8 zx)`S~9T^L6UbHX*E}F)rj3#rGD~p&=pQu+D_l)|&y>@j$;eMh**Q7$VVPoay(KF>i zJ^x=n`kK7=%~#}^%@4{ecRemY`{oPs;QBjcVc|@fFtk9%4j(NA3R@#a442_*G||Nd z4I1Q*X?4ns^NGrR1V1)z(=pU;j9@LP;v&_h7(eEfr0F zL-WGgrld+xo>tM(u0K_9lnXlw)wl?1Y2v=bVT*^aKHUHP7k!XxIr;Y&zjT)Lc8^rZ zKls59+=pCo1}(ycgJ=#3PQMRXK6v?t6A299{NvotFwdoOmMO)leEXZ0wBm)&Lg5Ric}s7{rCAiyQM4<9tSEU#wmKS(XBiNeZrVMZAb)`Oz-MfvuIR zSGjeHCTsb1eVEizkb`j_Dd${gyY4hs1gTG-J`NHi$Qh?bv&AtouCPFg3P#Cd`gAQ@ zA%EDuLw>ntrF=`T@7|)xu20vd!f~=)>-9Ia-u-;lDtYhL_42(%^JID92pKzUu#8lg z8#;8D0_b3usSpSya>aRY9XJ=x!@!Cm=fOHm+r6=Ao^QOIs_Z6)K-WF@+*7lmD=EsA zHU*E*fhyIf(_+gSi~L351pRSjY+1}IBcoxi#2E%%pDi!G?D_LVK72D;{%;*VA6xEQ zElnp6cZ5V5wM|JCpggUjqg@pp<-+n+4UV9e*tC#ub|hW5e2jl+YF|CuK>qUBaq{8A zb>){2oFs1^Jk8k~2Tqk2_MYkN`*&O-Pws9dhi|`H9^Ky7+5KBO$pg1_mb*9flH1n} zl3i;D%9d55oGqCJcSL)WSFZJs;l==;#ZwH-Nr=g2*F@4cRmq@>U1Kd6VN8bs= z=>oFMardJtOaoA4MI1b6m~`vfQ!Y6FQiZNl73vzxamSsg;CGw@!2bOQx_xkNY~zEM znK}Nzf;BC)Bpo=zoR@)CbWNgbhO=i5IndRsS1-2>u*IA1V!);5APeBqWxxUB76Eh1 znV$kJ_LU7b9-I(;N>4{X6#X7AQpE3e&=mu(6j((dn*lAZOB`||i;}XWE!CXQ^`+w2 z^rzDE1-dL6#ztWSq)w0TN4;$5&LtJ;nmI>}p2)MYn+(+&q*PH9kJ-~rCuy(*PP91!*{;3s>E>P$iEsIA?lfxSx zkWZiZm3;Z^Z{_C)UXWc=R>_QhBW3)cp;DkwF+yQ$n8Ma@g{`4O1}Si1L!?``ZgSaW zmq~{X9rU+G*O+rLvwDz^<-0y**T$2M#kiI8sE+q`=SQRq04pc}iXtm47%3A+4wD5V zhRc&HSIQ?lx62zVm&&b!2g>YTy=8jeeloRhADP~*tK8DJue>mOu6(rlHhE>;8rd*j zujzmRGE8A>(7-|NQxklGqF=v$t{&O>*fWW9vHQTi@}Y}ibZ!M&cBZ?muAhAJN$LSy zwUqfE#Q(7!$<6QW1!30z%u+1trDA^nzxe-`xUXWCV}GUf<$6is#04B<(I11CFCR*d zg89ZVDpEB6OF9p%BJX?e=>^b51@PeNAb$n2$a9)01{=G{;HrL2}i zDJA$(?tD`7N-8_KURVd{s*Osj0Oe^wP(>;pO{oa0T!xXxWm#;JeCa>nTU=#{WQ;upbMxW(MHDk z!+=sC6o=28J?3}p*wH~3+a$r38Ow0)F&p>SH^+abiyCDteJxy5zsNY}$TDyv|LDZ%DF;2{YvI)`Rk^Z~aJK-u0NgeEZ|_yT{&^7jFNKtS*=-6Z#I8 z0)?w#LkBz18murfaNqzLFdza9B3;d!Hb2v7Bw=^ZaQuexq5g zc~KcJa?Sm&yz)wym6Y?NoR8Ld1*1pm_$V2p!?F6?7LFPzPcB;~A8p$zuPs?DJBN*s z#r+1z%?eZt2M>}}`n&H?Nd3v8rSieXE%JjED`crc=x7D8!TtMb{q5`Ej%(AVO&gcu z-kM!<9tMC0SUz+yQQGNh7oh4VD+UVtB)X&(Q zUf;3x<>n_j$HnABR|$QpvyKrpyU#i*z?aK=Hs$kw%|PX!I($i|-&D}zHvIctkym2t zCK<=5NRjL!={&Gfq3b_HT!8fpk$01pdzMFkHSW2)1?hVcyHB}*$-#Pl;O)eI@&PfF z0As#NYQ+?wE3T|c7Ci`dcyDELSJ)gXc5`?D#42`5xzcqf&gVSydiW$LsqmMl{i$LK zSXwyvN#{|XR?C%l+kO5)`%N(bWS!@l71G3zvZD6ykMDQJvM+zNRo;GLj68G4wJw5% z5z%^i-?`3!pr7B{K;FH-v5SEH_FHx2kKg`JXMcPAe`VjNa<&(@|8MEsxvM&CWHp@S zhQo%9lnxy_xo8%Bt%y3Edrk|vNMVcQ8h{xo+N1AbMc{>#Z9o$B4~ifQM;x-8}y7%ZKSG2rFnw@fn`!H-hqG>18m#_cl@#@rGpw1f2FC#~v6!1jHI6ngn zbM65bJ0^zX4FF~w(g?U1$1%kT#M#5?!}+`M#v2`U;mA9PnoBzW3~br&V%c1sjx6e* z$2^QCZImb1OjMW6n>){K69E^-b>MmsNs5~5MFvpm^b{=mtr=4=QK)eMC;EGiK z0FOT}vQ$K9nt}ikqEuulZUB!z4iIrIZ9ha6v(E*Xo~6HWk#yN`Z#vr5Y3X*iuHEP8 zenb!kY`H`r`kRT^xqFEz9Jyo8NI_Q`OxZSy$kCK`>C&an8Rxz+G&AVpUed&maqb1f zY5IGZA35|S!BA7UC>S2(@CYJ^^oDDxmtxnRUdd1C2u`FQ8;^4{9@ z^2Cfe@~v5OE$P-Hz$t&yD%Wt;dE^pqlN%rXerzmg@>(^Tb^zE&`y{Ghb z!(RHVxLD3Tx4Da!Q*Nnm(MQ#RtO&H?#yz56821oBTeWJH{QT!XciCQjl^JyTFE@|y zqrN3WR}`(tcCYe?V5BziqiD|Jeo{`5I!fru>-$v-BA=$368`n!())46jsKYysggjl zMCj7r`L_N(irC*3EQ>9V8UOD~QEAY{{f@W#ad7UJfnt`~zVvk?%RYyg(&ac(fUX4L zBqnC}NnOV6?25+ebDm>gH_6^7gV*?e2AL<(^w^lm|CmBj4S2x!M)-ovoM4 zQ@bvZ7xqTct)JX|vV*+04>pju?x`p59{m60gZux7{N}#@pFFzyf5{oApQ(;hKj#$V zKu1p9MAtN_M~|K^(M87&ofWovIj5>$zy7*xqywQS+7*2}D}tU((>a`PmXRJi+V2z@ zJ5KjIqCoog8zdb%c9nC_yTD~ctXsd4)UDf4PB^}v9QTbna^1CU-8Srp;{bXcJ9c*G z8GVy00u&rx01Jnm>ucAM>x&bbaZHJFMV(;Gv-xS)mb(?J3v`IE>*x-hnH*a=t>9=p+E<1Ma)aBcqZMkiWELj?T z3oJU%2u!kI2GDZAW%CtA(ne$_0*q*w0iwukT(7ULV@W1lhQFBkz-4Ch-4N4bus@EG zb&e@ptB(0ycik;}_ueVT9r~?Coy1_b|Fv(`5PbFAJ1LTF(d_5TG%Nmh)x*>dWMwHJ8cmWmn7XYI~Mk zC41&wCogRtAiud|s(f(!M0tOAk^Fr74Ed?rTRRuan>!ZC57sP{N9IkH&7;T2wBCJW zc#j^^Pp=E0MWl=7g*V;QPR=;vESGqvOP6l0{Lr+SkE;V#_Hx6Ico}r@jKNq&cGn;N z@P}mwS#j}lGY%ZFW^nvp*t&JA8~RFwE^~zO!D4=w^Q{h-06@k3Dtxmfe@c}Tq>d80 z{NG=aJu_0|tJF5ASRb!atRnk$l?0LoUH?{SjAt+WSE~Qo-=9_=tb~k>W_dK5OolGI zxA7nb(?Hna;`cJG_%?Cn@VSwlgDaE1@9&u|572caN?p_}=we>6i_1;-D``{^NJ@~s zUdEz(6`SwfnK*P6TUV`UN7A|EzQKt~D*WYTdA!Le7gcn$s}!Xl94Rqf9N=^OlSopr ze=@lrB*`$JV?Jd)*8`^n9T9Y?oFfqbr~Ta5-F)86+S^%PjFA2qhtVP-zC#HB;QZsv z`|B`d9?lm|$bbO@+*|6YQzyIaX{Lj-VrFlPd7F%b6D6|XZ8vF}$z}*}==21Ijqwa8 z%ji*KrDu=6a_Oa4NV8_AyAK@Ks~e?#zww6lQZx~VmhWCgPGAHsM3~0P=+PW2a&p_Z z?;tnaaFg)iR?@y()XQMNAd4aAz<0j*DD1={b(R%83dc^6K7IR3t81>8Q%*fo$cRXv zu{w1cI^b&5po#S8P9Li|`unH5W`h%~Kp0aNHRRknD$jl38uvzI}4JLHDjx9@O3!1ds_I3OWPHJM>#Q!y9i$_9&Kmb$*!Bn2(fkdt7-%%Cd? zzT&`Tu$8r3k8fay**P=Lc>`MyJ@hTP|IkCS@X(VoI~x`!6!;&)OXh;ni5xrdZPgBh0FkUGJO z38n$iPMx|)>(Sv_ST(-6pSo=LhoOmb+xu@Ch=q*8mxz@ISQY zK$+0LPzVzze-9fI;HkMBH5Ub(A@{9yO#&YswQp0kHHU6eLJaR2H{W$((?^5E7k^460x zqW(G9pQ2U-&Up4>IPw@T!t!Y9m8f{1CSG{5Z&j}U3(3%xidgs#ZT3ISlKXaL{XZ<> z|EW37PSJ4__m^Z@$4JTl?WNi8-c4=vk;q$lK#6auYg!@lTcgCypsOVPTLJ8&0m<9@ zmd7`{lA$YgFZ?o*<+r5P@$X%h9V2vQ$t$}l1?V~wr7mhQ=!#vz=%K-l&4#XGmE3oZ z*-r@$ZITllch)0ulS?Wzr6{TJmxonWl*?3+(XLWeynIl`qKX<{7Jp!rQm#-j2+JrL zx^g^N(*FdHO!-2Wy>-oc`)cjSdC;o^V9UPx>MQq=Pu|#C1j`3594Z_|hQI;q7$g7& zgHxUKfeOBV6GdK#fMh;28abh4AtY5c@HI{f3L^NTzY-9{JO^3|Q3a#bF&$nY-MaLW z%PzT6PCfN3X>!sj(nx`etb_np6r>Lvu4kA(T@UMzf0Gi(&GG!rSVD49CQJH zC!W|q{_E=}%4vFzV+zLWwVSQKVUqjU@{l1zb$XVIX3z(V{xw_+9CfZOL#{Q~(ykZR z)Icj5(#K@HyKaL9llpt8bnDtfF1X|pY1gTE%vnV2qV(gu`8LP`s_sdd zLDv5L`yF_>Wk8r49+3O)JtVi?woT6uXrADpcJgEe3j?l6DRc7-b|RoKvwIL(CYt5L zRxap@TO7dr@yN0xT!0pE1i%x?+PCi>{Y?)lXdTkudcWMWU!ha&z=8YJ7-9!y|J?@^ z!uH9I?Ys2a?U1!=Zk1(ASIL6;ixs+}q%Bdzi(^F12@O{GokSKFFJA1XDSLJ;Y~0Eu zO+?AgM;!vfFTVH^Y2N&NX{TkmZ@&TVgWG({VCbOXGHTE$SulBytemw-CMtjp>Df<) z=sNV#>ffio4C>imM)w{nizm&MWixM!u`F|9I{-*PPtUk6H9vHt}%$#^F7V$6*HsTlv;F`A)aN&jo#Das$Z z%z5_yCnftnrpVFF{uk&^`~O2@|NjylXT&x!zbfatp5nhdm%VbQ{^Lt+gL0*j&t+8& zx{{g~K6k3fyAP!jhx|h!^Qz+O_;ys#72W$Ra4N-baRChfKAOK|l?alvMc3!~Rq;1uLg`NF|+Dd00Nu`>ElX8%F4^vij*e^qj>qAG&Thh81MZ-N* z{Q0RehvLvxY+bcuji4SWbeYoAyk(93Q=t?1?%li7KxL5AOHYho<+A<4orZzLCM@b!UGRKb}=k_sY4j&CBB{tuZTB74~)G3}Vvu4f}Yo>;iJZX}G zjlvdDtyWiGCl{Q5i36ENjhec*^9>r10=`KUSvsz+oYL$xbsqa>Il_?xj3b$G`kB|O zS8qA<%(K+-JT>j$j!+OQ(scnUnw1rd8K+L~KjR-ih@2 z(8V$g$JIa!$i)B$B6R>Nebxr5Q{AusU_Gz)a=}HHN{3EeTtqGdT_k3h;l7PVKpEU;fb>yt>eZ#Y z^y}GM`suPhsbmm+wT$)F`8_*zlOCPAN;kbn^ZS~>l+v!#L7 zq5t}?<6WjtqOVc&LcOjjc)~bGev_RmMpjY#9nrK7xkstx?p~$Fv!s@W0`kVU5@Il>V#GvjnerS7{ zFuc7?8r4PSjBO{g#@rxFimsDo({7NB3);vAwT(Bol^sj2mQC|6l`V75l+{IzWy9p- zW!;4TlvRcQNA}J?PQJ7GEP3h9bL54+XUNmrPnI9u(O7=6uc^F!uzuS9`+?(}{r=(q z*G0=B82q2f|EDV0{`ORz{Gco4CuN+~jIUMP?_t|$IrmGq$^x*=|F`V_dubJOoK5~Q zQ_8unr;-50Ed4z$wGRg9Kg?7!yuU0;UO&kyvU%arLYLVupO4o0hk|9&a=uoQzX zhU)Jg#-DaKIP#I~UdR0_)^X*E`mLM0@=?M)jkb@K15>O#q|0jz`ZDFXxN0qQm6k{& zx@cMnONB1~!H~M~{*CdV%arSe#GPZdbvLrujn45f$yZ5*zpU+Oqg;Q|!f0>M%HknY zQPHlW75BCnFy|;&zWj2PxQ~pI%1in|mZgM$I(h0yn-`k=$d?)V```aAPd)XNbJG1N zmq7te5g>r0Ww3>jaA9oWSalA2yFLzVGbfdb9Do2A$d*RGi5qWh=lYOzP>5;YuCw$~ zr;zVlb?r(Yi+(bA;BXl-c!bXHC)ZtjgPeEXh0>(yX$mz>q;9>&?i*Y7apP|sS4Y0C zj$^&L4djX|TDmA1KxdJMY-ce7E|L^fHwNAs$||LUbL46TPNH4F zaW-^CfE!sRnq?M;C^MidU+}`>`^7B!6+zgvD8ry$cY`h>n1IF7CCgouYu{Z5{) zFs0Bpg=T{QN(7sfH|nL`V=I3)w6e%O29{`o3#1JnKEfq@Y1p8#Oa5}j6<4}`fJD21 z-F^yQy?Q8E_3G`0-McDa_2}W64R-6=O--k}_muv9`@3eRBS(yq;loBLoDWfe>mrw3 zc9lZb+3v+f^n&0-x$3H`9prG&7+QV741(<3{dtTtq@GRYKBSiW=5OZ%R|8p^GhKS(|o6&rb zh=dvaZ!!AinkDrC(*NUs`{bn@(3R~JXZ{~W|AUHhIj!mcd-lI7*Z-^>|2I+0pGqs~ z|7fmteI@<&Ec*|UKc-Um8>qZ=TPo_6XEF^Ss3KL8-;@t@J*CT>blt?|DWj~FqAZBw zUZephy2reb_JJoO-(Qc)Q%Nx7#QnB%m8*=n`5fD8QkXucNF^O7Kv!I;ix*uqz3_49 zN>$1dp-Yu^bUo)dtMH^O`$lCyB$C#5=M)WBuT*pbrJz6 zB3OVH8Sv&PB+Q*nv`U>Xb&3H7wwpC8di&45a9D6=PCxxjmqz`hlbTA?rl(4?lTVkE z6{wn>d`5cwj5E%ai!QuEF2C$*IqlT5)d6iPbriND;EMW9op54(sZ*zcI%220zFk1n zm@$QV&d~>&IcFR_KBPKf0!<-FWDq%wG&#hPqFL29zHx$UqS&y($*#HLNiJf=aT@7y z>N~IlsvKB(kQJY9(6Fi0t4FGMpsTLJ$+<3ahC@hSF(PX&p@^Or*M@6^vuZGl^U5%~ zZc)=hze%AV?V@iQsp@g0`=}G%Sz+kX%dV6QF1%FwsAEo~D}t_>F3TRnEw|k!_t8J= z(0y{x!2=G!XjXXe-g}+hcZg+&(kSNYg?b*qd(bAocayUv%MRGHz^< zWI>lY$x;8T;;@DJ&=dzOgD&54t(#==V@2>4!Jj$tL>T!zz^%7za?oXwF5n7d{EoeM z%dVY!Wykj2vU$@s*PL+qvejD77b;{B&O z1RA6Mlu^W~G_&8q@1orLzbnbI;VPH09{b^1ksY*9q4O$N*XuTDBK7s$8#g&sPCn&K zm$>F~y)Ip7GN~XnYE+?&*WV3z6^<*?Ixt1+NP)uH5b4>gpWM{0lU&iVl|ow-nLeq> zDbhrrKMVmbBIm~)cY=$2+h-)W9>5imNT4_lTr>-%9@6v^;2Jn^uxqwVA3*$^&p&q` zO)4J&asZeg8Np#sB}gc>d7%^kA2a{kA|Uhr*EyyBN2MJdf1Bw4tM5xi>u38@X{G<~ zWsBox??aVi-7LkELdDG>#nQ#w{NKD9&HtAU{rO3TA5@Xzo+h0KmJf9O=+0=JfB!If zIYybuqaR@g$WiuvjeO+d_c@xMU8Zawu6!l>HIyT7U!ISZR;oM{D=TT=Es}q{%9LK^ zs-vTVE{1tRS6T@-F4ql-LswcQRebiJr(>K}QUxeWJCZ2ZpK`!f+>QmlDk9pIhcXWj zuiW_eHeGRZl&jdfM_sP$II(h-v;5_ue4xvK%EWYh9wN&1%rnop&i_7i0S5MF8+ZZ) z=FOQa3+Byt!#T5N%N&IZzzbtKf(Np>DV(L8$(Ajzl%`FZNn?c+GNv&k2}YxaK#u~9 z0u|FhR+E!Xb-;B>vom!bk);T9A|Pt)`lDQaSxf2Bv$s0b6ZL%Os*_8zJ(?!+ogv`_`y3UhEc=D{gdfdhc&w(&Qbj&^}$l3vge^T+PqsE zmtl=coXBrQnh&3sfDn935ozq2c!D_H-0%EvOj@V$Pv0bH1(I*YCcUyBo6mZqDM;zN+_O0!=8PB&S0g(+J5m;2`5G?iBo2kf5WTAHuRo0D>j$o%*20O z&`Wd4x$CdlFxWs{>)&d zKV=q^HQwm-!6>>rAzi&eS zzCB_(9NFm`^Xj^jx&bUhIv-~F$+dXtnqJ~GNh*uy{KKQf5&p_{6&UkR9b5apnseLm zZk&u`aRR;;m-i&_yF2@~Wx+Q{RHS|GG2Zp%q;cqL{oD7O$S>>BQxMPBG54wApJ1O- zlofux54A|~pfxNV-vYW#BCK2==Cy(f+XjvTTmuQR+rf#ifETM$pI?FQO`Z4ABL${^ zGNSt$CHi8kuU$P7d!jy=d(32@C=Cw?}!u~ zP?4>8S!=z1fBey-usby2wXD%AvL?Y=4e1)P=7Qkr?-8C`d5*iU16&I3U`T84Q<*pq z%9CNe^D$NjnfP_0pu&qdp|8U-2tXwSBZ$-M0+bnBRc%LLcn&4nDkGmx{vhn<1Qx$p zmSGU6Q=CGUB3H2wPVpK?&CoO|40hp1j9U zFz%xiq%~bwO1-Le|J9W~<$$Abkcd^21RLDF-(#}=gWfgc3lWnzDfO&ha%;Ucg<;!w z(u#^C9*_7tf@VH@Md0;k5E?GG_FLS5b25P){E`tN8(sG^Bvj$YRuHFrV58D7Nd;^B^tCYe^oc# zw)85uM(Wes0&GLb`q6SY3iES{{|ei*!sT>RWPUmyU}KSMM1wgFM7qV0;3cW=q3Uf_KX(OUBRC9WNH z3=6M%+Ri^J49)gq43hS&x8wey$B7W@PJbgk{B6E##d2>F8t!4g($_PrF5;Oqi)e@k z8JqDUEW8S+24313mBb=FEDVYgGzHz`8CQqtL+(P+&8Q_XUra#U5UfH(cG)9e-|GYh zDWuP3`z)lL#%yS~@>1HvaZR7+@pYqJ!=59;;E%f-0h+{1j z;a00gmXa|XRW79YMY_-b$xmr(;Qxs!>sId`lW`{nYV@XLwv#nO9N-t~0T->V{#>7IEJGD}HTWU( z&4P|I6DX~cZ1WXcFcRWq_9Q-)Wm-a7qz8}WD2~WX>l^4B2t4SQ+h!pnEiTn<_Mvk$ zEa&WGplhn+^JQ~utWi+%!?9Wrw@&GJC`lC2M&@eEKhlSskw?1Chn(S)F^;o;qh9&- z|8{Ku1&(y^dIc0ckepYCy6gp*mVNM$bjaGFuu0I^G-ex%&`blc?5ZJEfxANYuqeJe z2Ue&1t`!RJ`fvC#fy2EYMqXTH`@TvJzIIxZzP%z#8_RyG%Z{a9gj~0mX^l%5mj7%4 zkL~B>#o5!V5(n0*(e+fpTG*{iioC+vi((ou_gMA4ubPelzc1NQN+>Newn=-s6Sw^|}j8Msmknf}>pZl;TW< z?B4>YdgwbDCpEK?fQT%b-7~wVu0KW1vsAHYf?$d*(?7GNbn-Z7MqIa}*{AZ*DKwA- zB1^ww>0J^tT8cwsUZL~FOj9}*_9jxduf7!Dbt{fd5P&31@0VkG120+Ach|L6{T%kh zS{dc?QYjb+e8_%;3Sl2t>C;Hw(ov_5E!s)%v%ATz2Q6sV9)n8*j)&W+^|U z`_c3xJ}gwHVe;S92v&8XR*Uoh&J)A_NH&q~@zQNrVZai_6G zGoAg5u%=}Nj%6098BtJF9wlN3ZDhaJWuo!(ZiV?n*yQ=9EqG?epshFoPTS)#zHujZQb0i#NfB^Y91*Zr?^~jfVY* zEURsb#X#D3WlwBuWc3n$T95;8Ilr~?_5w3+cB)ow8)jlhcBZsb9VejDo(s(Df6u6a zUWDGblnf;PHlz8zr&BUCdPXrQnQyXBFFuFS?vZ{|<&gI^FOgKIxeS9=jk!0rBo zt=JOJzUNs*b?;M4SNdRT`r-g7SMpmxJE&vy)+T+~O)WmmiN1B%dHSm>1Zw$Tm;7bKA{ zbVFyn=!&4k@R)+`w^UbO-)-AsTOrkxp6m*C`N9|`k<0!9K5Ll%2shz}U{h#(pR9Lih-~23JkK#8aaM4|Vl2%^{ zs`}-CnyKodAH{SK2H?sxTj}~vn`NBU$tea6`rY3F#T$2ZixS|h#Lj%q0P@TrnM{ZcX zS#eK!m2>6u3EfzU&MN9^o5b6A(pm;wwS+VuTmv+UQBzcj#q+;%K^5t(l{^w>(Pz{O zlcceQTxi)nF$De_OWdFAyOuXkpcSf!$dZXIaltrtP%BZB>n5?j+#TkYH2q^^rCj^&pe z*uFhI4{N>w(jIOu00NR#J`6u47!#+ZxYyc=#VHU-!b2}+O*YrUyI263LdyNau|;uq z4H;)Ho<(`TJVpGkioqWk193dD2VxniFw%yApT<{xFMs{5YvIo~WxeP8=l5pv_o54@ zZ7Wx2z*5B0THK8G+6oYke!Ep&IBbxjKa-4Mjrq&V^FT$hF2UnGo(D&(Z+i#xY=HLd zmH<95mH31DuXMT;aCZoY{zi|^7o-e#`zp?~F+| zENFogi(5*`gOJ#IBGdJ;UCf8a9b!DjnLHQLJO(W7b?iky#F>0Z7j(#%bxRc2veG78 zv8G7N55&`4%Xj9ut{>EYVuWjj|3P<-F+TivS}?^kR*lbob(y}-c!(u@9FKJKE{C8v z3^I*fOe+3vn zyqtWY`a5P*w@MEFhw81SJ>}}YP}QEOh&iFksu_@bis_f0KK?J`Z#t@`E?)ZhUr3W; z@^E3BNi%PORDteQFeU1?+h(93hj?#MIp)kx<{Cj!PKGG*pIV3RH^Vk`OYQQpTWh`lvqd5bQ?dxm7qd zYXd+g(+|#_ssm8hDr`wx{gnrYS*zVRono^>&$>s}#%D{s0l+gml7tn&CyDK6JMFlj zj#otB9L^*<@+p{d%niG9rS+x(eR@?!MK*NIWp-LJn4CDqpCQxxQ%?+0c2kKTk_F(B z%CO#||GID!7j%3}=;Y&l&v!o!`sY(JpcHEQl*^b_zrV0MN3<>@gk&}YNG|eK*JEiG z0X<AylCauFds1CyeOD{U%wS|#! zate-Cw>GXL*vNUcw3T?ez)5LcM9BKOKIh@Rex>nNx|mTRER#8tmL5&{HKw>$5?+Bf zojjshExgGuC0(&i#a1>DC*9TzJY)k8jys^f8l{hp4z$bi&d&7LcNg0^AfL>?QRI;e zsaGR!N)sSmou|Fo$MdFEF&3@ zm35Rcz2zsfe~VgVM~l_V9YWJ@`^!Ju8C?K7gq)7l5M zoOT=OW_6Z+WArD=Ed|}UfbBz4unwzg7v+?75XSb?j+KpwO>_%eT;9jd`-i)2_**Cb zexFv}Xg3L&Fon$9%e@_G2{)ZKLNM||1b2m&DIVX5K(!q`dgAJ^qJGT%ES)pgtPqlP zehq{PAwz0_0&nxu=Bjrj_a)}3O5w+OT=dO6dGxAa9=T_Z07hbpz$lej8ki)t`Q0rN z!GKmEH=rxEyNV_l*Mr|CicdWoLohX!krH6s4`Z}nt2a`&X#O9$APd)ja=~Q9MgQEW zicrxg(Qr}yZTe55bO15J8o;mj`$a!}*^70y)0Q+prTyH_ssXZ-_%9&iaR5f*-9Gx4la3lFf2w^(Hsv$VA2zYkk<6_0+OpHDT%i#_e`UWjm?VG`ZrwmIKRB2?fCR4M~WzA+nMl9{&DIxx0d=E_xj% zAlsZ%vm`tRW1SXlrut)!?u>yLyPAba03M=BJ%eg9(>)R_lz5h&bA0sRXq>WyXET_wv3clkH<>^N8GfLv~I+d=@ygSAkMOArf zyzX8o)8m9*8mAW#Oh1&li}%QeKf%>max-HLB@I$s#qzMBXQz0x^|iS0!e8JGtWjz^ z{|!lhX@PoE&(!8uJRUHicny}l5i{yt2d!3JbcU%6FQc4b=>ZZH6iun_*|k@93O^a@ zPOgiQ+2?2@TzU=MvXTw~^blc3oJsRCE088l0+@Qtw`v`XK9TZc9qCdTkBPDrE5F`d z#HWASJ7RmCc>%d9QjCf!y78tEleo&nTT;U{*U$78=jDW_p20iDJASns)Nx*9H_xts z6Yn|~a(m>F{+O2Q-Fh#c&fi{|TBh6UuYEh=*G=`x5HVSBGGr4uY*!a|K{6vLc$4yU zN(Nt=nTtACfXGFQEu%rS8F&XjkEwS4oGjfG-M;0|K`D6DXu^be8E(&uEUc17YfYMI zC#(E%9HvrK4lj60M`muR^IWL6njolIT>C?hj-#q$GBm}_=m)+h?Od-M`rV1%U^h6b zBt=Ec=DrO9az~@G6j$*!XFFrbzQ+>uME++1H-G_^o9^GEynkoHdnUk#f@k>pV$qD{ zCGyQ{iQi-t#MM@Nv>2{>9@zb_|8r74Rp$HkHA$EFe`HY`bThv{XL;eYV0f;WbthB5 zC?N$UZtyb!6wF3GQ2KB0Ew(BCp}JUDJ?40WlY0SX1TZRfUkPqq3-bgbzZ84(9nI$` z3E410no_ua{K!v@>1aS{p;s@eM5+e})>gkb`v^aLynZC(K$M8Hx&K{V+jnhNQ+_t- zFR?!!{3y6Ha!SLU81JN)t;fW~@X=$I*L@R!LY}+v@nZ zbi?xrg1R-aUUV|q3ib76LuCAX*s9&IMqD=T7rG<^j}EcLPX9K6bpQ44YE$UD>J2W6 z7^XAo=Wn}`IIBNzb?OOvw*Rh`d;aj*b|kZk@bOb)k+C#+3+s2$lmfCP*X}ltJ=Vho zNJ575K0N|;;WBl}3Q_S@rNe?9;l=|9^i;w_^kwJC<_~msm@`I2&t@e^|NIL6O@n z!GLJ?FrcZ;9}@I8>V!TX1;-X0o~1PX_OfcYs&?akk=>J6XDJXWF(B-xrXc1O^wX zG)^L3@0l2=V*lJ6#4xh?b3^k?^E9J{Q13=WujaE5aPY}Zcx`QDtXWjXm5TyA3Mp;J zor_|{o$};jW?J=(x8B5hV5PDzkoHJ+bfXc0)jHkNLU73k3OIAW^qiMq<~nsLgM65H z_*3_XBvake43LsYHc_TH+Ha0cCy^Z?b(KOs|MVl5@7burUrhg)XY<6es=^bM66Mmn zPbRcGK^`Z41}cfHC9QGvn5MHLVaK;?)?@?kP(^Q}TvYO0rC3jrkqqBsciJyM&kP=5z4R;xNx3C<}U0gfwzBAZ# zNc;yZwUhWn3ATHL^tCx&mI!ruJ+X8IC>9~S*z7WDDO`~52D>p@=owtXX0g|u1f4V0 z>HbmHt4r7=_K51rb*ebVxy5Oba31QO`WxZde2`+|>^ACC+N)p}X>Z&GkXG)7V3@bm zFU+uj?_ipOu~xy{ckf5iwQcv?C%C=Trf&!(HDmp2-n8WMy!wJJWg0RVL~ky;`|wgk zzyF1eHdUVNj2@!R_Tn@2vUXq-FlHnPWCs}YJPyTeeJ`O)O+g`45Rn_!_HXx1^qIoi z7`FH0e^cC{7m8}|?PC08mnc1pqB<)`r9Z&IjLmNyZXZ-?vuVnvL83m zkBf%SWJyd-dxdh-wM00gn;^*!?2QNg((5n~S1V)6eOKj)US0R+B`$-28(D8()x_;} z)IYo#^PqQC?8KUKb>GVfP27kZ8QocSa?UfZJFLwrJ`=aS&i$V*?@J#S2sq5ppaAI= z`G2|{c&*6pyYJxI=l~@xpG$Tat$h0A{P+vGIZ?`+T>}MS0ryS*Smcu(*?B5k>Nj;~ zC$p~%F}?+HAADChA?N_E5oD#VdiZ2O|6dnJ1Ttou#GlIW}=jVN{? zp2L{+E?otv4l1?O!=2YUL4CEZJOBrOo0R<2sd8`#vq5R2rj#k%Doj8a{6~dj`lhhV z0_q2i`h1A&SnQcS+}D)}eAD&RU}-sUQx^yAB_Y&hWJ8)*alYnbqWg$%=@il^>#tV9 zfCAzjjZH4-Y+D_EveWx@>n()EI}fhNd7 zg2`-kGH`kmUo~#CO@6OAzScW=8I0Y*ub; zJupzbA6Z)iDO(~!5*nn>PUEDt9w6|6#$J+YHqvk!-X@VUM^v@=m-~klsee>Dg<^IKVOrr|Ai2{Hf~&tP zN}t=t=82h#z7>5VOQ^v{%tmj&9X;(*-TnuzfHT@|PIf(xxQ3xScKd@sYmY^7C;#%#4kP8eo!@Keh~ z_nlU5;|7&xi|WPdREeXxf*{YRg9WI3-sfg6i_U2lYNNbfGl^!@#Wbi$v(e^E2@15o z>wIS3r9K1iP4*FDx5%K040Q9E)!W8IrMNk@&~A{G1@T%&ZO2%pRU@47)dl!M3k4H%!t+{UYY2 z4nsX03wTC1Wb-NVbb(S$A5O2f5(c`MN~+A6)SbPi6k#M7b z5Dh6aE_WK4Cl7q|zzvZT;8wd`WLYh^#OzzL4)=|VY~S>|{Eaz_HBXsqoj5*6G_Pzc zcdf@)ih6vMrPxuk1}t(BU-;r6hzcX_t0nj5ltzgL$;1C%^=jFHfP4(F9u;Rdkd*)) zVS4(V5Bq<1G7i38$jL>$)2R%t`k_+rHCgxOe+S`#)3F);mw-q~2BIMakHzF7YJZc- zkRpc0sXdja7FxB6>4$Enb!*>^zrpR_Amz~J1?T zRvqAcmVl}PZFB}J1{MQ1#HkZdA&_z7G;B=ataj#36E5Wg5n>8!z)EDggjXlBSS21TLyf{PDDrV|0a2U-b$ZF8u zT=IDV^Z0)zo2$VOJn2|p4m-_)wR-RknMyGqV$d+s=h2z0H|qU)EjmrBaVCb6m@4Fh z%7bjPerhC=f$<4>V~^%^pU7o>6v^gaEq85C$NAWupjd`q=9ngPX!63N_QMPBimnUt z`3|qR5RL$*8hm@8)F4@Ng!v`|j?FVNdo?hCYK-Md$CeIymfO28j*8O| zD#dEBuM_#4gfX*5s=6M19DuV2Ce?l>;JZhopLglS zPxpgiSH7Rd-TlsG96KMdQhs%W@ffGPjqyPb`DTQH#Ql zp4j@^yJQQs(O)XVq%fo1}hKAnkpM# zK;1OxOTsjpK%NEyw50oLSCY}>QQ4ZHHNy2_Cy=IkQJCZfo8gq)a`Y7MlY!`6eUHvG zcWY7qeh;rKv@BpwJ;Vdq-0Q`1bV7nN9P>El!(tp3U161ASnI{m1#6FfwfW)g)pc%P z`=I__9htMrAH1EVRnC2xhIvKR3L=_VUqN*lmb#62DR9_GR+NB@R&``Ls^3-<_gV>Dnca)YAYP`5rOCK zsQm!aY|}p@m~0`u+Y-OPS8{Jd+&Qq?e+~qcppGp{5sn+hF@(%+4L4F~JrcgJ#O~mgE_eP{`}=WaSO`l^Rr2u+-{loAL`$6w-gI zQwQF1xs>sX%XTE3o2!$0gVqSz2w6vgKLkBHVi-uv-SWTw@sZzp+>){g;MuZz8;~Z!GY2$-_04*hXFmc)qg(Jdur@++2NIdR0I-%yHbw zO(A_(Xxi>qyY$93>0E1dUnIBd{BY&N?fKzGg~72o_^=T%j74EePb1#&Ar;Un!IQlo zTR1^UY17X)M6S2TnpMa*nmW38VE8TIw+8J-3}fs;cz+qavCj;{i_3x}$3nSHgrO9) zvWS8>X)ZdyznxNUI{J^e<9e}-#>vwq`zqYlWEHiOZ6^P}TW|jV%nVM(E@puJF1#~1 zA*75{;pXq3=T_PE`P2N6*wK%t2$3_I4%4v25cv>+C$8w|1dpB9GNO5+CCrQw)Y`shE*fQGCEL4T z?h$n1U9d(~lGT;{h1&>BO_z+FNcXE(|-Fs^WTHr=J2uf>&mXX2-B-2 z0r13CAicVUk5PKZLz7_OgPudDSE{MBcYXt%psdg3;h}6)#aE>7<&PsNpH`R7EVuqW z@JSy9v@=0c{)^|Fm^RN#@bT#67K@F3RYmj`zriw~-KE=Unf)NJoH-r@Tm8O6qRz<2 zXfBv&O}WCb0Y&qeFd+KUdDz5Vm9~aSM4jNZ;&1SHGZt8!-K6^3_a)xAo<{zPz7blg z5nA;tj*fagW%Sn9hN@&8fRlRi0u_ok(-p~8qq}ECv?egUu zK6u-9_C`!8kkDkll8viy3Zf{T7?Y?D6?F3X9t9Trs~weFUMlx;f@}31uyWwU;1DPFDz6jLotf`L9({9!5P_qL7XA(oldI$bC;T(y873cnn!0Qm3+Dny0AivsYMRA ziS^XB`soM~XL`wS4-M!3mu=!RD;SWq0 zO`rO}I41R~$PfBM&@<{c8acE@tCz?*!8bC_uzyIa1ONt{3NaTRIrwBKJ zi7k0v-F9F!8@hf%@)MJw+5HeJIgn^w_VbkO{G#Gw z9bwH|=#F%4^sN`9yu8RIXPN&U>UT|Eh|OTl+ezO)noxc8+j}9-qAmBa;ZWWVX7$UX zc)$bk15ckP^(>V){_I?GY!c)-x$QK$Svyd4Gq#*?mVKQqXaNQ?o?mi3(3@JXepDf+ zRSuUsN*X%Wl*Dc}ivb!%iSpn49ha@IXZ3k$=t(Zvnk?J`1@|BIx7XvjSI~H>V%}1W zvE90&n=((-+;mfp>RufnIZa3#BFd_a>y3q7=DB>2=a|9?k!--qD_uIL>%EjyB57{9 zaRh5{5e6bK;{NZac)C)l>WxU$A1*Jt-mlG;AOShxM+r3BveAkJj=i|nKuHP|Py2NrXpr;ww{Jew)Q2Yo$T(|o@ z_xoMz@5=g12|-npZ9pvRU(cGSz)8tJDvF5TW$EhKPeT$#7uTkp>~_{jnzQlEqT5Hh zYOe%6o3#sA6n5I2RO3yS_6Lr>FWE!F@qfIP$5GvhXWHZsy;LKmH}1Gh&-~Z@0KPp) z1F!9_fkWly^?I@2ahe@Z28V2&YlTkkri@PBE6c=3Sp@1CJ9eq_OdT#>?J}6PLgI4O zDwW5iCvO)}g&%vvjOjAoH9I34q)#y{^HZ4UrEj?d0HJ~L3*8vEd73E9)L?S?;)g-~ zcCkDHf);yy6a(H{g5>upyjUx&|L&#)A;8<_aUIbyw{>I^PlzJ$e=D1=q0qIx99z4y1g|l-J zer#HviK>-Zux?3Rf%w&g2$=Fb$g>{!^1>6*mWY5Vpz;Bhg+l(v}0NE zue)>7?k^hDVOj+mfHdAaUz!3Vb>h^{wxYI9iF*qlx&tPmfdKW$Ah^un!`@O!jw#Y5 zHEWwVa41fwQr_@o-sQ+~bJRtkpAhxs^7)DvGyL7ogs;#k>;oj06vA z8f(7M9|Qf$w(@|x?bh*kkLL~#FYjs)lvl_l3H!p_%=qHM}A0DZZ@*0v&^4f6Ja#~Uw)Rn+gg=Kdru(AD3b z^PMb(DrRgEmckFV$xh#~{me^rjSh?jnYmrW{vKOJqBTSLM=0LW(|Np*VGC8V_WxeL z5H1%NmBN$6oO^{q?Qr>6`4IPQiDftCrEvCb0VjaSwFqCC9m$lXX7csLcXT7fXVYL$ zz~gPveLVhm^8u@RqYxl45O(fo8d_9lQzb+`FPNvtHk|))^C&oq8;9^_6B0A3YP%HQ zDNM&y6JW^XlMtbn48ku#Fq&9D{gVyE9Ln#jnUdRZOz;uKxu9eWitTEP1WLy>YZGQz zoc#^z@hIM>&bCi-r-Ik`8#hEg^AZb>yetGjMuXBp+7!VCf`S5ne-m%fy2iE8x?O*w zi3WX=A67}&0KvJn(n4^EhJo5MQmFUjN&9T236lg_)nJ&2&$$ZLJOS=YJdX}DT*|1K zJ(`M|`gbr!I)d#DxK|tanTH!Zvs`S=lh8B3^LRVp4Q zJGa@8c15>(yk$vKY^|8L^i%*D&9lJ?3fL$=LfINd_3ILvD+?pSwzarMD2f?ws<5rwBFG|eR`Fka&LDR z;ATaj=4@QfkRqU-|KDR02xh^@eT)$oGYx|R^mASRWVub!RzBK}Z>35^eM-|(!ml#y z7qxkz`DrQ6@n%CZkn4A-(YL5?lxPNH*-}WKgH({Ba6j~Hdl=ZciT_RKcPfi2(@5tx z+J@(_mFrh~^3q(l2ul+U3G$EYU5-8r8P-yOp6(AolAl(p{Cltp{Wbk>GtR?&y_L`E z-`lOS|4p+CasPWlmWt2XG6z1M0Tny2GcJI6NaP z^=K`mRS};nwd_DnuTi;*rR$5E{2*=Hnyp>~>eiYMU3V6BZWp>nU+TZk-uL;yMI=^% zRkVxN1kvZ#M_tiM0hLyD7tV-s>ox3hv=tim7NxF zl_@VjRB@%fRedm_#dh@Fe5aF|;F88=_b9*1GBvkv8|iQpNNhWOr7Xy;{%%xobe-1K z%-*xVV;yrLx{<|_IIcSiFd_feZ&^WZI}R-)X>{UEt~P^8nB9twv}g= zA)yM;-km^N?RNt+HSQSFAh`IMBhVcM6`F+;PHN>!G_sVM)I0K>yW>d}(hE0Ox?Y2?$pYxjGR8{3*VO2-q)TJLBoQ_3$|(gY3oO(W~- zxad3}?ZHklT9}!xIXVc?UsVxN5c8c{*4z}0Ha5ZC*q3dopO=#(?9EFUytO3^RQtH*dn1^bT zE%H%cR34a^q-HpO=1nyPr#0BS1%qh6T#D@si|u5W%*qXzw77uz{=miCpqcK=H~)b~ zHce@=ea-Qpr)By_hqo~zjfrdfL6nxOU)CawHgO7wNGHfLSs8_*WgrHro2M2-m(2tJ zQXS3Ac7s4inK%5tgdEFuyDpeb5%v=$Jc*=z0nG$_bag*nu7PRa8#f#FFGM;~wHr>@@fU`y%sI6r*!GHUu5 zi^&Z|Z^k_K(|#>nu-;`xTcf_GkKzwEh05T+Nw!JKhe1#D;8wDW4fR zz!kZ9tCj86KmR{~(xN9#VaMt0IMwhyG-FQi->#vv2U*gKjOa@0gOJlWtJ>@M|BOk?`CS{5E94j zOmR||KP68GndH(xXNppjQ@>iNJ^kc5AAo~z$PE5d zm@@&vQoVFRr|r5Qw1ILo4u0A?dxfjmt|vWqx#cb^k4No5vik7;@am=GO}9|A{p{cO z%&^?3kCOQ|*qdk65ttN!3|m@%*Ev+}_WCrm%E}3ycr#Lg;@Q{|m#?koeo80Dso&>iULCsi zQIR}sR|;Kc+;K8pzISCyHV$u-%dBp8Zh;vdl!$3+^J;PBu?h6)>HW|8ukN<+Od_@D zyRhCUtFJdd`b5u0pmv#%d2BoE9qQdr3to>*OzSU#wUQ<(#>FDeA9jCfP|q4=y+u0+ zqgn(A#92ih#ydR7CGr2VGEE{&g=Z2_X-2fcnvcCmH!)sI!W{y(C~r>BU!0ndXaYxM}`{NOhW`9PwIH`J)gd5$311W$ac{oGQH7s=$9x;rD0U z-1#bK6vCg*Rd!t09pPyr2L0;e7ZB=khBJD?9set2c`s&F+-z`&7s@r~E{qs<)NvI= zMJrk(Bh?8)Xi(4;P$GaV6|#d)B=$He#_KBn;}dh@Ckx&SV%mUj@w@bM8pYu<9M`nU zIkUo5MT;s$p08qdgptZB`Ful2rre~Jy;Kt_uPb(lx?|>@gDXbG8=~vo@w|d^o%W^G zThF~Eq|Gy_#};wm^kG%1)-(e zs_OKU_5HOf|Chn1SfxitHY$LTY-orrCuNxV-KUH}`%AUJDmC6Vxjg$q+8o;o66$Vr z2(}^M4mP50qIN~s=U6?>gE5-?92M9-%^*3YUNtclgs{3{qZZwx{ijG1FM`a|?=^Dx z(|#xs>yA@{XrYT_0Lr1-@W_I z8d2abtrEa_`yoDX1@#9u5=m>TKi%!%B4O^~R-iB@IuT4B69lz?@u=9Jp*2yi-V+hF zf!QslJ_Ye>XY$yWL0FpTS_+kD)t-kEgFw~k2e44%6j>VA=qXP`Q2_8@dPs^=A@w-> z>)+7Do4UYEj!e!KqY^QS_%!z4dO{hbDb_@e?MlZc!S2OvUdJq{=9AjS7VcRZL=!6( z_nkKMUUlxf!Ms%@Hr@G*KxkMTZT6>I=+Wq-E5r{6{}p@v_DD)2YF1(=@#1LCH~i}~ zI*vK;5YcHfIqJ+<%c?s*l7QUv*u6jQva_(pwZb7>Dp)+2+K5R6lH;0(pP-uwFr*aA zaGwj6K$x^Du?MBAYYtxkMOR3%w=9MK5f`@~q>juhHYzu6>;Z&XhR64dDVIot`6fWp}ScRq~t$H7NxR<9{rd%Zl=@$HkQ2!nY}V5Cwu&HRc* zkmcTL|Ms7o=H)#zUg-u*uaUfUut8r7dK#kp|NPkIw@XX1!D-vBKj;FkKT@pq#P^Ez zsPYX^g~LZOJxAzabRso%Zh=(AlcW|*3!raK1>u0fg=R;b2S)IQ-5$p zUzYBa5h8x9?W-uNhr7OZqQgI&Ym$-R%@m^6rq&B!JKNLQNU*9fV{@Ty6@`u%eDnqH z-0*+idLS*_aiH@?;_Nq9nr z6^g}QXW1a0&Qw(W`%JduNOa6<#@ihFIT?fO2c$Wq3jfQ;XytA!YxGYF-ACAeJRYU) zj^lx&V;ie2n~?MC7^T~#M`&1mJL)3 zvoLe@T0H^z7XPZa7D7r7{fM=rM1cnym+~@nmv!`-E5T;xus0|y9J?5P zwC@Of5WQuubLqN$`+5G1ag5m!WfI|$Tn?a@LJvZLvD~oP|1O;=fmO#{|2k1)p#mc~ z_K_a(>p$&@GzeTG-8@|tT*dKQM?S{M<4+0GS`4hD_@|LrYsf58+Rq2PtULPl%u$5r zP_mA$X)Wfg0XU(QtpBjJ-C3u)v+cT93dj)4KZtuYl|`fr6%tu+R<9WNccV(pD0W>q zrcvUix0jUk+|~9hqv=@;JIyUBKqLG!1;=Lgi<9pw%57mUHP{g0cOh0Fcx#)6=xM0c zB3Gd=+r;L@IpnZL|CDYwlUz=i&2=W+`vMNG2wd zwc^(c`*+GE8DyUX?BKI^a>c5{?$cfNzrHGZSVa6qH<~BrIm!WWiCSKM0NFBQPy<2g zL9D(VI>g+}`vQ^ae+kttah5_nsUe(~L1)9VTz&TQbGOJ}$qlQmi~ZuxxDtKd3#8=8 z7}qe)=$Lc~lru_@Ga4@QnehJuh(UM0$+;3y0*nm0cur6T4YGVQn8Jn*i(m^I#4r`@ zq73sQ2J>NyA;3ix3#eir)PMSGQH}-=9^(3Sv3%61(GIqNQkw1d*D}rv48RK`4ZcCw z2%5iY{hB&`hWkkJ=FOY**}796c<`XS@#d@Yw=X}}CoiDoTY#=At)E!S(-#BOH;NYB@Gv@=04>-O7HU?leZQI~v;rQTG5t+c@XB}JDh8Zxh`9!?v zn-xXi4A?A6Q&g0Ry4kVf#xi~z=MXuqk<-raB4NR5(!VQgG347!r2YQ&H=8Aw{VHTn z-+rNU%5e(&^&23)d-a!d&pBVd{-4K7lards1s4Ebt<=Hn>3+9=Js5IL?AqaUGBih( z`|qxmUVC@lh;Y%LW%vjgIB2K?Ebsr!oC!90J zZ=fvj`2(VsK(wXYUw?Q|BIHyh1GxBB*Zlbl9B>iknm&D|{w^ZBQC~LhA(6llBk1>J z&_xoB2u7`*`ryU&va$}q^y<~qMR%h5OkJZqFr1+46iWN{o#d>u&QYKuI;G&nXBylG z#}&8$Fb7*r)48z&hA<2Y*=;|5&5`2gXci*FnoM~@-KJe)2vIAVOG3E<)*x9e9gl;1s4 zKe_x@0Ry;j%ITAXGu}tRr+vH5Qomkf`M>|?>vG&TPLyWNPILWrh%k_xf_oTU(~Q}* z;o5Nxac=wc>81C7kaK#u|J=Kgqed!lsl%(w2Min}UAy&=j-9&5jW@QJJ_>v*S8F-C zW50rzg4X_nvj3ig3Sc@;G7TNSOTp^y{rAW{_uS(^%pi;?*REZAW&DK6(zb0!IrTJ! zuBNBTl~-S@&T)Si=^8a^j5@#(Y;i7>8DI-|C&I=3XBz0T?_JT%5b#>LcByQ5Za^aJ zR0RXL_*NH5G=MJq$hBpoq*)tKeZvhmxh$SEZFAWi3nCab@Z#Q@`OrlE^fGL1`d(w$QV275U`0=j(2ikkzjRMHF|xD2{{;4-sB z8T8v?NED26Lm8PpdycC=UAlC0btFn#Ptu*qZayzE_vEDKm9@r;8c>Zbm?6W@w=&Ekw`&kLkU1#q;7p+qgP}w)T0JFCemYeZC zu%H^D|37>G9bVUY-D$(~$M?PS&Ll3X?41M%fB=X_^hSWFL2B+ELmlJ>t4@!&e=EwX~~t6&U0Ps+WYL& z_udCs_x`Q*d-Q1DI3osKu@M`;`+Ix$(g3kMEzR`(wR+r`2JVtD}9c zWM$;aO`p8YpzC8FyV)j}M!6^{nQlr6$2E9t{5r>geZ>9%Y}(pdHCde_ix(}HC0+E= zbenB>rzXfi*PMCt&GNgtW~NLpn;|nQs%80#HFEIKaXEDOgzVdY#FmGToRouykICVq zC*|0QGjjaIY2C-C74&h5JR>KVwD|OS*|YbMCbNsBxVTah5~eD2#Yu8%hLo08=x3Ru z2{-DiOUOBHfEK~$4W1Xc%#n2N-@o4irHk|X=*dHJ`pa_%g`VGKocPpon@E}P&V>Zd zf+#J(6>1B|x45`ercW<7FaQWprU(a314|5p=eYmf0W5$A1`_^43iGA8;P<;)A&#EM zZfR_4k^I6UNz2TV6a}!PDQPlcV!VtVgYCOB#=z+ixT61V?C6OyUXNMaq(qsLG*vRv zbEK$nx&a&)1Sr+>iX6~IUmD=YImc(=a{)^ptb(BBxB2kK8PUKsn92ok@!F_cd~e>L z9xc>Rlte(Ps;Wk2%&1f#on`yl|E7Q~4_rRH>gB=9mly(F-Aj99jsA|dZQmxxjvsRl zhL1cTfB2=(%YXdGccOsnHv?WV==wE}K^+YLo5+t}clUp{aFF|b1RfW3Hw;G1MB_s> z^oZU#BL-cu5gWhz@xAYTPyXnS{>V%;E?>TE7T+YMBq7YLgyIE&kkFE>k-U(s_;NFU z<=jJ-50a-~_+;KE_ddaAi6Q~m`QWNEeHA{D_6mky`t=~B1%qVUl^6n91n=uUlYd{< zNl0Cy>EMxVydU44`FC7Tmn$#y&~^0aak+SAtGw~Wf$mh?PoRpq#~rmEA`BdOEmX7M zo9(zeV*+__hQ>Bc-Zh%tvbm*0Kj%Ds?i_vnIr_OZF<#Iq3l=WX1a^_k ztZSCS!g851B~!+YOOQ!%Nt*CyNp)47Cc%`MIU@xRTK@BL4zP{y!FG~rO7-^dKcFyk zQ1>TghKJ?Qsl9UcFIopc&++3YEl@bw|1AA&jy>za$6qf_oH!-NkDb!zIknUu!~OgD z42Q3NyaE^R!F_x8?hgUi9{v0~^_<_N->F~E(^YniYisMmrJ}5RwaY;lFf;Jn4xZ~A zPxc$Y!ta@jDE@KS|9jPI&1x=I^xOPyJ^I=}21;hR9^>*ERW=m^6OHHP7uos5=b5Tt zoT0})CnsMDi%LSyhILY3*CHM5{LP>YlzvYBF1Wr<_xT)faoqSj69g{eTEIm_16MS3 zd3B5aHDHU<#T6@hWam!${SL{F9XsvsSW{E8emC4ttIZ`7koDz+xTRua4=@ISizTo% zTOpXGFEOOA3+P&{-v>v}BS(+OU3c9n4?c9Cy!^Qr;Cn@4h2FMiUK5}rNij7<17Pyd6@;q$FRUH#&(bH= zkwpEtJ=X`fgO9&nkd*t^GB^mmH`|HeWB>HQ9CNlqRQjO+ z7=Q-_iGAw#>(M)Q4+I|tCBj1&>nBg1HrQf$>eQJ5kH20Rz=fa-nDRiyvE_3NcU@%FoAiW-q!bAy>gAL(AVR&Ikx~0`kYWSnU;YvJW3q-45)6UrDalFJl)`h$;dH2 z;W2Y&&r?|Ey#_s9dOs04xe0%9c&~tjlQN^6C}_G6dkoHeX_hnZ_yw z*RX@(9e2q658NxyJ^!?P>sx;>Z@>NKAZk|-x-64-tG~kd$AA1sgRj{5HH~N&!*738 zn?)>pabZlABNsZ`J!a*0?2PUIDhlG>F-9sPFWvEmhx;#+%AbBP! zfAr4f;eVJU%lGwO^Nq*`5nNe9Gt?jccnO(40 z!ApUQf~@aGHX7W;x&w#=2=F;O&T z6qM_E=n5Xk0Rg}!$L*$@Zjm8FhS@Qu6prJF>d5z{mxx%p%=K^)9%5Jz!VF7}F~5QS zwULrtgII;2 z3-_DGFawphy1GUovBY4J&yHe9DIwp}e=i^m(Bk(M3`z;T%0+niiiWNYn>NV-91PE& zmwWHMN1lG>3Hio1zOH|(f68CsKmcIBdG#wce#HS81^!rRDAxUBczh77{5sn`94rS6G(lStc>UmOIj{l%`5g3) zMBs~l75_Rs-UF9c*a+MU{oGEGh=365B+?}9kKWm1|1{Y~u+2Tzt-ItN#pLAG|7fof zJ~`(-e4>8e2_iw_NaCBGmZ`uJZ!U8lygqr;tqNb7 zun!$BQ`0gmImVD8yl*vF_xsZ)=}k>dQe0XhGwbVQ_S`uNTAD;tx}}LL$tUHEl~pq( zzo5jRYr@3I3VdU1Jv%!DTnbld>Dl_e#I*2wO6oLyoV%ToktbQx3QhegC@iyb!ZBkf z>FXs*Tzry2U8^SiKo_4Y2wW~A(1kifP$ISgQ7@RYl8>noqywICwc%Vk%@_|J>3MStLn8H8Aq7ZP+Ux594 zhk{irud|V07>~Ps3+entU z-$NL11QZ28CTBo|0(k?Ex~ByDPzj92i&;+wKU zr+D3>>q8_Vaf-~GS#Jp~$H?!S;QnMgNi#}UPHv8rD0t0kZ*$-^UlU9W3N#Vz)Yq6d zf04{;n=Li94f@zZD=|!+nxPPtCmESJ23kH+QZo(6(hR^{7<6UkDOg2H5P`0gRQDQ% zMWxcL-xH`rdEvYXs-_X>VqQ0A0097?5@AF^Z&a|%FnCN2aGzLb`<-$_zglA<%O~F8yLS1 z@Iv8=0oQMJd}N`EFHIjwZ2UIHx8zd(f06(4UtEM?>Xp9mw(xy@S8w|-|D{i2{B>gw zdb5D8_cH*rFMa7tVduirr%xMnaWxpw3c?6*f|WYZbw=TA$IhLW396iM{`eLflV_xbG>;gTf6y^fE_^CHmY*ZqAw&nN6&-SWYA z1vL4t?28C^x#XPi$_48_aVI>Ck!Yisc-6!&2mPlzNB~-v;Ga5Yar~Gbm;Hxj_pbf2 zZ|@=5v-^Oo?cXR%x_V^6{7z|anSNM zTYydW0$HT5v1suUO-kLIMQ!bKWTqy#l~uK7wop)5EV+4w24mSd^mDlYtk{;DM}JqL z^>7syl}S-?xdPq{o13elu~m~4~EEjUFk= z_E44l@$_)avEw)qLD&i&$M*$YC(g*3Q zx?cui%Wrd_grXI>&+gZ7fQ7BQ-ml@^6usKTzINabTsf7C@ZjWO$*ETSZQypKe9-@` z@Q?A^yvnt3p(|_leOhzp&X#$49?qXX&(2#e7}1w{;ldquOmQS!uwb$M7MLVFBYm1o z%gU4T=~dFw+^)~n^L5TbX>IK=;Ns#1^K*H?idMJ6&_(EDf(jSsTf6@DX3tYt)8n;3 zzxNXT{q*YJ&h0z4>oLc{@J@O7!TaTlU-+#2Ck}@1yg3MT5kcts<-sdvr12Xbul~=g zd%WIj@Vr<_;ctC>WTETt{_gLrPb4;ejbjjqa*;2Wz7={*aOmTMYL-{GSmxUkfVB{C zee06szn|BRjo<3vY9`S1eug*EU?OBpG`K44=Bn8mb`P}vj$UW84v=%-(PPKt-1&0` zB_z2dZU7IZdfX=YAyM+`7XaoR4@sOz$VlQy@_o|BGMMoD`v?yN{| ziT$(#Eg*vD`gQmE1fP@d77bklunBl#D8hHdLK7zoD8{rgdIoVnPW-W zWle3p?R%gLwW})xUP~05mWH4SmW=gtLcX6vz}d=Mu=E;7u~K1d?0a-209a1;5S#Q@_KN|bkmlC?q%;&he ztdIb>qM@rz&$G7K3SJ6bbM(6`06g{Y(3<{Ug~2Tf-ACl&U3bU>58Nj&zx0B9`yan0 z@4WSf{v}q(`VFaFG3fd&4JJPx)J}eo;Bh=YW}5Lk86Ror;tFzX{3Zv`bZsaCu7Uss zXhm=HF<7bLD}C-cvGKbfSfIY&ix_|!Wxh;Ed*_{ZDnJ~wf6(-Dq4oeJ9;8;T(&Tpa zDp{kq*Kgb)`wr~4EBF8jkMl_z39m2H1JX#|N%jCR;0qT#g2dS;VZMZ@yL(_l7)%1` z2?;`%2QgkByJ;ZHJ;wEqxE_+obGo}p{z%{!*n0tq*Mlxf3{krx;HA)|NxE0GJb3xU zoP_-R`8&dp^;b`q4*n1Kea4^MpRKU9*^icp&?b@~5N(w0_1h!D*C@J)lAd~n5 zE^)MMAFzbQ&T{ckL|jQ*YZb+_Gv zl!q>Nn@Opiy5%5?2!d8{-KmluS|ZTp;mU=BFpjPNee&3O3N9$N9DkH56jY##zayNZ zT>LqH{Fs8)opRyAoqGIE%icZvWySJd{VlXfL4Jvq)~2Rp*fM)szLZVZbD?pTU8HEJ zZ;|S11^n6u`yF{_LO!bpuE=@kg8O|$mlXnBvj9RpKil+g+Z_E~3)s*4H)_?IHTw5t zv;OTksDEcK$o=@}CtbFrt|3-fP=4%ePV$k*B7${c&)i)YN{;I^OSp>JSgGU*Q zjo<0`$U+x?1m15sRBXK8aXsj|K9HHRm48Veb&Y|lcD?&!2Y{QfTcwwDwBy}WRUIA-wZ@2Jf93)jJVm=9rBxodOlqW@!MxQv+kdGr8v0wp- z+8lfS0)+wKZr;4P_813ft_+gIjqf)YbODWg*7fT*SlQQs{Rj1XDs&wGarOB0#B|123m|dH4dn_*_jPHIBd~ z4oE_2Xq&}3!MVY?FyE42l5VGR>1*kGa?Cw&xd=kn8a=)}26B1%lr0umiQ}Th-8NbC zY6aJg3OK&M3-I!4CCBijLYFTQ<=6sY=RUJ$P>_1Bapt8SId$f!LDx}w{q)>9sOJ;q zgeY%=0T=t7q#sxWUg*8c%Po+^gcKPya=Z*-DgcFN4_y_NHMYM2E@CmE`>AtDmrWkb zZ^kQ3>_>io{5G7@gt>)>Fb`e)uH0{o-wwY!V5(;sC6BA^^LfDXkQEHCaCwLUq}*?E zAY3`+()~`IGVUfIM%|n{cY%J6rM7?U_ou(R)2Gjbeq*SSXY}`ZP*$z%wco?^(h8ZD zm2aRmB`HmpnYz!4q+&*m%&cv+pofdwC}5Nm@?P$p^rsEhm=u{3I!bj&5P**`bgfe0(nNgO@*ab)RckcC z?Oh{lY~tZw>;K{(JEe)h8VMVT6-!FMDAmI{-FjP2I8y;0>*0<>-vbs2K1sJLCvwUd zP)0(|oIfOGBx$Z+r#}H6@PsB~Su!X=FX9$VCU+Nv=>^ zDEC4YG5884e%@)$mlu+x`_eO#brdj?b-?R?KK08fUjOpx+oW%0mn@jSSY~%t9N`8KkOCpYzt;Z>%2)eRQXWzYC6Zj?inAr+$r7|%t!4mxJ>^x~|YPILK>wT0M0$&(wIO}dr zQZ-R^rG}c6YGUfa3+KTW-LEV;rnB^z0$dz()CQD09OInAMS|{?dFvs7}@IGH%=?JB~NsKHN$S$Bda^C7Nzh-Yz?4ixrj@FVUnw1YI7ufE|8U zl;^Q@G27n5IraInzMvw-x`V&YP6t`sjt&o60E$3OWbZ{CmJF~`_cBi+V( z19p_O0-u{VZ?O_kE@V9P&?EA|16&xo!+vY@y|JH~8e65fs7x|5a;$t1AWck2HD!xw z3QCG+NM%K>R8`KDvgs90`J7P|Qny-c?l1>c?mP0?eR$XkMi{yXJGY(U<*njd^?S7_ zbj{MgMeV@kBHiZ-vCCJlQqboD)js_WXXVPh_sHXqJuF}Q+Mmdee)OO6ZWy}WRIFm@ zRj*%N?TSHHY{bUEL6sfx+Zg)a{Kgs(C*@7C@tYdIK+TG}-}iKdZd^m@;yJOh!W(J) zG8Ztu|NZX|Fwp=+P_1@s-yxeeZj`lw(n3HB;95#wlmZQE7trM=Q{{008YPK98>$xI z!c}sTI)DfO1F&#Gq>K^!dHTqhe3>QvXn@(_!??J)$(eaA8sh;W5>yNZxav*93IqW? zJpTOo3v%VkefB->x#x-j=+jR>Z3^C%EBD$q$|w1L9;ya2(eU^2U9jM0J|s%^NG3OL z-lp$~;lTlWZvq%2X(#wBzTXQlBatUT+D^CgvOQgJ_!mQn!G_j;F3M+R^D(L;8 zuL~26@e?LlUlqxtGe}V2q9jwJdl||X{XjjI$TzjLNOn%H0T+fGI1*M=RO@Ruhn)=R z?_%jEq;)EQeg_Mu1{iqJ_o4}YyM`GLw9O8$lZ4OJ$2sWo;6?K8%FO_9`gu^{h)7u> z6YM$w1G)eQChN_bmZRTyq(bHpnVOa*&AKm_E?XtNee3N!B6;`Vh3aJLr2^OSqbCf$ zPM_!D$WZ-mw+yi<0V*nMW#J;sOcb(EngA`0 zMMP%=xKNaU9wv=Gb?UTTKww|sl*oJAG2nO^6mcvZBzX|_DkQgoWNtfH1LlBY56=o8 zA+R-BF2w(+O+Z_*|G8}*QU`H#M+e~16wpzGat znO{+tG3bho*!a*4{f~ZQ4U$Bf`D5cZHQoz!MXOp-5d~h>^EC*J(ccw*&R`8-vGE%l z{6l>|rG*TBcdxwiikWC!x^&4DDCXnZz74~M4brdRvATD)tOx*CG<5a$yE(3aEno!z zV~K(VEcuc`;EU41hK2@9npx)xI`?7N!Q<$iLTN*p!hP)gx$|=N%vrfZ6R*4Px?9&> zuM|nyop)Zerg^S@Kl$X-`rRMY$KNS;>ElkHJ}ErV7L4Wl5lit*yGh05Gn~ zlel{jBcVr4VLL$fm4|W%1+3`!kLQ11mM^ZgtN4^mp>EBayVz8%{Jav0o0KFYM~s!B zLq=+hmeHdo$ixW=c7;DZeVXLu6&Xy;)bH5X)NEi>UDF_Wnv7!M4s;C}Izk~N!^-@a zXRA{aLtx7T7nAB@IgTjM2MNno~I(>#2UbM`bWo3p$m%a{VhA3b_R&Lk^SE9 ze?o4(jd{tk^m8oGbGld7XcFJw&-4J>6z-jo#a=yDl>S-Y70!bvo%`U0b9c!3vlndr z+>7t6)bRA5w#%Ut3UY^z$)4T&Wy|Ir(zj- zl6p);8tUDI!vx<62S|GHMvs}`R7-^}U>K)Jpv!;@V~S1(TYlo;g+P~rhKH!WzJ9s) z-uvzM^Vnlg$fJ)wZoemfV*n5!1Q5{!w?QEh=%MTpIP-S=sBu03N4E1AfRV@d_tS^i zr@wLieeXq0bY+`&-g%ci^2lTQx93TD@PUUFupZUhkIOxm@0BA*Pw4M(lXNfX(Q{&+ zsZ@FTo#|&wo-)-SYjWHa1Fe+gG&9G@%_%g+%ask**m@4`nA!RIyDzcHqcKzg+9|69 zxEyFXr$iszri9t%o})Za|3+aBgKB#{=;GYA@RvX`&AJR99D9l$Dn&D9n(VGjW@% zlSZyaw{>XJrHME0b()aRpEKVk;3Y}-SKM7fs!`t}Wz#FIe}kTmjPz_%e&RJbn>b;z zj2|~i#*7&!qeqXH$&)85P&L|TTfhEl;9@%oJ%$tog+&q{pCG^gdmoqK!$wJ2S*0eI zD=Zl$Nhev~v}vm;Zv;s^Nh!;|KH!asp!;l{c;(Xdt%ZO3^8Z)*yUWbnqOoz7?vEw~ zo<@b6W+^VNka6QC%PqGKm)mY1AwzB(VbC>d&LWXZB_JJ!p3nB%F(R1+S<>yhXKTs#-(DlREkn44)O zjFb!VI1+wJ4BI=HGfCk}lTi;_UJdYSNOZ8>M?@*146a?*HIdbGrmk+L0T{=}mlg(r zi=aGhz9z$fC(w24?L+1FKk-THeWIT&FTYq5Dy5dRf}N(hN{=om{H0 z#oTJR>oG?Z%A8l2*cY68m6bKRRB%>k2Dn%PzlB95l9HNk$HJ7ZTZc+=N}3%5r*d^E zWCdVr@j?qqJ^=-Qma#{Z zv15M0{8@W-|Mcs=Ss*iO8|-&HZCalGejQ-N$0f<6xCDudOVrHeIaZ#x$ zSwL1{L8&cKy10+25@wV;*y4LqmWt}m`NIVt2Ur1ndJ6}q^A{;pEp+BE768~F(B;(J zh>F{$=PYVh>m1kDHCvyzuxp8QFJCUb`nLt;{?w@xa{2OI^3cQg$;+R6QU3W~{*S!* z^PkAO?_j9mpzGJEcEzA8He%ymf{D5oT9vZYBsSGGyU zxXR5OQ!FP>o??j^fHgUuByEZTNK)cdi{vTkl9rYwnVNuSW@brYVS&&Cwtl_)%!G$7 zfQ#?MM6e{f(@V<~+T!FBpSW2*{;``CbcWkJKR5+)MSpESir@yPS}a>`SNt&%AfYFb zVDMT~bU$J)fjY(2e3J9U zU5lkV1YM|HOLQM_l^>&v{DNYcI4Qw^3kSrcDN}8tVqT*`VSt36;IZ^-Ips?MDg;_) zrL6&&Sx|O{VMf3-!^2h(!~g;-Mbvd18G&*VW@l&b=2~+lg?^qk2VJ}l(1peQZMO}P zkALzebNa*akMCgMrHQhKVh_ga)@_hY8#l}Ltvh7r_Fb|?f!fLe*Ke}eMjx1N-@R*( z9D8QjpulzdYYJRvR@-^evvie07IW7ze_5x@nN6uA>s|Vt=IeLkduzhpKF7Xab#<+k z&gJCfD?nh1qEM^**9Rqr)2Ek98ZL(8;|#h0NlHgiU2u&Ayn@iR0CO2V-wFEb_}+jB zzlTYa;x*!InVOoW@0+K;k7D~Al-B|l>>DnmY}>ZoN_pvfqihyc`SRr}Rswkb+#R-l z@vcj9_RIx2qjBu$DcQMWpG|eZGzY6!^&4_N>x2< z0a~`7I@wPORUWd!0eCS1I7TrFTJ&j!fXn};gV5zm41>_MKp}XE{+`zK_1ivVt~O^I ze??w+@mcwY|NRYlKBP#v}_vEJOGx35=Lt#L{h zu;s19eS!;+dFTRINX&pP?^a0f7UhbR3(`xqcP|saZZlZxS+-0TEu`FOzAV&4rlYN0 z=8&k*YLmwLMrlH!QTQmIK10e%%cU^CNOH6DBwv#*606LNTurueGzlwEK+CtJi>up| z-w_1`WeRX4W))IYr0Yfc8iggAfEWkt1293L+q z`~92blb^U%Zu;bH3OmCsA>=AMrC?SrrqBgwdFY}%%=du+3_u1~+eu_uK6h&3Rlv1< zd8!l?mP%$;u1royHaI}hy6Ka{6t;%QO*biU-8@WgMd{Mdz+6qHbd4A<6UN0WV5Z8n z%sfrXQ4H&?bdWi+nwmAiRfr=o2fE_or&y^WypGr9311+66tUdybkki;F6 zjM|xX=5jb@+$0$}YP>-kikbC}&8U{T`UrFpK$VBAAZP`_%-jm~v$g4d@qIrYvi$Af zwzjs}3LQ;STU%qthI7#a7fTOZ1O_001*Lc?DO2V4+j022+4{PGl;OisJEv%3UTMb& zIF5!dl$TX2bh`%YSj|%|hr?ih-#S^f(v=AAe{@k4a5c+@!%Q^2$|kN}sDK4%wYSgH zeL(-(e1!mP?-%Ipx%!=2t$dF2c*>L%Ntm2u<*d{694IL+v-zXw%R`ys++nV?88a#* zEh9^hhf}&xyntVzi~c)G3>Pd~90n~HdM+w#00{sHP?emVDr3ivmvQ69n+i;z2or1{ zKYo%-oEUGBm^j5A&u0YI07HIHk>QZ7U< z*x9pZ?R5YquS@|S%*#bm3v68vx_~rF3xgK%lqv#S*wEuvc>457Ya%~&;x+zeZ4f))k~!&azu?LlQT521H7h}luMB&U4@#=k!`TlgNtm1{B_*YTMf%#c^qlmDmJYT6LcSNK z67+sFD*TNdGf{r;zuzRE`1q}I^G&x~FVz?YkEv5LO?3bg=*RIrF1``p1D7x1Ldih6 zs8Il-bnK}kW5Uq2wR4myNX(&i^DRTH6wU|0^+^S;n{FN|x7?!8rN9Mv4Y_@!j2J%F zJ_`wJ+SF;bU#fMVQSt}qw0F!k*FKak4|8eh(`-WGMor>@DsT0U($&@7t)bsRVUlDL za4XU87@y!2GN5bZsBs2e`MTeymsMF`ms!9Y26hW1Xr2{X2o-Vgz0C=XQWhl5hgkmn}0095=Nkl6x6mXwhKUGyF;SV&J2(1m*Ag8cy`c=({l33Y4S*a-?< z8e=hInWX1YqJd9>f{_EHWV_A&a;jLo#Kk4(eW*{A?YH|EfyXdu~ytuhh z&oib{XjMp`HCF=_G14cos|2K#8G; zE{%5;yx#rg!R!5+EX77_e3%D05A&M-HpUGLT_lbCVfbxHez6f7AN0X*h6@$H%oUp- z{NM-nJe&)!T)Cn^blLz3U;>_iE`SOM@#R}Umj^GBT;K#yiH0sp3Q^3w(sf9G*C&o2 z(?sL6+;!k6pgaY4?XJtrrQ9hbek_sG`GTV##CSEnY4b2WKsZd6E7fI#i?N>^4! zwkBULQL}_iBRM5Yrf33}n3Sf;;#5rvQ#3i8qLC=$CnQ)*wsJ#F6!kG>3UQPV_V%vU z@3%^qs2mQq2vg$pdvYZl06^9H*zZ$bc#A^UP#HFKv?i$W_WmU$Wl~>{Ifzqcyc)rT zyx3FYn3k1A`4p21V`-gi&n3woHFBI>+VpX`YyIz;iuUnO++vXBmso*Q5_i+hLmY73 z3UCcGl?w%o337RzN&5XrU`aw}%&4}+oCI?&eL@NVZ3--uDrRV6i;)DSbtogi4`qN{ z$#><2UDB!0xMayPb2MyfZI@~VsDV<&^)is**QvRmz z>&pv0bOk{x7(AA8Irf(atsrpub@nOAEzkk5&YW3i1_;4(&?#IiY@3^FtjE+wppJb% zbl3>pm$yWqYvfpoQ%FEDt*dP?2mz42OC8UpRJ5muGT3DbUbqS_k@@o$%fba+vS6M9 z>1>?(up94EKwTnR?rD>)_q5yoX1`NHH`gAwSU<;H{oJimKBG>Gi>o9%yF@`LL&oWO zFl^Wug?Rl;!^g;I-M5n_CfIq3f&);{<3t&z1BQ9_odA6lyiuda$=GodO>ty@&*eJ+ zTN?92OS=GonS(BY4ZbTSjadGVQD_75#_Ma09~Womd7?rQzpd;L)RYvLn@SAK7b*y` zEib1?iVCKi`h?0v52ah?Sx+HLZUaiJqfDVf6YO()4PE+mda+Ew$}Ny-)AVr)UwnUl z=lsS1GH&xeK$%yxYHJ!4np;iPBHDZ?Y_-jrZM|}Ct}h2i_M6ak_5(&5^p;XC7=)|n z2*Xwwx_FHccApZIMhnXwTYH~Jvo`N&$v2M1STkimajJ0mt? zj4x;`mXyaQ>|IG7y*UzDw@8e79V>cv0c&PJ^$L$4|(SLx;i&SnujS z>DFWg6OE>ZCaF?TC@L(qJ`j3dut!hN$dR=497#>hR`|*^Ws8J1X-b+x*i=bO)MaA2 zBqwJ|YO+F_-dCvr!u(Ut`HsZh&GWR9`Nwog@I9F`2os0o zV3I&E39f^!;ij|=*UtcOkthRmB(Tg!)Z9GF5<2m`+A8)hj4*C}|EwsYHE$j4DzUywde^Wa#fJSI;e=D=*gp5}(aVcy$|4 zh9bu{*4=$P&Ow<6EFQ~xPL_i&Knx%Qs!*^1tBg=@7rz_#7@ntKUs7R?gf-O-PSI*| ziWb4~!QGRf1Qp{IfA08T|FHzTJaoC3Z|A;;t80Q*AefJC0Ceg8wD;jX0ue4TJ zcXi8Bh4}up8)Vn+J?74O>C#>D=wlDcm%jW3`QG>cO@Zrm3kO@jUg+Y=e(ZvFY{Z5e zzs(-U8ydP8zFaC+e;gaJaqU4PC|56k8Q{XXkP93yz4Vei{P4pzPZs5WC{rj^-u@k+ zLP;>_QXuJB9#OiYp$lcqyBG2rz?+AzLx&E^$rH!q{JAr7=N;z_x-MV3sBxFvt?zyD z&b#E!3wOwwQ>Vk=wSVt^*|BY>tk)!Ex^BH?m_ZMTD#;>!K|p~|*jcZuYqISmnAqGTuL7@)UdhqM}l%uW!=*Gf!cwTaObEvRamDlD9~2 zGdC5W1#qEqQCc{2W}`GISae`6KvKS_Qx+{kwdu4HDS&K-!edH$mW&>+z@?xydR)AW zQt+A>pCsA&MUta|+C}Li4vEe!vB`i62*bdmp|RDL^nFnR=hoeX%{&%Wkf6+ueFwBM z=`zVI@CB6l{aamKV~~r|+>VCa#sN6oxLsycX zGlixkku>vuya(?EG?$c2w>iEjAqDPngyg#duVv+xwj|gFywQu7uRwxBWL9>*T?~ky ztY9=cUXR&WD+$E_#esFGL==d=jbl1SMvokC0FBB7#MJA)?9k6ea!&~y5KXX8FuI6~ zn=AVrr3)DhY{PxL}#8 zON?n!EikQM0YphY;PYhW)R!EGW4@*HFKg8>-e zg*iqPXaQC}2HPHnE)8CX!IuYffxDIZ!5`+jo7%62fu|FbVUsk%2*9@ zY{bUZ1IVKP@mIMp@zz^!$>09%-^#PkJ}dX%f4?~w0$uzeLaFl5<=qQ`D?d4M5W2W8 z2wl-7hCm!8i-!*%GNtSEsS|Sk{296H&hw^p8F<}|+I4prx{e<`CPxn+kwXU#$(~*N z%q?#Hx{b1Cb-&GNL@y0$LxaLsO-+MTRMbi7^lDAksx%obm;C(cn!uIHv}r|}_~vQS zoa4$5G`(juobCJlJvxJk-b=KoqbEcsMDN|`ElQ$|-U*2=dT-Io=xvBDY8ag$h&D)~ z6aBgF-}nE#v8=_58Ou4>dF*5F&lW+;4Ua8i4`V?5WB8!@BZy?`%Cj`}+^fjD2=Kzm zEb_i25*dma{iMvSsybfUkyWzD$p&@Ap~)1@{Fxfp?4qipO$=S1q*84}J8WG6=I@WDV$XIgQ`j{Y7S*(=My99AkmX4jwxXn;F8n1Ha2&j@$-f4>-Oiob%leLXg*Z0$v440cWvA}6DWqd$4eN|m z!*(OcY5zE~G7%7`ioEp6=*o7AfA=bZ-eH46>Fedwuo;oSB_nEa|Kv1s>%z|kh84)4 zZAm&KM$}n0Etsz&u5oX}w0b}A?Wb!gG2(#7vQd5uA6G*KK z5A<*5ALMA88J(G-77X$)tu#tY6M6^f`0<0Co7R@(IO=9WizANPO+eG^jW~E#t`oGi ziI4hqw+W5GhA_9sv+a>fhW{qQr~n!HwOc12y*-YRp(GB4NV*aKmCmbEOp7_%l z)){lJkRvL1+F|<|eyGiWozf{OzV!zOm#q+|jf=|_X?(QBjg5=(Dl^9A6P0zo`3$LE zQJ3DXk~*dJ!d)wu#DjvipZ}1pG6i?~C#v6_$8HHvfyHc~WB2TvAh15!`g&Q&APzc$ z>O3b2^Be2Q(kH@~fy&Q9_=D4`gu+CMV@KSBU!wECOx!@nlpyn*NL@4Hb0WT2f}8$u$HuVeRD5 z@1=~Pj#+%iVVs@1{{G(NnZEOg8{wMwt(N-a$I%LHcnL9ON8C9NCl^lxW^Q+08n?lI z@H&^;#DqRfn$xqVpYk4RG&CE51=A+M{U9RD1>=N%=Ks~JNJLpio9Wu@q*kE)E=k1Y z+=yDhyQ`0~m%OfC@N1XKi+4XEI8W$Pww_OoT;o&j430Jd!Fg&iubXf>@nDk#25}$; zk=OL+;}gcV+q;`hmgm1;B#QfPQ~>SNIz^Ao{nzd}saLBV;w}$mfSGIjGs`f~6Gka6 zai704K`U@P|57>oa)#d6X{T&fsL z{pk1-Xz_%jJLo$}B)ym65-=TT@kIlgvrIZS{+w1jdc}J|FP)5+n}VY{vZ{+6@d&#h zUobSY1Y}y~w(s#N|BaeU{K;z%oooii$O@<3XQr0*k*3TPm-qLFm_BL*(i5+3oDliz zVy%-Mc&~j?z-b^d3zWXe)Izr7@;lA>9!}HNAw^`1oSAni@pLbIlC6@`;K!+1S>>|S zu0^)?JI-WFWZ0?q+D=L#`sNV3h}63Sk_s-a+4VsJ$t!O1nkus7teSQMF1-6Z1AXjb z#3Ylmy;)Ob0Z80(N1vC-^t<|>)~}`13aW{urTH|W86P3JV8RWD4iCM4Zm28@9G)Rt zk@xtd3}6&S=e(6TT#3~0XsY!;sg%Rv~* zJ!;BUZg;3R(#g`-Dbk;x7X<16N_6$F)6%zkhw| zLKE^kGEdgWY3^X3VC z+I;}g2%J8^c4dLS(dwSvxXHivoX6CTbWE_%#rcp-5I%^;=!K^r_R1pH$-vG zziu#^nMKRbeG0SV1i%V+B};cQX4y#?K&UG~lL+m@=X!C#JFnmo^$bG>cBXFhjVR?a z%Qq7-16kRIjspQdKD(h-G-B zUK?y~BdomVnV7?x1$I4r>GFB}YLzch>M}L(V3uzTpD)-TgAa9T=XdQ{H=o^!gWf2rJ+IJzvOW?CJH?V_4ws(A4suDW||)A-=;_ zzA?(4e>kT*e2)!)7dW=;W+GF&=+>{BAqNu4qsAxtURADlCxJ8lDlZ!)SoudyQmRr{ zyHjzr7A!pwl?V)8&sU@>D{2~EugX)7w!f4^TM!g%oai8up)R@&+j~O&O2sCQVA{rk zsr0GW`1gSw`*_p$)X&t+gT{G_RyeYX1mzA#XW7oG2|LUZFObs)?BK51f!E87--x&k z;ew?eDV=Oofi$#yy;Nn zIu=;I{D6lCHpeUT7I>tIS(p>{nWS>DqoDFFV$hXRuA^|$|E#F29GSm0U-m+iuR7f$ zl6!6s0A<7;9I#8SXKr-%sbFQHaxR?i*BYBgdz@+Q>~Rsf1lzLz^sbYWp`HZtF&brX+}4<9(bKHFxrS%v>{s=GrM>U!{+k z3vQ5Y@1UCMF)?AiWMLUh70{jEcjgxB=Ac4qg4Xl<@Ui89DEQlvUzbcr^yGiP5L|Zn z)pBTUxo=LL#+K9G6cT!ruX~fP;eZjv!*$s%K#DvNIb3%`>wC54v(veL5AQl1rW@D#r$|V&5|xS)+=$m!^goMO7#@^E|vye4w9XD4i%( z_26d?Q{($74%_W=7|0ga#9#(J`1h3>==+@*bHFmt&u&=SRiQu%KnW<+^=O6B@+$Ex z)3*08L^;T0D0i&G~2-EbLvPAFe5F`Irmly9n9Co>544;01 z5|DETdlX+BfQ(u1SeM(GbWRoJqJQ+|YO`+P5Ya8z_!vwU7{2}LR{qTlk;pd!U%M5# z{yTTYHM6MvG7WzV-_XR!=3Xz;xcLTC8)H6JP<{^Xctiarf!?)Ofq+_;<1N7=m4L}N zj=&-kwD*~cPtOxCE^B8!?ei{bU6$JQ7vL+lhqN!>rF=K_9zk5>5H7U7U*R=vJ!qJJ z7jVhYJT-2!P`7vs6TkYi)cq#xz9L_G*miO9tH*YIKINN)!-wC^k&XbbmkYgP57gV-$xUa&*6kE&Qo4eU=kq{&BIS1lb#8 z|3z*_ZvW38{EXed%S}^rxb*V&@iVFIM5ZsbbZ}$-N;D!Qxz=aAS5?;SV9s%YHY-1$J8KqfYobx4 zJ}h%&B7jYkimOqVe0uuo-sQqSVR5Cgkz@nCIlHvARo|-GxKCvORJ}a6&xHlC#6Px< zo|#9Aj)!;muw&IMq<7GG%5fRKQ9ALcqWJsaNh{g6?B#^$c+Wx1*I$Lo48P(MnOiY| z^ByPk_rjc+EX9VLy>Xjg)rS&c-3EYQk><0H`4XYut@Au%yCHhZ`p)Ms>y4k#N!0W# zif{i6s2kbRl;8@vmhNV+dpO6jFCjKSkhKTrL896zPum^_q`TSH!QpbvGo?OHwm&(` zFX~Ux+jh}%x1p)j@F$M_cwtI(82H3u@G}kJQ?Op3ix)c&Q z#7L-8*#3+0@G2&r=nzyBxOP(4*>(A+Z9P5YraVNDH2w`^kRD)-A@hd3E~43hQt2QJ zEQN{584y~XUGF6R8#=G^ewipOGuI_5oB}lzE;?F7X4p`F+Ka>00sr_3W6-TQETYCzXA9I0`PgDjQYrEV| zxAlYw3f&91AA89?rNr8;;q1v*pJo&aQi(`-k^y)#yAz4z+)V?Az+m4~LxsO@B8yn# zbokjRin17Z!49l@vS8d&QoW~p@rC5H`&22UiKC7SN(n~vq1iySgV_izcj zLa+T9$<6k?d~T27JW9KA_Wg5B^_+B9Ei^X)X-Y1`=zewp1m$Vv4Vc=p<6fZAv;NMm zv1u2u56mUdZwJdS9t(JMqA$K1Q2gPs{dUh%$(1xngY-Gu2rIXys(Zp`Fz2~igKe>? z>4Af?#`h%FuhNb&hxBsVea+8!0V7F3tIc*O9+uUlpO}Kd%r`oh1(uA@?{@J;L@w+j zpV;#1qpWrIAZACH?ZO}kI(MK;A7}Z*IG)>>jRw{z0yKCo_p>BBm0jet6$V-Fa{!V70=LAR zp|1o4ON;ybY4!Vq8!X*68Vz(;ExItK1j7wfqY939VQyLl8bsWcoM>-3Iyd=sbcvX zIOpt$RSawU4dg}tsiT{Vi10$ln(Y@j1Lxbgd|Q%)4>o$( z*6iVt{?`{mTg6 zyYDfYbI9!%Y2wiAQr{K>UnMfU(0wsheIZWkeL)|$2OCH|_98pCyScAM@2{kp0A6%G zL(eem`V+%|YIY&x=f9=gB|vgD*fo@W%@ThYu>6E_?jH2p)uSoMq-e=}uq7MrpM;m{ zlttfVMxT_~E9k+eJ;d!`XsF_e$q6=Ll&9Ra)&6r0cCBQNQQBDNFMs)d@4ngpBLJ?# zydthiq^GSDFt%`Q?587k<;NlT$EIZ|@L6mzS-nL*&$PW=h`=A}~ASe`fqUv@j@vI@wYxf|iMt zl-4DFZp(Hj@-J0G&vR6;$gz&^t`GX%uZJvqP_DCGRA}IPND2i8lw8M1tCGp678zN+ ztro!-oCqaw--%R5{A8YQ;RQpRN)-F5O}3z}65bx~ebLKdO=beRLaLI^x zE9ok27B?fu@W}^pam>JWU=ww)V_&Zh1J%V&B((i_a~{&qZB7+y87{PP(*_kQ!cXOG zC3*r(pr-;j_{u*>8GbHatKi%~5yPN4b5w{z!D~r?hW9 z39&Gz;uNqIGm72}V7x0p>ypx8AuwB{kukvx$CjadO47}T`7R>#yXExN*nHvkT$Sok zPnTQo-Y149-NlHwdve)s`TFHA!plq)uDKO+!+)n%w(&2{!B5M?=me&UBqY&grseAly5lwM04To{ z$1U~S|BmxX=jzmNoJ&UJQ0s=nwHJ}p*<#Ow*EP^0T#I)rZ(l6i|3-`nsQ^4`7F!Bq z3s;kjsOM+NbIZrYDG|1(B^U8#?He-V@|3+pA4VNuJ-M&kbrR?$**}soptOH<2bIgd zIm!+eLb`D+lBmNdOpb8aly`Pm{YAi%^Vt){9sSogI)#;QZRNf4#q<~db>;hq>`;1152!}IXzA_FlQm7B zku|Wc%)$VX6i=e$X@$haKho1VQq3&1F(9AAt0{5Pyc%>R*{HBy*HQZ2->qKmja_kK zY_c2~W zQjs#4f;2Rk&t#7F5@*6xbAM8wE6Ao$m9afioHAQ#?_TuN!ZNY8%6{g+-nb;G-T#8- zw)Xc*o8e@x*t?*3L&!P{5o%p;Ea+&^Xg5Lp!pE(5vQH=Iq4_ryKeZ!S2ZT^bv`VQ= zW4#QNCPQ?1@@Hn2Yt0nxT`+SG*BXxW%>>o_b+&Zd#+4DnH2ZQP%5|PV6p?WoWJz?? z8%r_(9Ub99o^e_{>sIQSg+=yw+<({SfHm+r@s5o_v#h+lnu4Xq2=>>UwCi>LRTVYY z>vK7vL)CS(>2(lJG^PIb)#!#fl~AZ!W%c4pg*l>D8Eqmg0|R1VuOw<$Z3lAecq>>s zj?=sIY$Ah3aSqa}S~S`_j*;FIB=Qz3;;g?KI*k+obrB%QqQpB(0CaQM=v_$A+vEuhFkWKS;HyLUO~?Z067Ta<~i-?REsRS=KSd(q6# zQ6J%-qQ41|pehMyh*>%EEnrPutPf_qpN+h~0^T%*3 zexN93knZ1P{`^tEoBmQfjQwoObzl|rSjcWhG%imh#hfU0mnm_- zEp$4eJ2jG$DD60|DSgZ7_gA+d9f)#wb^W`;KkfJA1J0jhwT!p1_ur-3f}o<{M;&El z^_NSGxPf_p#vd zJ5huJd&aO#{6gnR39QeTFDhO2j0*Z*Pj`?cekti+oU1gp*ZtYjZhCXOkR>=Ou=+Ki zj<@4G7ARF^&al^iC`P|b#X}=$(8fm-eex#xOUuj^th7edqHd40v}jzNaQCVu z@)(mg)klIU|4030-0YM7!54BpUX~7!wT9sS*y_S`Fm3at=hft01dUq2r}xf0#QLIY z-U@Z<3DY+Dg#Sy1G@c1&hMPfA?2#wwrK6E;vq>yg|Cq#v;80*~Pd%tL-ysm@_?#{I zhIDmdIXey*7}5@R9 z^XA_dQ@!{*v6l3`=pyDK?z@>i z*mYz0;@RnOMB>tC6Aw)=ApTwK&soR$u{c5aOQ!-HFhYG4v-{$QypkZyQm6E;H-+Q!1~8CW zDwR1A0>HPngAu-TP8oaxuo$)C{t@9EPl98n>rx-*qW*=uNdH_>?~2SC=Ls`@&6M@! znbj)gpgi;dzsO3(R4eov9tyZVD>W0Iuud(Z;7RiYS3AXg80cFvHC2TldHs zAUGqJA9#xAcmDZJ&D`&i&tDn?hg2%zS&o*tG7h#oW5VpM0N(;H3qZ|ennZgH`wZ_E zV6LZqZ{c*|P3iu5A=nwzy}d_~vx#3?k8MUXu&;ohK{>NHSODW7huUpm{=ZOsdI@=NK<>f zM_)-5%}{+`vB~1{ZZ6^ek(0|Ka&H>GE92Br>l1!m-|E?6-zD^3d+RZ)DQ7(< z9{?nY#e!>rQHU=J?o0hx(`OCHIF{r2)qRI%fJKc;^5tGp;nn$w%6%uoZpA>%<9EfX z-=f(I!(Zi67jbuMFCPtl`sx;`_KnLLzTO95h`4TFLr~Uk^9A5oqN`6b(-(z1P9rqF zw08y#bFTND>I%2zw8GP%^oiH9|E;8{}c|NPL`dN?;qJ@XNr0=&q=7$Jo-XmmH=ttMpCz#}VT2 zJqG*@W7peWg}c%6m!rUKky}&pI!@w#Zk9%Kv`JGO<$qn8u`@&|_2ubhjfC5}yvN@O z`bLMvVB@mm=szz!pJ&|%StHb}1Wnm1)u-GwJgLD@vB+%9j8TF}-rYCWr^exfse<3l z)ki3OAT5{-8#F=`3QoDkgGAV7*yfpz1fBwOBt99&$l?V zdJ=;6Z;6@&d;=S${QOZQ?RZ7qaAl1@{flvy8w=`$#xdgF|uMxo`Y2NoVNXrfH@|7k>qZ%xe*+%>k*bjF{R*KU#P3JlhckJ z)*&|#(7c7O^7&XGfGRLi&nw~%!^C@xY$ItP+yypC6kGEDrR;Z^<=_(T;m_T{ALg!} zm#^8oKo;3Icg{09=FL_t1_mN=I|j@@e*CZkBD3Zr$qbSp7v(EK<0b%OWMA)H9`bn~ z57mj$9Cg@08+ASW$=$wW6KyHOH(_xd>o#*8kEtN{_wJvudgVlXG6eq|hv3H8;ySRr zA_d|j{yd<14^FG-(m<;$GG{k;(7%3_?#39B*OH9#8Xtx1QLSVCk$YJ>#%AT~L<%*^ zPTD=^P@FD%>*k^r5MSuHY{tqiyUu%p0fYE{+QZ)Tu#Bjq|IUU|w3Sk&en2jTAphx@BnBoGN{@L%aSD(RF!~NR9}; z#4n8f^!L#J5jeK@aQMSx*+=fqSe+0M7%Lg=-mLW<(*zXDY}yjN3v~$nuKWxayiQz8 zg2lx7&o=1m;Z<&j`^BC$LEzM}4g4lf0s@BjBgt>n7XP_mybtNcu4Ue4>`PBszx+Qi z>9;qq|C*dnLms9c1xVvRG6pa0M)#r6?Z6lWV;E>0mSe*p6c~+C^)J3g+;4T^@Ox<2 zi&54xPz7+G_~hx})%hSG5p$n>V*dDP?Rq+fp3g zDftDw-llLf7a#cW6%>lKt?Hn#|40TY_Ygy6AA~wHBhxr^lV@C#7bb_sZKXf+p*1l93C4$)5Gb23K%ND$b5`)qLQSj2QiLRsy|R z4vakJHT6LWh<{P$jF}@nrHa|!(i|hzL~35u1m4U}ji03kbRQSj-Zml~3La8x>p~De zWfxNdwsofhRiy4KHAg+CBpqa34*^vk?&ht0`A3>*O*JFyCcSP?-GqHuShb7`(;fuH z8cMFS%(9R$Qz1_dgQrv6!+GCfLqV)nl2>p78V+Bfxw0ctb(D( zicZ?6D=>Of6w4xEXi!-h?e-rmi2erQ!OFsIaiv|PHqM)z+hx7xI+R?#my?Jtc@$Hh zY`DQU!q>9Vj}5~1P1_eUeu1$?=+M1MAnGQi_f(f@OEmjeDH7Agig#*z6qHV6VS)-( zJ;Iqe7vl+oP<{uSBIefF(0s3TmVz9>kBG zTWI*#QO5JlfLu6^z=J@ACJ`aJU_^gBr_A#&g$Fb&1QOFoaym3n=WfZ^w0r@nL7oK9 z$&IWV%|DYs%2s*_)Sq3Jqr>-Ss~lALAw3nhQkEEYv8%rp|A6j;-~1nrN2(YDb(7O` zO)E5A=toP1o&aLg!+Akh{s9)FTo@j2<_fTR~Oz2{VXZb)v zq<#F?fHtv~cdPXZ7M@?bLwYX0!@Mpzj$w}BLhCgp%7a{7hqbPQ@{}r+-X{}NX`i(@ zCS_Pmt?<*v<$*hg+R#ub2TXmswCPbpeY9EU>tD8U-V>*H@8(%+)Hj{rvJ_7|ySI}r z#5|R1luCpfW^Ch0*x>moOIDBZO?0H3HdXxZOcLa@iulV(lz-mi2obcK->yE|Bt)jZ zfS4kn=@3)+QCqLdqmxKjuDQ;$SwV8ZQdBd@EkLF`nhp9W5xfo7Hl&D*JUMHZ$!qwN(lb)O+#ymrmkKDLRMjhpc61J za?X_n)@K-IEHwp(PR9uIXe)k2?H3g?A_AB?_JzctTFW>g8^XnvA)BlT%42Iei*E5C z$M3zL!WVfYgWu8r*_B(AG9`72_0F3RcPB?NM{?!QGt~8wDr)&v!!LAa8a>#!+hodi$dy|a;lb(XlKDfa zDE+z2A^#wo*glE_3e{D@fZK(!1CgMG>W{i?c4b@agZm9KJ75_~l?;aAO@BHZhL>}Y zI`&_dR3G3xLUSV{6HO!o6Tg|WqKdFLO80U<^6eg>cb#_R9WqO6TJdOZa$AI{O?_wX zjzu?e{~Y!GOurJTaI~m~RcGR9{F<i!}lj0^kv<)m89&?OM`5pAtS z=I^37sP(G2ckR=_74OXWMJL1mASIs?UjFoz@4jrQ8wD2qHbIyUlerB)xmD05VQAX+ zB}GUqqey)SA&~LM!l!xrS~G?KHa!*DtSP-n?}H?g=kU#w=G&XhZJCjy!}q(J%oCp| z2@U3m1M`>kzWVBUqLbtB$u?Okkvcm!Ep02^pjH`L+ChPs>DPJr(vXJBaFU73FdI@% ze&zn1Jfmr|)K;;63QtE`gFmw*33cG2+YK~mjb*A~36rCbTt)8)-?SR(Xr(`lM%rC1hD88zLHL_H#?3k)_dKK-~aRE>9yN)+i;chRr8kbZ+q(n>U%n z_9X)R1c=|=R~6pcuPXRO{CR>DG_Dae?V)o09n=V$ayNcrefH_GjWQrd*TbmD&0E`4 zqL9e=jk=c-IgjSc$#eU9srt27uZLIdh3^ifC7HIRqM?}eabi_bZg*&gC|doVJ^ej9HR@U5ubuDv+fnQU$q)f=(OejP2>Mv+ z^Zk`^d*N(ypg)?sRtb)4OuxbD9067x-KZATq@04BNHMEskM8t2m{aaqRW7H9S3Dqa z=%Pb8IL%bkY3Lw-q0C0Vbl>B-W#xr{TCrseN7QUK8otaSm#=iY@n9WNvb%cYGgB3N z7K-r7s;uRqGH+^FgI;^17vb({ahHf@(L^YB&s;hv)36)tWvqu%d0M+(UGt;3tLvMd zS+TX^JKU=Ce|lV@`-sl9r~g^uDxkS%!D|^b*hSokiKKO&O?8ofl0Hwt+DFx0$FGo) z#VS-20)|Il0tbB&g?; zvJcNMZtbo;RyWg)D-BJ>6C!IDwzT2B`X+LmjPOYE1=C;t9WjLMxnm;VZ}LKU$RLHl zdd{DPa046FFTo^WRYk47kvziM5^BgD9iUpxu1)Vv3-rX(1~}rFxx699nDnI^rAzSO zcnvfO#UiN+(|4o)vRQHqCP0?jE3$dHP z-q?~?QqPRPX{senZ~e0S!2WYU812nIdi(qG39V<&OP}z-rc%OwI5p?)EEku(+iODs z5pX3?;1`ii#&=GXz?8>l;e;C)&v?Xc{USrs?AwrLL$W*pBgfYqA)l}bk@9|HK#dq} zQKafV&qOn4?LU`BGw;RU7;?wx0!Ui09xfwWF;aXSMH=wP@3Va{9_vGDkf0A8+A7>+ z*+JzOK-Ezb$!l{9Zm+9Gl&)UBEPFn2m`*1sf%eY6HiJ=V+Ug5Mev_j%cUXQn)y;}J{H{^L{jIWUFTVQJL}zN z?;_v@J<5KY^GI?aHvJOzxn?GjR#IIRhz;O4B8M+Je{aV8zefOW0suNO?7m$)8rze8 z^z+*WbeZVveC~%)bT#uGMEcB*RqP*z_O7uVLgB74g$|}OPpjh1B5qvsy~+GEU2x#= z`MsIrW`4awSB`{lJR2OJ5;8q#-<=jeKfh&UR2Pco@|}NCm<-5;-hUWb8r(7xwNoiG zD=o-PVm?VBe@oWNK3uNSg>JZ7Vv7MB_bqZ^+?&qq9DB#pu5avI_Q9;KnP{QJ46R*1 zuwX4MVkqWlmZIu;)Mpv%4Qx8I zjb5E{ItcdmA`&?gW1bDpQS?Tw7A=v`+Uy_L>UX=NRrAhv!;@eCV=i-Z^61KB7T-SO z6i~3@)=XIuTq~R6gXkLZCab9zD?gBuVX`|VOM2hgVimT7VDUmIniu|E1Vk8=#5#!L z!tpEE=dN49fj$s7$;6t1u}vTc|936q%wR#`>i2B8Ra&obO^0xGfB(OZk zPR?^7T$Rb;zrdV4m8r~FIR39KA>mbz3mcTQpb*42XRy(fc#t>F0!5SmBdE}F>#%0YL$xubY z!)qOmaRb1?%*&k7IG6;+_RU&WB;K=)RO74FLG}L|lFz{4?O`D3SsS1z+@*h2JAw4? zrGs6Ax+P#mz@_|jLj*{;L>R#Sb=Ovha$}kT0w3tdDi*$7aCuX_MQv}F&Ek8pq7a;; z?pp{@6n6^wmBGth0mdAgnyU_IFIW>CWQbXNkYG&X@I+lw=ewu_7$UFs#zHM@EhT z$~;HT?4YQX6D~rSto_qJQFY}0v;Iqv|Zrie1=(Huk_|!mbSJHf6SlT)<2!((5vyNc++FbB=AFgxcwEfoFFmXL_byxPo_2#g%1KiV5h&s?uCO1D2Edx4y zbD)D>yCd*eB7Z6vtAC4xjA#E|H&kumEZSU-$Xv$I!25IX^Lq%`f&t<7V!~dE?>@LU z?PD#d26B}^3*O$c4#~Ts8u3J zAj>DH_=y2zJsDa9k7+ig1m1r{NA>r)J^a$xhc2*G-`rgIbk0_xLCi4`e^VR^{8Sz` zj{r&d-*PpL^yjwV2VDSUHX#fLL@9fk!8!*mVqiS)rkaZY{*`I%w6Mp;#)h_NOMMPa z{@;RS`Xt^pa3FV z>iRMC>Tx2hG2)|Ehqtj~kzq%@$s0$L_P5cMFV(-l+qI3Vrk?b;jx7B<_A1(Z^86`` zoU@&b3RYUi@mfvUN5!z>V=Vvi%(lcN`x^#aGvecH7qCKUIAO{UbhAK)@MyQaiLB~T zlL&MwWz#S0@3MQjKM;S%ng);EEbmYmR9fBwoiSx|HZT}$D8$B1LmcQz&%)31SWLE-j>pf!l+U<*^PRtaPle7ijgHl`}# zaGQRNnl;ZA(=Ai7wnqGsSHTG|sHwl+6;0e9-TF5-znFES!0(XZ^LXZDSR&Efe<>EE zLRY|pH5bPdS(kK*%OMm(4i8QZ&Nl0j6OLiM73LPVa1vJqWC}^BqroAlh+1QN%fq;A z*eJ11QC7QyOsHHxtJ~Et4NZj9SV;D$F<;+15TKPpxD79;LyLS*rGRm$`6@p*$q78a zBya-OGL)x`**@O%zl+*;r`u$j7)ZC+%j^(ClC_g<{30!fa%B~&ufFN7mHo(03QuJ?L z+Kn%~^U!;I^3!WE@3c^EF-22?Ippzs&*w#p+XmUisrA5lI)XZg0D;_Moy8yUld_5F~hFzii>Sus@WHH&($T4oS zUcILX2^R%!s9_~kymee7^0^RF3-yYIix(5_1`$TR+6z5grB=b$GjifxZ-Z3bjequeN4R;pfG!OU zhfS3b${O92=_4xx((igzDFW^)c`4B3Iec84Di+TJt+WioE{(7QZu^N~l+EvQF$|52Xu@M`YPQ)zLA5@T!q@ zxm4y`z}MXX;MdI0g|dyA3b&fkHtd5EAM_emOF8pUBsGvC0j6eld~Z zv^n*GA)>pn~TR`dl9&)+jeg|Tgu!>jb0#*pY0d``D4f^51t4hO) zU%p=~X8kdr=pmjv&)nvfo-uOE?_5Td?)|sjLugTr-9$MP!Bpl6;8* z!RWTT)R6d`6Q-Sw|LOT@0GPVt!?;D5I=8@}o;=#qV?nRj^^%{HCC@ebVt+y+=Ye7y zyQhQUhkhNCZzH7mHe#jt`eifwk3pzkmonr88>hg>K^u3m2UZb&i!(n8J-6SIoDd4O zjZhHwy*}=>leD-A93$W3gYv|t!^Tg6HmZR#UJul$4g7wDGwPwLd5e8mA{*uc@i4Dbz&?qeXO?>mw&mR_Skoy;6uX8(VAImTet5vjfcM&B%z%j}SdzfEB0syV^3o zyZox+sn_<#GqD8yyHQe)-E&ScABy8wHbKzAK%i9{h${U;YK$MYBOj*8;!s^xDh&3_gpZE1?dL&T#d3 zb{J%o#T^Gh&{gHUt$D=YguFOiCeG$~)dX@`dnd)a;Z(*Rp6&L<)^FrTv){+Q`M;7l zUXKjIcFyWYCRnw`*{i!Ma&pD&BkswmsWrFO*_@_3JLFbN%pK>3*J1Deq}BRK`&%et{O;5?B+xx;U_6%2zCOn8OyMmmZeVpOwbDrS;wya6i@0npD4;! zDdTVGdWbqn=*f>QcEpwCzML#Kow8uq))(1R*C&zBRQ>u17)W&3I0ek4>*T^1oD=vw z>#UNKlQQi~Lx+ZDy$U8%7g~)Q-<~jwTXgjHDukzT8~$KjN{w8Yca&pL>8GXPpMRT7 zBN;qD&wA>gdv4?&$FYo=gs)vjM&M#?8OiZd%q?qsSL3BF<$F)7URR6zPZ98R5s45* z%=U{5BM%0CN0BNBsR72!iqG$ct)D&KU-F1J3V-@y%r~`{^n;RCj1U+~q_B0%57unC z{xyo2p<@^nc9HNdHzqgY3TS2qs70;ZvWGHgZ4?obq9geID>BYZ@Vu=|OMG5U`t%1lxay^6x*@BV1Zdt|D&WkZh%Y*nAWf=xEfePH_ zJ9aMBFOE-1Lj#Ua$1>0|^KYknKB7qEiOkH4P7BGf>z-N?Qh?HdCf~vt5fFlcCt1Nv zb)pZs{Eac`Y;SVxt082RG*Oz>;(C^k6J|yEn0?{ZK{8-S-USThJ+%LEoj=82N&o*R zVf}j2r=OihEoNe#HI7e7?yG0fM{b~oOu`MTC{{TH?FHF~HT%N8RVdDOMfcz6tv5Rp zqgx)AbIM{q?3m^blT>bbVqQOPIroQiC;Lz1g7d(mTjz=es4Qi-!qh62Qx zlk6oMna`gEz9(;`?;1B+_Q?q?W=a=aBPclDdQpEUnrmRZhRCoUBLE|!af3$-&)hJE z3y0m~b^kB{;;*>y+Uj3^u<_5PA9UD@b){XNO~%QL60nKX8elt})!0(zlb7}+J;PAt zU=DT7xsFDgmqTN?ccbvM(!Ml?jMJc}fBMted_t#t1Gb#$fXPvzfuOrxABV9cAFUQKtvRBE>I-3+(K zTu)e@;APv-s!7QnUrwPfEDQe0hIml<|U05#sZLd6hM88f69jch1`EEl;%T(C40&OtdS ztFlVy#ky$BnJ7{hlZ1>+w-LR=XcVS&mW2-3*tQmG*-B`LYlAf2NojY9zm=@J;Nz$mHFB?3w* z45XF8aFle2zCZ8#e%|+a{{;B#cU|Xop5OC0%px|&fjCM2fEc#XS$wGz8o;Iv2=S)p zV<~qQf^PYMYltyw-dDuOqiG$Cf)5?Q+@k@ zlHIxnOymRcD0*J5tsR->M5jVyxg~@2DBj_p z3=@GA_A~NH>;*5DkJgACtDsQ3oC2cvLU|>R_PB?I?nUO2$i#8b*W|E-zM{QB4W}am z^LT`ZmI{xa{i=$`tQcLFE~7GVTm`1hI_4M>wqE%s#2)YZpI{!i#6hzA*&Zi*Z+!*2 z?#@4dt@&9}yHQx@QrkR_&VI(dwn{S=x^W@a++D{H<)LBqr29~Sz?XU=kQ%iwzzo0+ z(Ri2CHCSw)`FmvN3o!;5mZa{cCmrX#w<87 zl)IS|UB63y6MBA|5Meq4!`>&_8*Ux^w{yhh_1`d+=Dqs3)3xDzpKdoH&I#4anwdnC zr;pWG%cGB+$#rSMLz;mKvTwRyKVM<=WXIYWi@wnqc?wpp_o?GnhO0m3zRO=}z?~gX z1*Nun%8D6xHTJXO+g|_0?Eibtk5n}cHhLsAsgCOxirAWFZFF5@%Dwvx^~wEBsqbV7 zl_{{Q+TLEyluKlpeh(?ZJ2LV`@3_9bPR_CnOF73MdKC2i`hEht87hAjWCA&X)J9~XtKK}8Ljr^s!w6QiG=3#zUsDgcXO2I<{^9@gD+i3{OTckP^wfs_f>+vB`I5NP@}d@n!LlW@MV^|i zJ=!rk#;Q_-wc-7<_8QABGX<{&;Cb;a$S%E4p$<8%ZOM1#Kt#O>KJ*Z@+bb#^Mqo&q zBPchY$7hC@vwT;2YZxa+b(7RZT@;t2E>(^MEO;TI^(F5aR~rxdQ(r$I!}u1{j!%{M zfK<@jTzA<dJ|-7i4;^_F+&k3iO9UFbjg+l(Y8Y3DRBMf{yL|$mD?*F59znf@pr-uAKy?DdnzBV6#3JX3?uirhy;^7 zHg)Tva}UW1nz$V4AS?=+ZzHWau#WG1h( z`ThG`rvCNM;$})7=jFQ3KK)7+$3|T@0HcoaQ|I4XsE^}#O@~pNk^zX1T6@Ou7>zRSo`Gt6W%6)iONJp1$Mxe z20BKD^&j8gS2fzxZT$Ft`oYDo97nGNRiXJ_F*(JoZgAhuSGkQ(4yrZKrHbBn!?PDX zdR_rKAQkt_nLwFm<6)MwUv7n8g|7w7o=PGfYOYo{HX5g}UisoMJ=GGwKGZU~err8V zEo>6T?V}t4XB^CbckxZo<=j-dKYr3Lw(;sR1>YVCp}%qOouA&`UFX(Tp9KkzOGTZP zAMzBi#1;jyn|iJ7ooPqVH)N}>0wPKP*CHcpy#BDdds+XxZsg73t{QIn&+Ymp{!>kC zV2Q5*h{fmkIh4)T=71p@$iJY!w>%XY4XB48S-AD`27!fB6s>wd>mi)OxQk>Ghvpmsps2<36^PVljm>e0RPZBy68u|ueU zZsYsI6xs*m%bd%{06U3kgTq_KiI(NNHbm4!b~WL-?nlwcfL@%w+&wrk6mY3<6$dE~ zB|cXg0>Y+0@ZtR$^yDS&?XW%%)aM^sZUXK%b`#N(`aQ!jT8O_S9e4iBh~J{cSfo9| ze)qLVoR*WNH4%soVpYvxq^SGIz@};szfJ}`=s|OHm)g<9lKsVifiCUYa_Qq9gCxtc zd}NqeA&EgnpLmz~4|pW1WcA+1-!L$$vd5$I*cSCX^(B`nc@&NFXmKLX-Nfigd94*k zop-S^yNcwxt(8Pj&c&4W7oSs*?@9<+a~>sy8dUj0gw7Z9`Gn1~BS!JiUWSmGX#uYM z-9l#-#4-ttixvZIOZ&FGEI(ap*b?%~!KCXG)aj03%|(QXtX^$_46?oFpuDrDKjQ-@ zvc$5sDe&)j+D3%}aDhf2yENm^dmBr`3qN1SeOC0{Cd_Ts{Mg)MzBrlAaB!5hqQ&BNHpX?zs4TS21gA6rK~luyBb=x1rmhj%K@~8Bs2e>Z06WS`(y6( zLv^eu5=@Rhq_(LvD9T6|PX2cFf}Tfel@!x|1+Dg#fNqVpY}}rH{uJH+Ffk(=>)!ZQ zD%IBe(9g&U7`|<<|h)I!vK*Zplq` znFo-~#py@;ZT*iMH+4x=^j{FF6Fj(v=s6b!a@kno!9rPk&dHXQt9h@wk^=*}( zQp<|E`Gm+^WbD#hS*k{~MX7B}J|!&X%C#Ld*Qd#R6TA?ya~u}Vv*t^PZ%PW5j(~LT zJbMLhE8>wd6~8?s`dV{@-$+p$j)-~GFE9O2eof&gn=@QJS5kWYupA#CI#LP{4V;i_ z7hUk&n$z@`Sh0H2E^)Kl*@1*vF;~BF?-m+5b79)<08uNV2_KJ!VGB;1$ zaqrzklyWaZl{O7UDn*pGo)J#@Lku>8HM<;gDRS@%{4nCT1 zwAG0;1(lR<3-WzMJ50~g!arFnZDgd8Jj-B1;7hQHRJB{1B}HDJ+S+{GPi2?_3TsySKF{Eyfu%!E`sX)jN$oPO5co#z z63x}2>DVWX-HT~9VC(>HMuO6UC_BH0rs`lcD;E8dU|+U9DGJQl?4$oY&>e-Qm{)Ow zn&&zY^b{}+z(olfwwD6t$HQaUHy*6K;2XX@TZ;0qubltz;s))p&-ZqkP26ba*uk75 z!-#p$$?(AdZ-n`B$d89?fI!q>{Y`7Bur@_o7?I6?I{j_e{}&D&yu}G@$DghIy^I{A zk?gcf=a=Vak|u9z@z6)ccU3JeG%b*H=IMwq<60FU4v!H-*(T zJX>W~K1_$3sJnY`eRczse5{DV+U7*Eg%+FI%?WKMXByjIgCq?Ac6DUI6eH8ocs2#q*}VQZuH4xp_z*8PlCs)4Z?22 zOY~pj=)0D_O}h-QXqdONu*f`QKa38=Qy&NDm;L^t0sOyF9wGt$9UtE3#WG~cllEUzMRw@RlI_v)Z z^I}p7mfKgmb9 z1r#*NFgf^qKnPuy=a_{4kk2aUXNjOE+m)NF~ zwiExW1WTA(i}hD$eg(T5JOY?@kL9sk1;y7StlkgmQM-K3tBjg@M`hds(LKRobBj77_lgD;?ld<9xzkVVtnSBdsSm@qfKdfX3pyv}6cC@n0~+}I(Z zk5pUI4w6EbKChtAY}Jpf<_ie22Teqj0-@1AXD7M#_@B1RPTDG~@=xi_KWa}t+6A)z zhVlv+@m-$If;?c}z!c%Iv8vFsG)pY0L(Td=1`xE+apm6#u@|(x+w{06(WC>v!{2T& zVH`5OcQ-TvQbR(2vR}$-_VDK)zT6%!yoLR8?e7u}Ur!5dn{4S2V zu-bWO)W&kQX;kPptjnbqE@o#iHj-`a!|Os6#s9!|%2h=uN@n+Y4uYsnYY2C8rj>Y? zE@}?z<<(S<>b7M5#jn4Ad~eb*y=pZxuf(oq^P2m^rB4q`_;S+|6UnQfcY{0`KF>7I zgSqS99CFFmR3~l`Z7fLh*`M^XzVUs=eoI<-5%Zu))h7FXQz0`Q^*TLzkx&!*eze%* z*9pY}+nYgBYmtB`(8}v!UwR^nUQ+K&<@Tzm_8^`TIO<^P1@2!~(el-_mjd5`1u2?O z^I=CJ_?6rzy@6b>Vz_h<=i}6LW@BK&5_=nFFN9plBgsy=37@j13~4VOHYWZIvA4d( z*$I7XU)D25eq~KgVR{{ZfQxBkA%T?>uO?*N#4u^8Cu7T=OB?W(?q}xvOd=sKJ4E_a zY2VrOsg3|S$(!^K_PJliiT6k#I#h;xCTlf%b1mXlL8w0# zfxo%qcYj( zt_&i!p$?`FJ*EzdGEa(N_==w1%2cpFkkhv@k!^hQt=#a3kp73Puo7Ahw07qQ3;nZ0 z)&v6QQ|)2yS6W$w)4hM%N3pqW!;kYGS@<0N?WN$48>nv`e^Wh|x~+A_#Bo^*aU=ED z9oNlZ%ZLTv_N@)RgI_5tLcEt}wFj5H9hQGC_rm*iXf7|XdFP|iq?EW~it!i#WtNqE zqKx3dE2qBv;?!vQ+wnUQdSgn_HAL~z>f=Rn||yv2ks?24N#(sLI;_^ z3K}bvg&ej_y_!va(cwVKby$%v1|_tLTP@C0LWdcsgUsw#dC+^DCbAO`a$<Wup2TOt`o@{oD zeM`ZEq2H#&h@IFRdx?SNwECN6?!2Husi@ePfy&y5hwvuKr2ZpPMrHgy5E6Id%df zA;h*B?2oCHLBPtf#inXyoU+!dz}uU`gi9iuqhJ&TD;uy_NuEiepZs(pw>tjPLDq$+ z?Ow>$%m82r>pnk|(%lxdcPz1~3(<-Nc_ZjM4LkS+pZ8ts&$6}B20#oqhXSl2KzPDj zs$Vc}`Lki)_*>Yqee>8TElq-;qZL}9ydwV_5~<`JcMD!br}c)D*T)Q}_XuX(4|T51 zGaY|Yzn%3&9C3VBBIISRzJdc{#K!yID(lJMnR<2gg#w>$ih#JK-3u1|2~y{0!rnkk zybOpF?l>OU{#{8KnY6!k{7gQ70r&dWL)=`0qkqErvYf~dJ)IKD5shri-<2+$aMbg_ zpP|hzpT*|e{JK2nG1>r5&r>k2sxu0tl2mZXUAgPM{rAnUc)?MxsFYZ7hDWNmb9ZmP zrWfJAXfuPg#I+Dxaht~&Pw$4K2kTE8+)b2oUvUJEQP$&PPgmv7mWiS@%%y{Vo%3~s z2*m}l9ReWJ8CUYk>Prm#?WP1$sO>Y@HynIVhzn%eH5$F30U86WuqOUXZwYqe^fS4mOaQ&0G$pzdD{*R_Wbee(rMx3jsN#S z?RNO7R_JQqGu%0-Fw-ZT;Dbw21md0D=-|4%o66T<%Ux0mz#;Bk_TPRw!})$W@^;U^ z#pF%ZQ)R;Do#5R9Zq+c0pq+2dE+oJ%n5ZzV7}VPvZ5PTniH!fStkSVwoa@S+`eT@0 z8Gk2GZyX>3KyY`!PYrmo(;udMoYJK91lPgt290j$TbD)dAoPP8tZcn0IGZ-X85>#j z`T5l)C69GRi-P13wbc;b&^K_{Rz+EJGescMvqROdm3C5)p)rBCXlE_FUXK#hW z00eEnJ9ch_&GDguf6%uJ?(LCWMX{l;=z9T|q{c3@@|MQrh7vFgJnGwV7f8)z@)(&o z0{D~44I3v%=ZNZVhS8aJJ~|NzEE#@&KUHQR+TBd*o+lj<+R~g9So86zS}U>as~v$d z8+EvtKHqpQRtWy$Pa`0BA#>{VuyWf7~27RJD@c3`dpddchFwu)g=Q#`8{lT2^&~%r3_)i4nb6V?b451h|A&B;Z>E_SH ziCffoxAor}7JiFtt}?Htoqw9;iwg?4?c!g4nsUFtd@ zf59@<4e<80(?AJ}<%$Jvc<3Yq$3OSsa-ZYTg{XL-j(LOA(?c%9IqlE&0X*d%{r6Q2 zSUV}Q*b#sbhqy5oEj^2M4u^6Mu(pZFmc379(vqE=bc||<*I;IpzXt4K`1d^@`LuvT z9LChMzA6UN;Zv2H|Fk*8PkJ*IKl@5gst*jX`3?oVtnX*NRt$UxX?p*T8T0pj6qC4T z!d*Xc#I*b0L(X2ty|ZOGxtGP6!H!rs6Xe_cB4OP+2H?=w(H*-oc*MrM@OpmasrkW| zq6h<<$R!PsJNEA0{am-_V>Gd=tb`pP7V!TLNBKz!XOU+wB2zbuA|rasKIXWdX}_*3 zhXW{pPg6MPYKzx`LpuKtC>}Ki1w7B^ zHY3c)qX&J_5EeVFcFy?UADVUP+Fss0ePZR1Vo&NEN5nZwO~ghfdC?IQeL$`kT7Qr* z8%5OC&se@+YA2sF3Z%A;;yw@>|3TJ~c1r zua~imOg_K&Fy)u&Qr!&%&(Sfu^={uv)d;=nqWEcqUIbyeotXFDke{u*(ix7Mx{UEulV$+7)+JvQ`0xzST zVreWkDX*US`f{e_ zZvLMc|Nl9mQ$B|LNK#y{`+HG`8xby&11fA$|H=CUn&ymc*Xj^}iLy<>8~Svz8HNJ5 zWIXrk&69bQ?ZmKdIy4e2osSDsn}i>K%>6NpJ6qFyjGJ}}U6}Q{=qBt??=?CD5>!w0 zEz`7%50@C z?uZrVJl8<39BIXjym$-~ z&pglXP8LsKw{Qx4KDq1bAVS2%^c6((o09IC_U~x0(Da*PMqPvJqag3}q|bc&c}=}g zQLKokpB8VGMG515ZPD`bUM+i#*G>cvT)MBvx@%*np1s%AH#+K#oaXHeiG0Pe1e^+H z1#=YYZR~hL#kO~Ox`(~$)G@!BZSXkqXf26* zXMFGD`o|y61uwwiuw?mRtWM~87m}YA%1Hr5<)pn^U}-akj|AKUEWtLw?>9i2EE(Ef zoER1>%3wMkUvGhh@qz&DObCE2>Sc4!wnZ?GeICgsQR(@8|A)pIXHAc|h08Tx@)_Vy z!jek%@GOo`XA2?l?pR0N_%#wF8ZD^ne4g;6F=9YyK616V;BKVNZlA)RUoX}T{vPQb z#PWtc{2TZ8=2t8-7ufIH?JznF9Qw}=U)=u|oKlmEpWOS=jI~Lx3&V*ksDaAG`y#+T zCDJ*gxLZ~5+5vFHfR%oX;+;)MK1*myuH#t*n9>^jm=~)QblcP_WKzg*xm1pvA=_Kbh7&WxYn!+Xn z5OJ&t-KXzhO7;tYCmG{qCaHDPM=_r`>OJ|8=$_mx(>(RYWD0`8Yw3YQ>Mboxg3rEB=OMmB#=jso43_v!mBWlC&8 z-_0*ggpvF0=RDt4C%uRr@?x;)W75o0XV>m9#}JWG0&BtE$>3rS|9%z%0g&B{(Y$ad zMA@&F>)ItwLrf)kWQ|)*Y_5g)X%H`jMktDY%8j!sALdZ%A4*NrsQY&(6J?9buD9m0 z#YlYp;JSa%N`+lO_Tz}CSQ8!1OqEn>oZ5Y_tb199XZmtTCGB2q0*lj>(C)9Pn;V;M zEG+aQk^-IW6ol^9u?~(4W6e6aRyI4rB zpe2g=rr@3e<|J@WXw~6rnH%woSFQ}jz}^S zm%hLAZg#NAn0eAc-;g;yEznlK{{AAOE1^Q%bHmEkh=kb~h=NUfm*-Hw%aK}*u&}Xl z7PJnd?7o#cUp`gp`(^C@^qBd`sPmX}xNVQ8RjbW~S#8=ewXtkRhXpfa`ObpV zCi;fi_~?0y0iOp$*K-B^K0amtvs98Le*JD%5~j+3Dq>L@4bWvC4e-=%TaEfQdU4{l z;9Odm*yVw6&g9`L5C++C82FeGVPeEUjO6g^A~sE|1u>~Z7j~1ll%3y00sY}H8uRxA zKZ=hOd9I96>{NG0R7VqEfG-wga*F3Oz+kWvpiWK=SA$Hzu*2l8NwTY)3XA_TlLI2c z+_Kszk2G4YicL&EXd*E&fH_JQbYnL~bsEwIv&U2SWxbH3A(iAQ^>v;Yqk72rKBh0c zJDVnz1d~IkX{%c7t*(!1gxIRGn+|Y?g%SlUwC!ACh}s;UMMQLi6QQAiBlM*7g=Bv= zCjyA6@0ScR?jP*qG~A^CE(q%@sgSL-Zi5X1WUHhz_57+$MB`lID!FpJARP!?k7zQe z+${S0Tlc`{?}-65bVU*0Z~9|XE%M27C}sKBaiBfl-`yww;^hBdnB<{dF(UkOVI?cu z2BE#%^EX0vN(qin%{0^chmHikd?&JA@-k&+I!f4hyKkLP7v*RAKkE&p72d?KL2X(F zIZ=g7k3F0Du7GUS;QX4EdZXEz-R#10ai^(%@2#92TDd56-nR#Y%>y*@NKgOEAWd7t zhX`_@)9)XrVO~EdMFK;2GUD^(L`|)#_U}7TvxltmM^)c+)tVK~3#BLzV9qIWzb!=W zC&S5g9xb($NMzJgh#qHbdbCq;Q5 zv;Imjf7T)7#bEey^tq2;YK?D$TQBX%>gf@y!tAV^2>T!4b1AGg1X0t9Pq7(Q{0qevB90mH-9Q#q*sCL>@j@*g=qmJ+IO8p}`{`V~cEo>c%x?ATL zbrcT0-aJO+IjGbgt^^2e9wa4Yzb+NdotD?}IfSm#IVQ_}wI;NayuwfT-^7j5vUbW* z0D{{K43S*8Cjx<1&2Cc&(fa!KB?5QRtV4^Df)E!%B+ev!(#UJ>Q*O)5Ma7Hr9M{)JiIZY`|XJ3Pj1fJ11XgV7c|bi3ENrD_U1$S2qEwe+FxwikL~(t3{yI-&`H7 zDy=U@b%6m8*COirje@wCV>*ev3^7IzV;UzH2iW6-y33-7noYHQm$jm0P3j}JFCy7%sf56}(Bj{1AJbsOr)}@C zV3s7&`1A#3U2S79mR_Z`MLWQ;sjS?^O2(!_JJ^G8JJxy}R!oBg;lDL`w5kSIb}uW; z*Gx8}BWpFxgRxAxYT1pdOwLON67*2wC$Mko_?OoE7Dt??=(g>L+moqz2o#UjjSthMk7(qb!(c^gSKgLz)3W zWM5-Hu*!-Dx^sPhz`f#C2vm@tCv6!diuE~=bkfXTsYp3=;Z!$og<#)B#jXJ^CUN+Z z@Px|Wn%`F|f0IbCDeH7eMIN1pY&uwv=yO0K5mgr)jn453`@cdV*V&aoe?G7LPP%ve z)x@mvyT06`sMvDkpj|Hxcw7=^(q!7N*ld449hEi(iwl!sl1Dkn!LunhRBr->#?<}b zN@A>;J|?twrW*UPv3v~BcY_r<{0ZD{z3QbEmY$IHtr=qr3sijgTfHyq31sy3eOUz~ z7SZ53@6gr$!Dzc104>nc=S45g&{$NjPW_|D(jRVWkT>%8Dd;c^Tjee~alC-tyRv0Y zt10u{CPPXhrG&2WsELl~&@!jxe7W``nwt>l5Fs8#J~_9n_$4Y)siW1Bxq4=eNwY5K zJhUT*?ch0O-HCEunJ7FIIr@T9h!-n%cij(23U8S4{6Gxq?YK{4`9`q!ndO~7&Hc)| z|1_uXL84F+9W_jT<~VCIjk{EAvSZ-asuGdSr{lry!k6FWBho&jhJqK-_3up_vq`=@ zE{5@WfQXvIJHV`kazWxs#7|moR87yZCcHu6c6W%dX7i=>L;iI!Sk)xb%af03<6zNA z0j^C9hwM8&ON$mD7lI84zGMsEdDB7rhidjpnF?NO)i7PC7TjWzV<^6b8VD-78v3Ky z^vZCB?IsYk;3dM^slWmt!_yDz>&CniEv86eHR%P<@Of`HP1;FF4&g@rlq^%vw3Lfq zEcqe2zoSQ#Uv-r25imE9fI1qM{CXiSDF}x|s8Mh(-yhI_Rp2zraRps|MKT0@5^rIg zE>$RdLF9!6DR`8Q6>|-XC5N|PyTd^domj3oeGLLcI+|Xk+>aNvq3UJ0 zPU$_HpNJ5$z4~d6n|jDA&rBzjS^j?1dWh5%D=tC%4$7qf^wYc+_|y6KR$6uGZ!B&W z69%P~llq4So2j9~$vm%bQJ#)?s+tkt9M<*b%gH4+*Ww6;XWqVFfh{~BQ`%5j<0Z~#u{Zu5>j7CZ3n z2%RQq_E(O44YYY$hqm-t2N9sV$ak-Q3|W>2`k|R(C8kKo3Nr|zC(W6EL+|_=Ne;v5 z?@7n)_VGutR3XB8uS`-uHF{-0n&02SzpHhtpO*Ma#snpbdR`E&uFd!O^{)+<_!1?X z#-@OsOYesx-`-1?xwzpmChZE=XUA`>S?Vpk7uHEWt~5?%b+mNMb%i$#fgu{6DKT?@ zRPH)^Mb?>`KhYk4&;8aE|1)QXPeu2c(*Wj}!lHNfPuJyb!;T!uIXfv8LP*J_r|KZ)8^KUI*zK+Zd7}4_>t;Pi76>4tTCB2&m9MLu8Rb~&v{~FU zl}rn`P`+D_cgIY`Iz5zct|JD*Fr~;^?1PO5ATGjsHaEv-Nmk-ps$h z)VjsgF4iJH=KCn&5to}hn23sB6`hwYge`>P;son|m=*tL^Wc_L_us3%vFz?6L15+` z^XJxZdn%JS_rkI`{Fjocv<^+H=X}{@v*1@poBBeSYjQDvt;=&p;lorRX% zomP|f`uM%qLx~uX~x7mBI|L&!}WVMuRLS?dn^lJb8SOBIDd;;{d3#@RNBV639t=xh}Hf3Fw znGOwW4of|^Z+n_Li)f6Oi1~3+2JM}*1hZ};DoPtq%5EuXx76P;{8y@?S!Et909#ae@4daL0Zjx5~PYC)MLixJjz{ zP1Zd1)(Q7?R+X{iE`_{Ca?cx!6J$&1#Z0e-R&QAmQjFBOU8ITGOI;_@$FHf&x0}qu zC4|&YCUG;hed^-u6%pjUiD^bGP4WN~cKl6}Spp{=Okme$i+@D;Ja|&evJwJ%z==Rx zZ`BkwWxyRkDYC#(;3s3+H#SPGkK<(hN3l`vj7w@h0RDTYt82es`i~6u&(EXP5*$4e zG7A^nFtpV$fS3X$Gn&)sUyQTSg&9okJeTbtvjYHF=%`542qCNi-$Tiu@1Gd0 z#xel@SYrXcy0|;v6`WF_5^T2HzS(&1&)L91W#ob2`Eq2$@F>m7#e53x2C^=A<>D=Y zfB@|y05E_9i1+{ZgVt0Pk@!6x+Iokm97V&=)v5$yVQRljD$$M63z zKo4?wN`o>eCHt*Ek^&;pC=dV$>&S7+X40gD<;}SrtUzSYsn4l#uO##IQPdPfT3=^8 z(&j99=*8|-B$a(N3Ymp}f?Rj=B+Dm%mQKPx`r6f$>3kpa` ziS@KTJxMFPgPhICFeQIUFFRz>+G1X6KwP;pbP+LMvpMS$rN`%)i1xAPu(7Q+d{AR@ z&6<~y)zLJK8E1T^JCE zu(mZvB{o9(s|5wN!q}L?Mi)mb2tJypib5k@(qm5N%-yJdz<>V()c#GmywQeXJb5@gCY8X2}z} zu5mt~cGejNNEEbep6yT`Y!KA4T8ZlvZ8L+H|Ge#=_28t2eP06RjYGZS|5q+4m7##9 z=eX7EZzf^Oc=e9orzo0C z8g^1l(2fI>)dtyuNY_Q4iprStS_wG!OM|+V^@b~iV+$uH`qp?=EFG#}&?uif>Ofzp zmjOJ|1)|^ zz#xk@Bve?lKbzfnb^}GT%FmfE$AK-Iu2frr1*s;k-C%cKL;k46)k4$Qjx_Z02J2HsU(OF6chC zcv|eS$f{IE*AT;0=Zd$Kd{F^L1zrc9do{pzS!s+wuG#fkSh zwH!C}^xqQ*w7_#CS)=~F)SY{-;|Gyy=rc6-RL5^l8!=*jlHqY&rZ5Gl}xBWEP*qXGJVw>i70P?qNDQ z6>nXB_g!hu1w$Z#vn3UmNhz+-YnaNHwCM=15mcCrg702?IEs*A`&w z7O0wSUBvQ}7Wxok`zUOI@?m*-JM8CEG5n0&BWJDJ43=zbneB@X{L)C8sP@~mlDhfn z>9UnzWTCD&YnYjKgCLJw&2WWz zN?%(2v{npEvr#3W;;W*38`D6GCB-B2zD%Cd_6r`H^Mg}sH$E|Qk(f#OXByURbsj<4 zP36P#Q%G6hVFoIC(KuexFOv`917`9}%$0d*W9>V%4&U`M$!l^-#Yt?cV2-Sq54qD? zc8$`IHNZyzz<_mj_tIN86U z6fjGi`^m5Y@~;kv6M$^%()U@>t= zF|uUx*d%n}D|ll&LBsrC*W%uP19E&fc>bmQ6MN2RfFgPP?jCJEu&@#$@egQCivQj~ z1hQ{gS!e*-n;$zSo+tmkqUolKF=(nn9dca@Ea`k*Qucca`swU#h-lTR@q3Tno=rT zb<@r2f?gMR+oS=j1%cw$dQ%6JL%!Kh@bUO3hnO(Pl)}wL}$t z+%Up1w;v;$)z1i$53|Hisoe;d=HeN(MrYF&)u|7NoDqfI#zYH)S~1O6n7s|1CpcPU zwps4y^=XOP>C*j|?*h+O`DlD9`V=;P0)6e{s2gcpR!c9QWHw*i@X!}6 z=MPjO4b`p#q#)OI&go+>Fk$tTz2BfkmCqi7emN~~8L9YtJSS3uauV2tK%9{riM$!Q zIdB?S{`hmla;*S4a6KEjc0sK24sax;s$D0ZNKaO9tVaV53ginBdOt{zM=rJdGa{Ryu(Qf&;Q?`Gy8vo z&WsGbgkiNm4Zi{80_xt`YAoPHUjO)-_zD`E38Lsr46K6_+nCu@P0*bHOub}|#TqpFtBgmDhVcrz|B+u}+^|xDzY(ehdl?|+{a)DyG1flQmPDV;c z3DwFoWz&fh+TRipo*Vp9P`8$*G)gVsVA6{!kRpMiCcOkoiPFt6{lH_TSSY88gp9Dr z3o0s^2$ksvoESuscz5=`^TB4c`F8t3%)w<;Q@g)W+ zzHWheRG!b<*{3F+A$|wVrMt)L)@L*@*>pJdE>30 z+l?}sx7W6I?jX({S!_APIE~U^Mc^p>YnF6FbHX1-epkfOPfkuCim_`dp;8#IY4|68 zrYA8p4^TL67LOtGmCmhtwSarg1>?12k=juopL=Z4Q0Lb#hksWklbTZ@HK-L`CdyG^ z=ob-iJvtO)VHJvknBQOHbQA*#B9FpQa5|31xhP0BgdKG2?6dFd*y*`2a*)m?^xOuu z&I!l8K#f&HMX7<2xrs5c3%Wit6O}D4f7AuD*#RiXFn1-3oP+Y~g#w{d4qMYJb2?Yg z>fOeKfTU3|wCzXC;Rd|_x`6k?*GS+gJYayWRtx| zj-65Fp*TilWgL4`WG8!tjBHArgJUEk5gnT(vtuR6c5;a9jEv9gx~}*4_Wc9=a=f0; z=i_mo6NDjX44_)?z(gGZfb$Q427D}#{(t6LNHl<8CU#x?M{%@2p)XaK{Q2}?oq)$6 z00%j3TxGNO>i|dN?R`KTyKR}vDjql+u5Y*TqXp0%-Cjcf{^Cep-}mh+dEmCi5*Qz9 zXK&wCEi5X0@GjZ6L;}b%q^2><`<|C$fs7H>1V@f%)>in++TaN^}1^)*#7<@h6O znG$;H8I4?hNAJd7MtvHe)!IsL2Bb!*P+kFGe(N24;Sw}aE+(tY{Qx*43b05=%Q|-}n3jF}E7227;bwFsKCR6d z(%X7MrmsdqW5yl*9GhWY^G!66BwoU0<9=A1sEn=4pD@96!9rRiFG*z~jN}c`yxv~^ z>Y7*8i_Y)fKKMB0MA(01^)5X5&M|1$TIcNpFYyOEL(G^5@Ca&WZX5{y=vb`#=y>z5 zTFYomL7hZuAw$KxPT#aUC7r+g3+38S)-SI!AGW!^E*?-ljk;$q>1V0<|=$x6diTBGIdhs`9874COPFd;DzCqNC!rQqQ3ZnnEy-zHQv4v zRrNLEjjCjJ01qlv#3T?6)pn5}!(t_NMZbLdeR{LF8ul5d)^7qa=Oc1dG%(X9)MXa< zpn-cXha)|I+*#yh46K6FK&#l^xOCu!bF$MK^6%SE#+n&}4TZOrr-z`-xVP=niexBK zeV9obNH*2?2DlqgD?ZK?Q1Z=xAKk^#1c7d?LZK%k4@T{wIC&(eACSRDAOY4yDKwx= zdVos%q2oKFLEIk(a-@K^jHfbvb6R)>o3E80pR)||a{_L}p0l*yu2(S;{+GSVAN>i9 zxBn6m`|kFq&HxZ{`Ko>IKf(MnQG&i5dyG$hKLomM081vr&B^~MI?`_bZ)hRm;jRlO zqZms7T;*4yU)2u8K8BxiD@U9)aVq&~@Ojvvo1{x0q3CcwIZ<_=UL?B!=}Oiyb)-*$ z6nN5qeO@!~`Y37#pya7knH@0@D%BJ{AnrvN3sqPqzBv1Akq{60O%NA<$@k<`2*Xej z4&*1iNiMYNyGPPggiA=#HlWI7zJth55JPF?2LLig;tbF!M{>i&f-+Fd%uyF4ni;sS z4AO{|1!R!L^%#NAg8;N@GqE`;U$ogDmes?Wx8Eu(EQB5GQai8*9JeYepBdiiP~VrZ zsBMb41?(}1v@h+bYs8nTbA_HwV(po4W$M|*`S6=eaKkUmAKXCHeBbv;l1#jkoK~l6 zr>Zw9!fGG9v(7kBxwzr2aE9<=ErBw_A6$NSzA!2XH`b!i&U%pL62|7I=asNfTwU_y zLu9_rSv&l~4%OK1o}6d{wu^sOpDTegq_TN$>wA1dLFcWd?{VFh$#?#|yWdFa6=JqA zu3dj-BIh$`+Yf)5x1!oZF=8mxbJjs&)hLp;t}nk^SX#`IeNkd54I7_q*1^*0sJ$bx!lDmgsCmQlcK#vz&+=1{}iW#Cw2>zt@%aSHm*0kVal2&4d^ zZwuI%R5Rk{Bo1vsy~?a_YBsmRt1OAsDy#rKGZ(uAU@G-biL!Du6_gKJjafE#BC9XI zoqem%o_`uLyz#zrZC^EHxGdu~Z`AJ4`kH#zKPg9|)&@|&w-mI^(D&bq{U_!Bh0|uq zu!VM9{GHnmi8>D1CzfRl&a+AlCNqkReDwSMt(F$|?XSM?6^GSi%a7Q|8s6w@8kYEv zc(nI0i=3b|@y9m$_im)66Qv)QYN}pO-Q zfy4=Fa!y0RfI>?4rJ)d^gu%Ly;kZ1yRJq%JC{`R(q`?L_v6qmLJ*wLW?)SQ1n(K}! z%_RG^#;o@ku&nfm(^PhnM2kKUxO;EnQ&7`qHg+BLf=-r$5M>0-PgwSdnR99ELR0FR zpZd&SLbb)%UH(p=Q-7<;>oO7~xZB@P2D94QUjHDVV6WqrZ|nb^`>`I6_WlMUg5QE} zpe0m>6jD<3g@hDFr)qz;gI`^*0?Y~QT98{3&~6u4PZc##rEmQ^ zIfkG*Q}NX{Al3##-?1NH?@}h%0#uXc5;epqQ*MYWl(C?IzBPDd!K$X~*4Tvy5eVPs zxDh&bL$&0`QTQgliw3IFR&H|zIjpmhm+cGoTSA3XE)sm`(JbvsR|_SEpg7b^R(i8w&bD^@c0V& z&!9rci=bSAwWvzHU=Z%xp)x%s7})#k{Y|VXwK0L)vmZ_W$|&zI%=_eVJ51#I_dkj`icYXj9;nt+9000NVLWPLPG#^_@ruHh&{*hSa{dtNPc+p8t;c8~8wPH0;M)86OQ38;^?Ll9Hr_R+Z5-EahKNZ*CeG>eYHVfx|Z*%6}wCVEan7 zf?i6=>_{=m&>!IfR$51YUNYqmX7&v z-`1L7na%?u4HngROt) z_R*qF_A$>vCh8DolF&q>XuYmTmv?eyh&?Fk8y`xg(n;a^k*LcmIow%IFvL)EPwv?~K^3yA@3Dr4y zbq4Yv)a-q`FL;I5WxV+*)CW~fP0`}w@`218_*~b+fa+OWKFsnO#qi^Y=pL%!r5*vH z!QZ3FOb|W+DuisJtYGVVJteVScagk`{YE%khA3a@9&Umi+JAZhME9QZ&eN)Vgv zqVatp*M#$c%rE?U2qy)%!%z;nJ4bpn*VR&Nl}}@PG~6jf&Pd}}IF}-ig^OUhD@PEK zT58YN?uve|~bLodq)o5k(X(OzMWEW`dM4w;S zU!C8IsaxzAxBf#x?7g_$KK9xTu_N9fn74?~tOWS-3qHel(oP&|QPxFGGe z{Pmu$wvx_3|NXNj1M&JBSmgi?&kdl9?oY*0;NMq_Fk8iq<&NKnYvT{Y{;t(ImdAvm z(Z7WdGx`C^7;@Whjo%h~8_~no-_CB?x#6|0^4MD&>QHTW=30C!`=7I#A`o!}9w6L= z+=N(=*N_AuVHBfZg94*GO$m>q;W;9|T;u`?1pMK-kGSZUYrC;O$d|;W`Z&wM*8@p* zUwr9H;uAF<{pBB0@<}g+LZtDL6MDQ-3J58YJ~?F88N9ZL7O-Oc?qzL3*{pZh6n}r5 zmNxd`J9DI^Hz_U<*pJA}>eA28X;H6TA=lnkWcu)7wD<|1_5La;(y>EQecziHkttNu zi6oxPUmk_{ChZ?RQv|LwnNW7uMB>2@<9&59oSN0{RnmlfG^6T+rZPH82l6i_`2HOP zxLd+bgYxEf*i9BDvDzZC{nc{YwCqrVgVJC{pqMnLB%Uy&PT@y+{3&=_B@@9aV#Id$ zMMemS6z@XqUVtbRiKLCzXZQI2ba;e1pS^wemUGQ|vYsz%97Q*@AvWvF68)i)OsZcz z8HKS&QfwXm1t_NWm!m}w{)(AvaEUpA5+m0Bntz79+c@$ICI|k>B~i*eQ8a~Zh{17$ zWLiI`UepA)6k7o5CJYzsn7_z3Y-T3N*InxZ)npFHl4cNtn?t>^Lbe}hb<+UbPZ+hDR>ThN+Bf5;*)s}28xY~ zhLhW!w>5!Kt)o;*4Cr6+qB@k2ofZZKbmt#}PjtgYRK!CeH(Vw(}$)(U-iUx%+ zz`I(ufsDlye`rvb(9xJt{!AZeD$iNIc`Gz6v(c1OViW`2Vb(ZpnW_`UC+v}G#xQYm z-^mPbuh>8R(Db&zZR{=Z5&s%bRFK$Mv$V%|%*_yc=Ix1teKv>ZGG{omC(BS1+|&yf z4c4m~hjV=gNpGv)zK&LSS4r;<;TmPXgGKB~}Bw z;)1<3y|O!H;oh*L9re_(qhRJf>S>8mGk9xbvzf(rG8|bu?0XjR#)TE7n1p;!9y<;l zs!8ZwC9y3SPVk*s{+?J)jYUM)J%03Ozb!13S8rv_qg3%(28d4MjiF5|bFiS&=Z?J( z;&M}v>-mb8i(r)g!KDeqROf~5sV}z#!41T!L7OVUz?d78;7^_E4MvF$Obt;nJi!Jk zB)|y{Rh+zz(MwDCw3zpdLBD2TUX=cX?}bn90IShBOYko%O|lQ z5_)fnsaabMTqpS#svRZ^5fw4D_Gh>YcEt*r^6|WH&UKZ4Uzhl6%&T1IV10Zg0qSx2 z^J9FL)yV$l@RCCKcR!Bb6=yUgyrOdPS(N7E5xs(uswQ?-(a;yJ5UGQwzz7hxl2CkG zeQ}X92bQZ36r7sb=PUjNn4KV)(UP_uz~nj6Z%$U0fQ;QK+`UFi;?#HFU9>40J5dtD zCZ{H`K>RT3yZEsd;Zc&LnN2iX;?uq_5TRySJJ5>(b-J+#zY3=QntT~i_7ql9Mwo)i z!MgcTKo5|F^5fv$47UK+iQHSv@OUB5WB@3NC2YKa{8rgLor%Wscy~RbkOEMt7k26jE&6S2H#5{N zysCPjCEn^9;SVSciy3spJWZ?1n+iCt|MpytRc;C<$g2F^xP}Y5xEmIDm6*f+h5^ya z_GVv8iLEnyFXxIRbnFW9;6GpYg{0(vhnyLY!XD_*%--sN=jclXdEbTGuaXm$SohU` z0U?TL=7HoloiI5Xa`2li8a(#jM_G29!&UL?*MqxxLU?m&E^*6raVeMYTAx^H0 zRV3YagEA5x052X;i#R*jnM}h4ZXn@sRZl$H5o`ncsb?3-(5V(p7R}%mqm%Rl+XK9G zRIqsvJfNUQVxpnxZZd}BFm=xPBm^cLr4E5d*;B`ZnU>tEQ1y3AmnM*`Lv-Wo{b*)p zFQE5DlZBJol)>3WsnK6FwX7+JY{;eHWnS@+ajw?n#C=ceJK_WvLu|O3QRS)<;bCMj zgy33fs;9|4ZLYcT2K!OY9pC#gz~i!Lw#nf#+*&D$#5^b8G|)_tr?N9X=1auczDy6* zU+F}@s^n-Jxes&3)+Ao&+un*3n?WQ=jF%m2DLM4XCy59Yr>t=IFNdle zcuZZUv&R=Src^CxXF*?0>ftRF{HxkIefxa4jM<+Aj`mB9s{@`Z)EVwFH)hNJ>O%5t zAnNk964&Kr+P8gIvd%RkaA21E24n?8DVacQAQsX7NdXeHwq7A$lpD!C+iKKRdYZ1x$#1BJqF#=ZTaG2X5up%q@j1HLP<)u zI#B0fhdQ86rqpIK6eZS2EC43w(M)C=eS0pT`%$qoeb--6{VA6H(1@iQ)qGGJ4L0zM zLg)oYc=AMli6^H>45kN$%FMZ~kU;&Mx*CH?|GNC%gODP0I8O18cs4x@j6*`jj&`hX zSJSLeEP+e@k!51-kqCd#weI3>^5~EJ5M!>sCa^u&io@?Ga_A&XVw>puvfr~!fqV-N$l4xj zKyw5RHDT9pCPMtc@s3|qmB#&7v|-e&47y5nS^^ew=h$m?Q4rhq5}GAVV(IOSk4(HHUkYp}&_g6(-q%w(JF{5&i`);oqn>yMOmcqJZ zgvhsO8)m$2b3XVfp!FPC|)(k_n{7hdoU zUd8WG!0dh7XJ4wTbM@oqb9+dIn*BVBfP{peZ-_z?u8V&kkyH-H+#NdGSzl|jWhWbI zY{ea_FsTYB2e28f#2a_l7bc*;zGVFV+&w*?;5bYMEMH81V&Ao__>k(;^e(jk|8^Ux z@uvDIrZM%Ic!kCYtpg>EU0-5)o-`>d8cCWjv3O4vvRPd7V4Y5S^!R?=GemzVVsx8B zvOd#lJ60sukjI65^Cr_#*) zd=Wwn7zMMG)MP!wX)hyPmSoR9IxuJ0)p@cdjdWv~>TCtJ@Z`-k@r*V=B{G!6W5W}8 zB673jmG+kBY?Zn(bYR*TQl*bEF%UG=^^WmJknPE5F3fao@V4@g#~R}k4gE{yOp@eQ zk}-L3p()G`MFOmwyo@T`IYW?vie;;3Z(Cs~0Uwo6{$*Id+E%v#L;vwWO|ZyVwLJp- z=~Hhm;}W;(KUv;jtfEbGSvAR(QyiSNlJ@>Sg#wM9L>9dJdN(z?Odm$#z|qbWsGu+j zI^^?2#6FX)|1E3kshg5%SL;L<^dZomRYSio zPlJV&gNeThbC-^#(45d6{ybO4RCT zI#<5z0}}k^ThV8gmsa+Ow4mw4A@h4sH^m?p}Yu|5e25ugx%j5m;!yIwAS*B4pTh~diduIf%TUwpeI8a zBc>iFIWr8bH}Lhb(?XJa65c}*bfiYVgI{mZg%`D$0fW+6Wt1E7%>D{_b#m{@=xV<{ z%3&!i?sE5z_bCh$(&%0vxt|cXt{th4nb_M&bA~RVpSJBPlbj!JRS$t>Oz-_l&`ZYL z$NdNjTq7d4PnDY^Za<3ShiH%n2KDa-(6aVb<83XfnBWR=P<(>2?Pepj#&q;0b?a1+ zd1RGS(oY_Ixjw@CY>iFfno~7ZK=g$x2q(So$X zWX=Pv0pNAvbiWHFna$}}j7mm-am&~Jt_O;d(g?O~v$q)E)H#7z4@D}mYq7Im(!LHQha@~M zU6bfgi>_0P_?PW$=^lBR-lVi1MeX<6_VOxwu|@7mQuH5UB{7~IM7~6_5Qu1DO~jo#xF)tSnm=w4PPF=HFMl^mtm&BAMWHgO_r zCKaVlXmy9neA>CjS~+ri#0#+P^XFxqw1RvL4GkR~Qh3!NlJ&`dVE)Cx-F#-WvioZo zB-z%;%;F`*75|c%hgFgUk4(r?P)L@YF!kU-SkNLY9?_DrAf8(71wzC}qD+y@4%Fh) zsXvf0B3#sOHrdNLJQm)vH@=qAP%w2GZ=Y=nz2ux@`RAwp)17Yz0fax~uxV{OeSfLw zEj;=@9hDZef;} z!{J6~Pvu!ND|5~Frv<1l_@l9kpuj&gxvM+K1=kXL@U1*edZ;C;6+2x0vfWuW69W{u(DNrV<6KZngf zp6twoEY3pEXNgAQL~Q&T*h*}05B4zmCLZiUAh-^`i;L7yvbV^Sb1=`NvekS&VeAU2 zP6%+H1@kt$^w?VCJh&xo^XfdUuscv>QionP<0dRIOM*4WeI z7u581LkkG0j|P?w`QxC%9`BUu`e9lWC6Dr7zn{ykpZ2J3g~0x7OMTl5-;&vF`3)lW zcK@+Be5NiP*i*Q>xZv>RO!eYG{VM&EU>_xgCT#u8R=0nB8XA1?N=sI@}Gq{01 z8u&!Lc+Of*8mZb3UE>Y6SDZ<9dXkpQPMg^UI?x>Ly98=*Nf1}GB$r#iH<(E((s#Tj znPd}ljvM$qU}EuCUR*+|(&{~j=W_4IrbqKgmB(9hVcmFgfiw}i9cjP$_13#zix(ITj=TNnVk5q_f<3;1B?xy0A5VXRKAl2gQ@) zCo&6)&}MZxW`$pY@gKtR@#7ESg*v~&T)5A{L50bqG5MEyg?gr^dsHyW%xflD;l0rg zBUO77!wR8aJl>`3%+M{0(yf!ZD*-9u`7zJ4-xb(Ba3oKc7L9@r#sMd z8LfWCjfb{8mTh7+3R}iFg6lRsqq8^6tgVd_68in0{Ael?24+s^5*aD&d7bW|iBVFc zR+TMC`Z_QLx6>!G5yw+l`fuD!%pfOokPuE}SX~uM%gE=1{CS%SOUZcdC`$Il&;k8Q z)HMNYtClS)+MOS(46+@+h8a5VC4NPwW>l<|E0NT0d2Zz7zY;R(9!P~v!zIc&svZQH zPkniz@QMVA%%Q1+DS<@`9g$9h;W47o)0@oCJx5cpO<|`DRIMF+-)gPlF>~MQY`xl2 z*Lx4B{rK2Eu#6N9b}MB60^`^|xP6;3apoFgAc;Bx+v|`g$Sd>5GXB~N{|Q@Kt*j?o zP}jJY&ib&9kMN8$S~e%WdZEtVvaL6*vo2mizz|Om5NA!-0Tn001&{llrMrmoj5JK- zOaG%@rNghDe4cx_5fT+@GemK%>*~VB>F-2khJ|41*)ae8{{l*lK}O3E6BYns4LOLFOn zCCm0n=%BsDUEQ=coQO^ZUbHCL%HcqEYStlYIdqi}R+pcL`(`1YG;X2PL|~rH_Rb`I zBHVK3+SD^fG#}!#f3HdmC)ZQc%5?ZtXM`fHh!F$EU)lKgw;#NugqUEtRC}mKJ_OF? z+tHulJ*|nnzzbCT@)sM>5_Hf-C#GDVrMw=F3Q8Zo^2%YwB*qQDNPB({e_+})O#ijWcV|e$S(#yFr97T~C&I`L#C4_>JIl9IPp>_3jzy=S=O%vV?I> zwGr4EKWqa!RipXwvz+02i^IU##T1Xnok_P&-z}~61OcLRw14l zfzKbo4%l$7Kd+O7pT;)!Utav%Tlc?>-Fw1!>$&>k$0ym9LH=RkkqG z2+Vz|z}cA1X=C~d2jnXshY}nYK7j#&a-(E3-NlaFqzAS(^WDvQG?X^;;!M`(s4tQ^ z+UOyUgcu7gO{~l88%Sw$(Z>Twx=-^&g5;PKTNo{o8b*ux;&I7|tu!&wlbM#={kpmu zc$(6GI5p)Pv(c^JSzI zwD^6(u;)#YECPXW-P^=r5Z8y$J`ez@{8>?#@TSO^JZsa_ z3RG8})g&S;NC`r(QDYyi3L7xJI_ZhKJAu{|&{^J`eM+CkxzW?GYJ_V0%dq4%L%S@B zpJwSxo4fR+X4M*zTkyIYb%JD2a@cIxAEMrGyW7rq;r4ty~jw>{Ws zuDi8F-SLkXq!f>XUqdKgL%#Dv9ewMjcX|8$?(x?6E6z5R@fVtiD!4bA2A5U(S&kT* zIp<;2n@A%P((pnT16jM|z0le|29fKdLQJ{Klqa2gSq!})35>W>1avDlO?RP30?Py_b?7)_gpslMX zkfW=?YNjVRH_487Ow1~jF%Nqu{N%BgQcv3Lp97PE5V*Z>4rAEffl=uah$p3(^F}~Z zg#m5;td*BAi^v|#+i8y0{CNg*w8g_9)<&}&5I@F z#X29HDKxpRs?4saXh8E9=bP-nEgkP2B_FOt?CcUk6l=@U&N+<-S)_m##KeiO{rH6F z#_0!iU*0S)wxztO5wCia6}JeDmR?}h_@0Uj6PFTWo@8T7Ioz0hR`eS6WqjNUX_DEx z+FF>@$py*R1BsP=lI8`8i>FJm6;(wKkrPwC982?}gjW16$-+r++It-J2IhX}y%Cc! z%M}rAW9PFQ+OLg=e!Lfn`sVOcwpc4R?&N@bU|`TJ@z4zU>SgZ>F2l0Bu*z$F5YzkN zoCN8>>d4XC=G-I4hHC-Z@@G&|_Jvb-Qrb^-k-L5|xoRCj$&Nf5qgo$%yKA18i7Ujf z2od6M?#50K`0>-28o8if|N4yk*xfi(VFSIzq~#;K=DYWS?c_~}6pb#jN9!x=UxkjY z``w4%>>gE3!=rNnnu8q|8Wm;hzAO88qm~_KTp{W;gEzT})z4?=546t*2v30Dj*(JZ z>^4B4B}C(e4}KSqtdGZ*YQ0%?ehf#<$X?#wT0G{SKO>0T|FG9W+z>bnWXB&h2@xBS zu-gA$pu$n-JySRSXTHrntCz6@ZFTSxlhSz^4~_|5;;0-Ng=eAYDG7W z9Ecn$;b0oB&CmGhILvTn_8kPl>$k=aOoLFj7dP0JNC;!ZCwSDD!DaAx@%*v}(Fnrk zG(eB@egq!L6X74W)=6YkglEyxwgZtGv!a3>q!cD0MvYI8w{(h&VD;iV@b06FimQyC zPtVSU_YOiI_o^0arelT&0{C_A#>*85o7x%OG~fMaYHBX@LZJ+!SsKImMDS4MU48W% zH;-zxQ({wTDZ@*(4r4Sx+JNfiN!zos?&qxZ^Dy-3-urq znHp!hMP3&(m?M{#{U7y3LXjxH)_uce53<79n zlow^L{^-^wC3$KY<4;)I5&zxG+bV5`&Y@fPIvjYuVqmgtjXn)nEz(?Z0WwOlBc#>v zoFi16?ZdBuH^p#sH_B#cNd#!BUUR0Nl%10{_oDsfKVZHWO1$%AS+_;_KaZ7M;PP!} z(t0ZHiJ62(LUgx7Wn4!CRsEkIwhy=DXrL>s}>J1l`k| zVRXHIPpV|Miwp!v4p>6}LkVsF58-<$S%tE!v&Bf-e4q^M(JpIkZPim}b8F%O#D2ZeZjX0(*jW`3S?+zU9Fi5aGoLcHm*}20 zuI$!-X3;jp){cBWTvgQoc!x$@6Tv{|gOZ8cF46$g`kgFMJm;B?G5yxCax5vL-<3|7 z%J_q=#dp|?!SNfjhm6wpE^4*6|rtp=J>bl(?c-l^jJxojinWGLjWmf(eP%R zs-ZE)vc0)k+pNjdO-&L#!Q1?rgxaCmdyeHta}abp{Fv)w-SPIqC49hQcI9mB;ZD`} zv-H~(#jMdSfy?37LpSz&AsUv=TsZL|efDVms-l)$W>@5?>{PuMM7rJ58gs*4X?Wy| zOHx{8cejSx2Wgj3X+#&auPaV_Af2n)w9;s8ZB0-HUe}^wxi#dtMkMNvjg6HSDc=fl z7u^_K!e^ZA$;@>5s&lA>iW;&h7B4P>Ov;y}3vVjqPO!b5m~hzsx})#*hFVE`-#v`O z*Y!o{=NJnty-8dt#Jh^oF~^{>lsjm z`1O4%6XArhzjQH{C1tXO1r=ic>@>#ZbLVY2wQ(JXEDfl9JQQMGkDPiPqfevn23q|p z3U(F(B$Zf)4L}unZHPKZJ%2V7p}GL*%}@x|4{i;OeavY6#foCamzIKgiV28?QwZ`j>=ii^RO@8CyKX5^E zsLn%4)z+uk-1B{J;TkijMEGH_OrUDt+qwZr=>LYm+W#$GGakS{L(Y8+e|7}u7J3uR z?CtL*BqT^`ghd8|BW8KYa*Is@QZ2$1%S`s0zLV{aFN$> z@;-%#qk!hz+7HRTb7Pujb#PQs^()hR8#8T8AX+w#8~NL$$jAL*Xaj4`dv#v2m<7w zGx6ZM;v-Ix#ciR(|Mpp3%oy&v5(1+Ek{YF*6xS0jnhmRUy5z-Om}^nwgG#IqDBNm<`=2 z0Y2NETU{VwhmngMLBsYwRG)5wXyQybi2X{(CaI~bTz1!1JGA0ok3m~lBta|Ryw!XqO@p~l@FrE(< z55H{wkq{|)J@CkKo#Gru9uO^MUR;IIe|Ep^4xlg@hM723b?YAm7c$r9p`l3NBXQN0 zz45QF*OQt@pm4IWs=YDGZL}C*rp78IU){u?PKs;{Ufeod8Vd^BU!ql&^I5e|sB`DE zNX7tC<(7v3Qc`yBj}A9XRf4zJYOR}*2J&8BUZ1oPU)LvG6F6{(FV=n`^Wjq3>a0Vf zFQPXh=?;ut$Urv~DK2c;bJP@avt;DNZ`y5r>G$iMeDxV;SngPq)JhxcyllMLKbRSi zK{8eQ59IH7;vcvv0LZ56D)7?`J{umiwnO6F-3cFU-{b>)-TnS_uA(XlB=mJ|OdA*8!#V%RmL zW=v$!?o+)*77aj=bzhCRKH8P7m_UAp)FwMM4fK%izpEoH`1!s#kHm%;RZ)B8L||g= zN-XD_8xrNXO$JCVHKdjUQX2-TW#>$5@>?*Nu4#UtOrtf+K$ z)Q48us=3zS=Bmd9r`QpBuWIfH6f?mvrY1h-c?(u30oJRt&#@Y2r6=Y)>;mnhISgM8 z(_xRZQszyKb2R99rXzcoE+2!mG&3{aKa&BYJ_b0Sgt3!`U`315Xc7}55M0yK=BB8J zxvT+vyeE^P!*^&5)l)rM z`%TdF9Msz<*P!ANF;?GmMXHogtgKcTDwt+$QzUY{`R0<%$Hu>i>@u# zc*+jCl8^`Q#Ztp)KVWWWU(ivSL)xROKN!hqgnbM zOdeztoLf_E7@jxcujNZW^iBE|l+-z*ozw$t3%z@f{?$ojQTgGDcJ*Cf%fz~vHR8_< z#@f!QSxluU3RHLV;h|3*dl5~#Qbps zqedAyuRACj`?^Z@qoWnzcTxnT%F>Ao{E4JhvLG-CNg_y;XHajC=^8hGgmtG{@k9wZ z&>^b>^~zIBIQw^B>53+slvGrsE|S72vr!&wOm+tqPXO>kbFXZb&nLxCVyHffNh?ye=QY)uHz?kl0G&$ZD_d?I*~_S4{ckrZr0n6qMN@#tZ`S= zO9u-^iErnr8-XJOf;xNx1?^rO3xZ6j%NNS%{%&U~HAP8rsWn)BXpKDS{uj<3bFnk| zjN(|2c+pCyVbK2+W_OExZTFVO6U5-MPgS~cJ32TwU-q_Gb4@#0&x`(UtR}gtiC@GG z*8*@-E|csQ%TjRUJ&*&;o~_mPvq>)+$Y|ydI22cUR|on2xV-+5h4}IV{|k;yZ?;CZ zvsBrEA1|pRcO=;T#!WwGh)Gl+BkRWzmLny4?IJpp?5+E<%8g{*73*%sk+eBd%*sgy z%%J)tG-%)NIwBhpTg5A4bIG!??L>@y>U!U)9rlTqno{t=NZC0HuZ#;N$c5L@xKVb} z!H+>MtwI&`ix^Mb;y*Z{f6d;GQ<4GX6RWs`Q#3^owKp2$kH{5x^)DfFlL96%x(9Rk2ZcwKU8 zI*VMImRkDe>4CcMrLFZxC$WgrQ<1~ynBRNzHZc1ZVj*0HEKoH<*F|o!;V1Mz;6(2K z?NGIVlVCEP>z2o0me5T`njDsw7zs7CPO8ALL#! zl*TtlliASvKrIc|6SS zCNSx_Sagr8&bu~ z?a%4_QBrhbzn?o$A`2LFOxe>h@>n5}iKdZ2vGsV>t0n^tUzI-dQZ^m{1=G>l+uvWrTo@Q#y?_?d`!2L4Rl=C`X38w->X<_ z6_Zy`PM4j`Qt~VrN)Bg1kQ-?1vuh*SAj6))0?{>jF*U`G-Zv#}Zf9tEtJPX}Mt^&2 zJA!UDJMyZv*V*xTAP`|~qbN}ZJ+#=C&7}f2fGqzlF6vOg*knnW(HmbdqzpU}4T~(T zk%zmQXD5AhW}Fr_Ter?I5mzESTr1mr3j<#tpG4F2l6C);!EZYk$T7*BKl*K1UoHgw zl{~isGs%C$7CMAwt?^b- zSP}L->L#%y&;lz(za@uDTRQsRq3-#1PFy?P^w_5#UXoh6L;fFC?->nuxPE`n=w%Sm zMTsP$Mem}I5(J~y(SoSaMK_2pgp3w#l+jz%5JroriP56>PDGEMJl~vie*d)|YkA>~ z7r0&by|2ALn-B1?SNXCPb;S34G}Hc=e*nhf__c6)kp=ns#Ih--Gd&nSL_^_5=TpC; z)VcIX(g^tRjeXCaFZ3O+ZS}Rc)7tX(;nD|2OoTn%N{k@1>=Ep@;0Oa zH@+#0|Cm?-WYjaZbQjM zY$kf?qa)yL#;5jeRSoXlc%S0lzVwSl#v~*Z4XjYwaDq<4yQ(7`e{Kt|AFTCs_O8gp z%9`D{;lN7_Z~3!Y(KuMNymQJ^LMCwETLVBh_q@kDr^Z4M^OjlDBIs%Ndw%WJDsj25 z(Rn@5?_Wq00)(7_ztujn5jZbvs=+^i*S3zNHaT&&0NCIdqfk3+_Y*m{ZHBH8l>dPk=O0LTH_ldl5bv|MvrovX?mk8I>;XXQU zh*j;`$cS1=|Dl!VJ<;%_Fb8g%Y3>)GCo3KJd4Z*Hpl5`Pm~uP(Zo(p8=a=O!SeQ8( z9aOZYf?fEn7Q~p@x@fc|i@EgzubPmTO%rw}CtQbh5m~yeQ6Eqm49BH+p?2l@6MRwp8@fKOZ}s_~!0TcFc%SC$>f7fdK*;~FRe6L}$h+%V zME+hc6?6x%ELqM1aF&1Z2+{Qam@AwctcpBVy72`^jccvIlarINu~EOa#(a-}*6$Kh zZn_7_`8<-6I%Vd1dO%7NnmGC{FJ1U8u>3d5eFI4ThB4Rq2M;6jlggSoj=`&Sv{xqFo-#!3wSf zsgY#sGv)Kk{WV^_*vi8iSq5=?tkSzlYB608$BgXkt>ulXCDtT`YH?un&xHwDlD4R= zaNC$KVfq4L{LounyO?r)N_4_S@X>W4A=#_=ZG$Xv(pS-E6a9HDSG!IG`6T7s2HeKV zj)JMUU+Eiat2nvRU@%;}`18~w*(i=u6Hw*s)!lpEsZZ2wJ1f?@hoKv13y-+k3oCe+{CZ zKI|lA|2m*XOih`{uZJANFOliQ4PXI=v{L)^X$i|s%dY*YJvjF#wl^K<-zYVga@mL^ zGT*!|6rsd!tj}keo5Py=^GqJP1X~bTIi_kvFS=1QYDc_h&P5r{u$4PbpYLqB20YD$ zMx-;h-tmRLHOk*>o&XHETb%zTnn`I>jgc-~~m7JR233Ol>=jdVWS^EtDCY#;Hy>I*ED!8hN~^}}y( z$8Di#!%vGs5RsqNk<1tVQaXL)@G@t*mt4FPYWJcBcI9y*t!thIdGpiV1+Gp?%F3kP z%Bre7`1~RXkJaR+IFB;~6rQZyUbNGOsv#D?s0ADgK!%8OB@#+pQr4{4-t~9#z&@!c;}8~?$)w_;LwR?*Cj0?D)tmJT zdSY{xqQ~W~p5~Ax{*=`RJzRX@tV2nvZnT30YlUZP3{5GpYI^NVMl0QvVYeff*;@;k`!6pKRip%8=^h>X4JQR z8q2>kJjKM3H17Cis&D7sV)TBdp5>@XqA*8CN^r@=pG}DY0Rk9qC-e2`iz}SCX%5xx z@j_0yH^=BfTAv*@6lsTez>rlN_{{k_?VAkU5pg@J7u98L(UY>GLY!Ro49VSrOm$sfgnoF`t!H>hB6 z&+HlkH;aeyZM@lDAB#3$AEE@j@}G-FhColwHe&xg*f2P(TN)wPCTS2cp6PlX%}{+R zdn@gf7r>OOn#wSH-TeWmQoAShp$l-}?k0t&8@8eD+psWVZo)EEo|{YC+1fGMGYUI) z-T2@52SoFQ1}3sBwJ2*J%olA@yc#E^@*Wk&hw~3q`u|9?~JUvNn^ktv^s$1ujr z+Q&x}a8|_1h@v#o>C{>2I1KK_#`x{vD>~+vnlm`Ani4H5%0)A@Qu`@fhPOnm7z4Ii zNi}=QuE#9JRI;*we`meaL&Ub zXWQu&-4at1wXH|nsNo=qD{iux!p5$W>)caViPl1Y?0dQ4P2J8(Bfih>x`f+`j?`ED z^JJ-{=*VBcSg4tpp4_^5cz7H)_bO@U!xqKE*qqwtjE`R~-;Io4fnZY^T*XJ95wSc* zZA2etpiuEWOXE2>?d_ac4K8C?4YpoX5^FikW7DI^@QywKvKCh~&8coJq29A>9nt}; zq=u{{zCY8neHOm|y4<+wVclp%y5M9J|3gtV5F|N`nj`orjtQ|KNdw9j4Lq_Q3E3X4 z)$4MJ2Xb$0JxA}f2n_VE;>oBYsY*EqISbWO{`%MNIjpp)n6_D^<-ht?GRZ?bI%}W- z@o}bU|Lo7}8vK&kHS{%Z&yT0TJSu15MgGc9poqJ>tddTG<0s~!zEKLrjEw^rWWr~4;M*+pJK_xLQAZ;8xh19#uN0cA>0c}V%J(&tB6#5s7~Z4n&%*T6`=u`W`2+H2wSg<1hh;mqmvY zeighWTfwC)Bc{>pm%pzIqZdG7em$utbmRl2qiSCGu8Y4+3tciL=>f~u%80_ zfEW}9gu)C|$4NGN!5 zQU4)Xp%;C_kS!RoIg+K3HC2Tc4uZ&G0^jG(w{&5B;w=hl_Ksu>0CGpSmJ?E+Sawpid$t4q+k4#UG_hQ@h0)HA-H+sOae3ae)5Ib(i$NOdw zKSMDkvhIOs;XgC;!cgQ`w@AqIyK-(W-Vo(C$}lS{PJjQav1!3yA}-VPjN4KPSHB~i zSFAi$9P>3oJ-2^EOG%zKfawZ+o~k0N!KNW=z$r71F%TLYi zGt5fqM3ciMKY9VA;oJ$_U^d`|wpHcTyvQVT8DOcF@-;EDv!kBk@2@Uhsg3=8S7D~G z@boWc@n%$=mbEywfrxCE^S?%)7K zX?)3AoRPbcI67Yrv;`qdexw^XQN;B6m4qwyFH0pgKP3*ivns9IYSM_3e)q+{tPRO~ zTuw`Um-8`9``s|lv~FyNVN;r*M5S>n!jRWeDWeg8T6ge=>1>mo%>I0n&P0{W=S4gD zneV8^EOOR)4OZq^egZnqwQ&?aRxlz>v+QoCl){$8cVQ)BBP2J1Wbc0?@d)xQzbX@&|}gB{dg_phv-HMH#9ai zo|s7+S&S<~KF0Kt+UqWixtPVSRN~XD62)R9+bB%W6#Y3Cv%X$=e$X+p2hk6bY2aZ% zL)-1p8Ed;4?{cdP?w1$bxPF==`MQ7;&trZ&CO#2WdT6zCUS3s=ytIXVc4v9Ea`I(8 zhUoZ&xHgqO(JSk|6M4XgfOEs&N8i5(E0^sKVk52B$us)!*(-#*O`?zw-5EMJu&F)C zVF}F{OMnv``y(~4XOzBeegVW26e4OR8eP3vPKR?nJQ~!2sa6=Obl-6ZVFk7+$bl&4 zw&CAL<-_h06V-Cy);p#NW9U)T`CO>!cTNczgjlZy_<064&9`hCJ z14r%QyR4yWNS)Gm_W~S|beN!-3E-N5?)m?puXM|heE4VInQT(Q>pp2}lQQ$xHY}`F zVi=3oAO*vLSRfqM`Tv@J>gI+zz^j4RDo_}IFjdS85y^g(zxS0mTWc_z z;X>d(!$uS*6{D;Rwf`q!`O7O(?-euq=^kf00m)>`&lh-cAEYyb+BuRr2<`=b(&$K| zz@@ut#73NT{agaD!p$ok@q730^SGyQGrXY*#8dSau=kIINpm!*eH;}LWlIC|gpEno z>AuIS1{p-&T+s?jrye?666oP-rBKrJj+fQFq1sMS+%W9}6Mo+H)T)*&AB>~VAko*> z){*6y%r>WU7m~?Yfz)S7G-NT`J9BN|7L(r0qd`?TS`+d3O(++~_YeaWiT7PrfW{}J zisXfeSu{H_0Mfa7KvR>8>BB)YY5pVJrlp*EczW;>{N1PH+h%WNzPu6*h;=$2Bl!N)P{Ul( z5l6#L5x=sO9{!8hHiuU~ss6}}9-uo(W$am*as0Y$p^{8Et*B*%eZ`qa0qr7wu1j?~ zm50qP#zO+FQDOq#RhAzUe(=GcSJ3en89*#}(gcEt{l2jq@9~?7m@Sijw6e}2YvoQu z19^DhW|U3vei!)W=v-L4y_h~D$WVa{Vs!?w%E*d3uS;90Ac(qW7pdQS;Dyi1ir~k$ zY6;3d{MdPD(A`JML`G%v0Np{s7h7Ad>P9y#YgI~lPdE~1<+;?TnJkZ!aos&K7Ln|$ z-#)3<0}G!En=8a6aR44iYkV?UKr_fR2fsD@QLDH0vdy9Am*ApDI;reV9MDc9@vYpO zY$u00Qh>T^U8bt%H@1uhm!aoQeNJ3AgEjL9S-#~_)kfcz55u5S_w{1gCIA@9s;$I4 zIXqN;KND$E1J#ELy!|#a_)ni>Ku+h>9Y(w5R?Ktb4urjijN5(j58# z&!N+fhj#+od&KR%5!a2@uZE~~qCC;ZYgDVNoKoCzis3!|b8~rLlg`(bT%^hHy~*em z+OHt&Te%VaqyC^S=|X5aOMz$O{<4e9XPvCyS`hdk9}5ay=I<>9!SV#qPQB}RrRd(kk?!IM;XhF9?h~ z9y;cU;tr;TS4EyIKa0t&YO(p7DAX;=la9R-El+UYd+LmSM2`afZwaOJcwtEV**hJJt5PRvuJf7!GvUj_jJeS zLRxQfTt1FKY~+GM6_z0*6$bn_&+#Ti5Og7Q3w!wV`YQL-kHUNMr-wp8hqDg{7rKHu z)Ai9&8TIV>Eb8wd^?se20Ou!HO; z4*19#Wu|zVAYQx9Zx(xi$-h}DgI3s^H(MCm=?r$;8hLf+@B`^2=|&W!zx?MrTp7!t z?BUM9!BN<^JBGcWuLu5Qi=ndQpaVoroK0sNPGH6>t1MAb6Nn+`nEp$`j9Z3Alo!|@ z6B+qt5aEub$GP)0k(r;p6>xs%FWRuyOz=rCkobX1A3bM}A^_+^yR$Ut7~k#gHa@~q z_>CV2c`1PG%5Vm?Vwda)+2m8XS;e48Ol5wBWKd%RMN&O(dTV7Uxgrq7`npd~{uTp+ z=>MqyE8qf`WGHWeU)c0j`m%+Pwc0)tig9_{%1&kiWyvnPvS%D#$yZ$b#PwNXXm@SS=$j-aHETh4wuAJbuStrU6xAmf|7k{2ST6!yz_hRu0UW$8$!0@sX6T5@x-FhW_YtD*_JIx9% zU;_bb*c?d=lc9i1l~^j}tAcZ13^eey zTdI&Er#u4axyXn(J5q%;%c5T71^3sU3Fh4F3P)w}8_b}TRfi@LgeNN&y|TXGUXv*TYV$r0Lw^V;ROFMT%m8E z2KFk(f}fyfguYGI`cNu-#)1(40r)+LztjT6FF$1wRoy<U!B|GN$~CpJLbfQ;eq_i$Fis23Mm)cjvsy`p4=B<(Am1+R zJ#*C>uE_cLabmINQ1Rd($p_K+mB23Z*>pt<-Q>SZtbuT^72qDI#$!~C45=JS8syxp9~?YC)OXSQ~y&HzPj+ehMP)!Ft?^zaw9tXX_xnHGM0*G zcth7NlB5ac4*s^8~Ycc{o7J*)N3l^8W6kPHmGj*BJGub$8^^Np!mdvRe6%Kn+UgOPZ2yMU4PtCLn7L!JGk0jY6W zDf&|Qp2KK%X0|PK0XD~eVn051>E*!1VXh&O#;2tAp*6u6LPdZXS;epKO#p8o1Z<5F z7N{1of`sAsrEav_G&r{3-u30@5!t=*jYx=W@SS`xTkFfv^Fv**A8~Ibu_`M;sM{67 zygf6k98KQF(dl#AbE~Uc&TEXojPn|o==S2a`Lw<> z6|4!-o(gGGnhI%s-f?q^OXwCVrda(~ekv66zzi%9!qoI>sgadmI2$|&fl)nM+Y((S zjY~(~3#p)PJouiIyaWvR#gFxz;x~+&%za;c|5Uul!=~r;%p5|mPPYjmDTH|36s&J1 z+qp$2oTe~2bB=O-vZwy}6YfJQvwX{qxr^|QG_e}EGBC`jC!H4t*&*E+v1mYu&t@Ibi=EX%H( zmIwi+P@me;nh6r)WDq@408ia~^siB0t!TVLM|G2Fz~{qD?U*F=JCqf}{b~RT0)cs7 z33_+--uZpR2a!UslbLVt?NLI@31JgzzeMr0JbF+5U| zPik2JdP6Ou5LOp~Ts**;^M9GKiK?Uz&ThY`({1}`$*^lxv7(Xrb9;!}eSsXl3HnFj zbJ!kpGNRgcGPH^DqiKU#NQBLkZFfr&4?e{ZscUbYsG4wnTR*p9fu8^1&DuVG{c>j| z$CBDx;V1w|eu;XwH)J|azZLm_`@hTK|HO;O8c*p8@__keqHkiNCMhWi(Swjd;KZ@S z5IDq)nB>#y`!y~w7C$u}H_m_&iX>}=Y$?KR9O8evV0bmu@AS$)M_o~Vg`-+NZiFF6K!uMgIl+^t$4EjayCEhV zxBylF$>&uX*1xZ`p*TW>v3|YzMxFinEqe=&x6j(`vkcguHL)M?>}lB72s{ocQ_-rI z?&0qTl5^8k24Z7HBt?`qUHxrJ1rtQ(`}8^=X_K6tq*+vwU(_t^EDaoz$)>^5^~u}jpH{9qhrp!P(gRj^=?g_Y6b0G zfj3q5;tY{^w`f#dW9H)AW%Y{6Cq4C_*n0dk!g5*^-mg$g=BM4LGvbIJbO45vpP>O$ z;5L#|bikKwKP_1(uc2QW|JX|RzR%ijQqw2@eU8?%p^>|vLKfQoUX6I4r02ODM(&?g z_({8c907?S<{IIQ0B$l8?lZQfZ-SVdHq)09ExZx*cq8ip8sDGj0#WCaNdcWZMu9SW%z~WdPVZdC-o3LTTkV%!g~w?|PU|*v}D7+B35-Y|lua!gNO|Ie8SB_Cc#xS$P7B zz*J{8ST8tT-d+2X<9vFt2+Xd(wDq*mDQHwR2ZArEDjn8x=QnuZzwEG_|C*c_pWGDs zpZ|gb1Q-fli#CAAcdu9J#cYFPc^)9Fs}rwLATREFSx@{Wo9nx#IY+jU)32_u8Pn(7K$HjYsVK}wXlwO=y~(B0(` z%_5cIWcl^Je?(j!L24(>#Ra<-IL!R3l{kC~QBQcAZ)NFr{6WCbp1!LEn-@mP_eRHB zftr;@>+{PNBKOdAbGx`SlR;RY9*aU8bp(sbs8N^iBffD+o&L1Kb<=Hqd zU;r|%vW_vW46fb87j&$o zsBEbtd?=}Y)tdLp@rU}7!xi=W7uOKHnlU=Fz*;4j|UAjS|r*Xb4B*HV3NE4;V9 zina!>(P2Wqg*;vI-P#mwfiK6i4MUu991sGy{dkxVeQx@Yrj~h_KEGKF-E%Q5p+~uQ zjPd+(q>frRePBPS{en58?r-bWM@+GRYa#;aF~0k#U<%1q{~R)zLc7BAGN(h{=+EpOuppB80m_#bj;O-nm(L*YoGO?Rb~s`( zSK;K;yJJs*WPbp%_qykd_q|qGo}Gt3oNdUPpjrydUkXRFE03MTrmV_mY-XTHL14QQ zIjAas)ExvJin#L;cRJXd1Ou~}ek;}e?aoFNh(E(6X12HMJo=J=g%mhJEoRNK$I2wR z<0kq)F%t_6o#%t{#KRPxSz= z(AV3S5uXR!u>^o$>BeNXS$itwEZnr^SLV7VPdH zBf_>fJZVx%V|9%P_@=)!M>yw$(y1Dq=2F=-QmMPk?sT3#?lY^(3a3S=_uY%~$~RfL zdji2&Iul3)1t!{(u|K;gzIV(1tou}aW;%L|wOJ6b3*iHFKO+|x>A$y#L6<@MPs5v2 z{O|vM-;NPDw#FWNzkb-E#zMV*ph=kz7P6J#dK@=)Au7|@lqx@!Nw!~F_X$xx6j%1q zl*@E1$qq@1Q)kHgLAxUT3H2w_Z?RO=6+Qw+R-Lo8_K|h;md)x+2a5`x7{_+r<*2Ef zs~?*8Z26FqVs6F{fA4b=&Nt-dc`bM{7(-6t$()V)Wtjzf5Gj!eT(*fPc5z|WU(18s zmsqMC+WQb;7FD;WJIT<~OAcSGB0%G1D^;TVt~e@XhxoxD`1uaD)l-L>gA=BntcyZ} zcDWZ)FO*jodB6CyzRrSLZep7?4nvr6tZt+k2la2h2>hV_0BHWQ}L&7d-VB1Xi$8S1YpqaF7LSr`Df#xVP0gIgsJI zSe37t3Iy<4IS_yZJNx~BRlkOJkD=}2cBa3U^um-7w28g7FsOKs*QzU)U`LeYhM)_; zSk2XdT*^QhBrVl6f{PRq(B(gM6dQ#w3C-rR+K4Oy$xaa-T<9~Fl zxn6QO+^Tk^w39TBA>a$hd>4RN8Sup%D|p4CqWC~`Rs#^D=~Z)-!Vr@>csy>Z0voyI zO5FAbdAA2x8P(6?Z;t`wO)L64N|cnzNaVXG>}#R`v5l1bGF;O8w4c!XD_^kdU6Dw`=b+m?wnw%-l%H&$Kq~b&z^9!zJGUZEQgmDhd3w zUIlToPmmCQk)+1?tO|Ux6UNQXH}7(VNs_O=bXm{)7{*5GL<S6G!>zn{ zwIGqgD2~Gd$QJ&>L1;N{O|~y$PJE{;Co71-BjVTE@q*duA>Z#4pT+38$>0e)mn_8@ zQU5=4Q#1$#;&G?xvpj>O4EWiV)*u-^Ks8~nZ^uxklG`Q2+7DlcoSe}?Eb>NU`Q-#V z_a265lB@k?v?zQS{d-(BW2142-17RhYq}@2b1HZLU@WjUHPonUN-L_y6=a9tzwgh? zN(HgpBikT76b!MME1Zd@7F5gcmv61zbE5l>Kbowwez2vTn`u@fDk zg=$i4E(9(+#u0y_7vzGoaVSaLQ~pxy$LNi}u;X9Mf_JK%5e4gfkt&lm>q7C%jH$D2 z*^?g+ci7BLL70a9wG?zUuRM4g5NOF*jQ!k>zY3J^D7?Q3}qu&>x$V+4?o`Z?U3;>O&GU1Xiwr(OuCBjvS!)E;V}@Hp!&{H7UYjhQ+1! zh~J*ai_*1!Z_h8pdaBJSc9chGY?54>pMgqYEHM^OK0z>lbHjOt$HFPUb_G90ixU%2 z&H|;K2bLk#6O~k!A>8T|)OqzwOmufz{8*fRa7Cq#Lrh*W)bSD7!f%hBMpbIyn23kA z*vQlNQ1tEJgFp+kxHi;Lan`#lGR)1}l&gPSeKMPqSm*QmC=SNn6B1!=5a$b9Rg_7; zj)D&!yeiv*_MZr2!I%b;$DrZ~ezF~>IYliI}B^bv0(iefaEF?I-8z-+_}$u9P`w}D_Tl~fWCDh+lq zuraYpLtrK7JE@D&>|%Z{BX&Pw%e*g1wS$3)=B4-#VfU_1>*7Z@2C3{q%@ntZ`E2>e zy^)_+Y$O7H`Z0Au52MWt@0=H{m1<%D+2}|E{-rMS~%#N-HQY zk(_U$a7&(1_(z0FA|pQn2o0hq-qpmf+MU{nMzgmoXRMGMZgehB(Rg)1?p%u=I^n>J z0mk-+bb6fDVfH8-cx|HinU5$T5O0UIHrU-1sbPXbNKo(I3By%0lV--bX{=NrI0qW!r;_^GQ`0I~Jz^Z>-54fBk=Bh7o5smtI$= z3m8jE&90knuV@zbJxAsDsAxE{K}1lVY-+oMv1EhsQa-*P6^xvtfYa1ChM!s? zgKHE>P)&Z9-u*`1F`w+y1*R?XIP$j2>~+y^=GH-TzDKq)0S_1e$RPpWBSp@Wu)&Q3 z)<@{buC9Dt!wk~p!I#Ucoc$w(!)1D04>)00Ef1i$b|?>18^}g+2~5HFaVqV4-2U%P ze;u*y+1lE7hJ4xl5pG7jaL(GZ?;i|Kf3=G0syDe(-FJQnIDOu0qH!L9(*&&O4jYo# zoR$K!i+YgO{2V`@&7bclciNr!#NKYRhr3?BYUv0_5b}j3h7Wc#2dlD%)TSpgEdt!! z+3(E7ck)W}I0IjoO26#59NZp}vMV)tx!pIkwX?+otN;1VXYB*n zg!6!^U(u3w@UO%x%aYHpUtwjUDz72>6kvS+Fj@k{S-5ii^Nm;!w{ zIaN3d-vYYAP{1sK=oqNxwPaJwRb$GrI01<_jVqCnd{pk|GaiSbR)f3lN?&ekL&r_e z=v$H~&3>HRVhf|$e$-xXb&epqA9ppoE!0Le9q-5Ra*C#Uj!!nkx|y~5v3$#1kUwE) z-Tdxa)Y_`f&BayZn8`p*B@=mbi{r4Wq^%pSzth0=XYdc8j4xy84z9#2hX&iJo@K^|D^qtI*` zmIQtPd;ITH?4I8=3E?(~|+ z#LI7nfCN0FMs>E8{Dz|cou9y-T4H9WyL0m6`}+30ieMwBg=*3WBaSdWn%%ln-}Z0I zb~t=oybWNZz|We}5vKP-$WJ{bJry~)={WpnyPls}pT1WjT9WAb9+Hxt_bEL8CC=}| z%S(KH7)(AA|59H>ChxeeL}z%Nh~#&!QgT=J;a4TfP1+6nVwl>Z$j)5&f>`!)Vx0bTlbG~r*=-}!hPSZ;@#fq zTfr50In5C_FxmstmVMW`p)D&_v>Nkq&r_VKQ8)JcX9H{mWfTk~vUdd#PWW~N zXb(%)zxwKUG*-cUn{9mGw9eNE%>5(>M-rRY}$f_9z~C^80(g z$rcw=z8r#aX;;~niQL&iy=o6uk8s1dkSZ(3Cma;)xoXk{FSS{{qzksPpJU$5v0(KQ zUlM5v;dlGRf6+q<-Y{{gwb^y1bIVa*wB|!3e*zEg8Xf{auHHS8Y_blcW&GZ~)k~_= z{T8a@EBT$LUb`9cWjOqRHtvGMj}BnIb?C@=8^l>ohkJC5aD4IZm@mpT_BHx7c?9}( z{=^9!A&Dzhc`4cS%2ZV}>%waoo7y`1w#m&xb?)-_zS)maErLe4yRs6><&+tb6N>LZPSBXh~tBeM;W0c)Y3^ksd*%U!AL~ z8^cnam?K%MJirzKd-;cnNB+gL@NT;|rEtVU1YI|XU0A@HG()I|w#oib@rKcxjoOb3 z{XCuKkKo~zC?IZ6VcBMTv4AtKGp*^Zs>8OTKU;!GTl?*$In9%;S>(FDtg0p*^u1*L zOROou;rLQeZ(fb15^(m;s5c_Dkz>8A)WsDg2`2X2brb)f{WTx|ca(ho{t1@yJG{?p z+7M&^JzEWpMvJ`7w|1JjFko^A3m!D|6|I8>$ruujn{1)3D zLr3~<^;CXk&9jPr;gvhK2@4tU7usO;D-i!2vlt&;PPLfK0useQ8prZ=09N;zEn4!{DoJ+^6Qj z0qX+6e*^;}WmEo?y~txh^UJLj{qY)(yLyAUTGflC>a%+Bow&orBZqBwXk=&oi2spR zF#cz+NiTdlSwwg^z7IorDmf_a*TB`Exp5q0P$DZvPTPnt=fxds?A1!aaJwSw1dynZ zpJHf$m6uFZ=AqwcTamUKM5Unb?~y})05d7@6c2_ckHZPhr7y4$fVHplzJD+Bw?km{ zvYw;K@93tC>!S5%U+@LSGl&1=WW^tBA-1t6tC-F@8`$|PzwPMp{GC*20R!gn{Pr}0 z@e|~P;Tx z%edj{<)1(j%x|F};?qv9yTVur0ds#2xAa$KO{w&l&pwgHqX&@#16s08wW&ilOi!0m zgQXU?wv@DILXfG)8|QY;UtS@rUlrbRif?otd`wyk{?q>Z_#ko-bABO7Lydtt8}Xte zPhO4|M0z>?%2p|_C|e&PjbbkWT5qT?FRz3-OBeZ?J${LJo=PxE*h&CS>X?9K(u`lQ z&jC6{QS6{pK3=5tj*51=ypa(m2S`4!lLL`z4i|Sr zr$4aPtjSgQ0u)QLzPac}6b#ZSQRK{OJq)cMD&VaRFt@&=J@K%SlI_%!O|J@}@r>tc zv1-V?bd5$)1KnROp1pUkkRw#hm-Qw28c4pVYPuW$Wzy$H8I$NCQr`ct%uWCA#RQby z(QYZa7U<~fE18&>AiD+dm3d?Z!@@L_6>$)xVn?tRD^xPKx{)a(VhF)U?+p6tCx;pW zFkiQ(8*vHQPudAEoV?i*u>e5gokb!TH~JaB>N(5pK-oQrNWin1Jb5Dyc{+P9AG9IF z$bLCx2x493Pr7$r%$+XuO&}tD`b)=T?(E_1Q{SKV!>2nhBKQ_y6uqQ;_7`dX*~1$o z_d`3Zc2W__LDtrksS+8KeIt|S^}7}H zpLU6Q9IfAZgdWHddFLz%rZl}W9;$6rNZB}lM}IJ{a_#F@5^=C!1Pxp&q&VM4Cy{gZ zOL=Z1G*fYGgD+?L#4_&s2~CvfaR?NhYe;z=^DxW?{$3}RdY$tAj~>U)ym$tWPh2y{ zq?P4E0XLGKkW_=GNJi0ndt=JTA%zyHhvlh;H6R+q6M2GRew6L)&DuFrx@~{$@Tc(o zt4SUv2nWPWJYh^>XQb6@!9vKP)HsP1T!&I|OpWV$hT6&O9M@PB5@qO`vXs7l>-Wk< z(m!b6Jak~-Ve}%$@);9|ASRI0DU;KZQ#+_1MYyro<%)~>8Eh%m^EPYn3|k#w{YmKW zEhN)VMg-X3L;cyW+60zOBIpLmjx1JWaD#F##uoSRPbffsDxf&kNw6_MGERY`X?7vb3iA> zS~IGG{Sfd=AgaS4@al;g{;O7$HyK)?ngDpSKrHvS6dfjqzPU2JWtGd7p3nEaOzG&b zE~ZSEmzpN z4AA77b?P-aH8pH3J z+8;vGcQ?jxlPM9^hIb)WVMZPy+z*&_B%O{0bpyOlid)$?-)X%bVQ8@?D14(WCpnCU19 z@9{V;R!V&wj~bsVHmG;GHP3U^D1;xpDwdgR!eW@s9OWW@bhSV8K6mdPs`YVaWwyg! zAr81f}49Yd3$TTa&WHTwxcMV>^62=x>B9|oNSxIYY{c)p0r z6FujszI}x9p}K{Ec=g=U_~<6yv9luz6v5T>ak*Y~=d1YbewX3zpW<=&@k`WB9@@Hy z!oYPGU0-h{b&y4Oh#wwI4Ln?;I3&mzC&|DO_=&p>#^?{M>fO952wI>z8zQ%a#5bqP zwEI5QKkN-X&~BaDO95MOihtP)N?h4%C=FkNOE`k2r@VikdPpr4Eopo^3!jPNmXYoT z{m$pK65tBE_sBlG>y-umgw`TXKgBPDBXHt9m!*=Fsudh~>YUA`MEA#rJlW0bhwhhD zA=0aQAzD5ReX|OQ6t>r~=Cb|gTX_RVg7dT#xHzLr(L(+0W9P3kLUTzBewBCrlmXYi z7OT$h1*&D__wl{#b%TA_Q>mYqoKBQci%P0TC9ILsixbq0uFX5r555)TaRx;g z;W`2EA%-?4O3nPC;s76ymF=(TIT9E1D=lSVQ%`6 ze9R=Der_?6!DG_$ovEQy^o)|-m@yeIEvU@4 z7nv9}525&d=)cJ!t96hCkd@NItNU&w!QMNV|89mle*Cv-hU|y7+^y09=9=$Y&eL?K zJtr=4Iqg9bFpvw8r^5k71tY4FNa_z#sn&zAW^Ysj3~HnjKmtwoL@HMH1)MpZn7 z>J#d;G=zQ468KSj<_T_{J){*oa=IfF&;m#j$m55np4Rk21a%Me?@m|-aH||1h=t56 z3Es&2`3LBcaKvq|adRRD4W8MdBa!b@Rg$f{L^AVvMEOhuKH+^rxr^$L-bj))*mgbn zI2Uz2_vag0Y+LG6a5bmd_3HyvM4&IRL$Kd+uug-l>@abSj#w#>&`UF{{T|$du+uAj z*PmAq|FR?hU?k73Q;OqO8Am&v9?2(spFz0TWo`)aJcxlWsBYua*V_A248;>JPf87U zg;DhU`P~*+|(V7;EY6Sqh5|^5ql5SdpLE$!c8{WeM+OJTHH}=p_T#iR`htvm%pS|c54MG25<&#wzNMh&nXjb% z&_7|4%ubV}hwML&Z%qGivPUlo1#uOUp_yn@Wd@ zg+6vFt7}7g7Tf6s1>xZ1N5A8McKhjkmUj4(;UR*z6{+yBRQoU6L_NhsHD;pm-aJVl z{h*a_L=UXAf+Z-z~4Hp&|YIy4j^To^Ir5 z>zG!?W_!$@kv~@!hCKrc9FFWFk6Om^p3ZHJ{L4w?`TRHVm&1Sa!vFHvZnoAsLf**7 zl?({C1DMuWvF&a#aJxC6a*g4&Vu$dj6c_68Kj8%BCk+w6xzsn*gcmcu2|u$x>69-)YBnOc}8flOkU;se|L~`gxKpH{1Q@Z zkD`XD?BWag@z3+_`olP$D{BSb!gzRi@+k?>hZU4OklwQ!@Tn%f!>#|3WT`1 zA0vO0idMP}0PH$DvQo3^I5D)Dnu*xge4QsD__bL(cdnI#@KU9{W={4GnpLtF`yoI_ zNR3d`DO1L)&5Xc@%oC}J^O3UJ6L#T;Z@j_#o*2IhKfL)^2igB>NeH)I|469@m&t$F*nVd1-J)(x%Q1A7gd8T;p5+{WTjsDYuQg64^rDE6D)+KRMRFC(8 z7j`#DbS_KT|EC3xWmZxaE0q|&9e=UoF4&s#VyDr*cDB1Sf}7y?@Ru`Hj(-0U27{5 z#kdkT6zV&fQxd=_pAt!gp%}mclytC-sRU%?!(Oa{{&4C@vxB`xgLTVikpz(pb}nhNX=|4EJBH9F@ezvf>jG z>cC*sfC$UN@WqK2G3FQANVTw8Qh|J7%AN~)j}%%SU89t8nUN-!y;lAgd$MlwU;bt< z@-9<4=vKPaq&W+~%u%GkjQB0r{6x}v)uGm8TZlv*CXl@4OhcR3#6;RL=S zQj$7hWCOqrYik{-6bA!gzr65XYpfKpe)*i5J{PL_@Tmh&OK^oSt{FK2+N^Qh^Z{Nk z@oT;6^Gh9yxh6O1n7v0e|iUAptuv1IvHdg9p0CQ zISxcQFuGY1j1-9Wb=WWtxXJxtel+CedS?RjnP<_ej$wIfKcR4Wy)yf}| zOujG1pKNu34vbv}8lX%mos1wNC2?(Et$ zYGO<3&u|%cH=w)JWl9{K)oC;!E_eC(9_9NDtjHomv8vMEAGu!q;njj#?+xq+YrM!Z zR^r0l-LnL70M57f{>{kw?D?544({NeVN!Dxk&44l4fcGjeLU46}; z2%hHG4DJ{@<7hNj!&l<|r&m0v7M47g!4FR4B2+1j_#z+vPg@|P{LVk`EwBHf9uzkB z%!rflI<#VhIbYi)&)nWzB*2JbpYO4-zM5Zj_jd|-dr56>lX|!I2)ZC~_j97*CVe3L z^#T=^QuczNph@u2KfMnG!${G|Smpe(dOYCXhe&uh{YNBxXZm{rVB1gz0Ar|UK+d+` zH(`o~u!=WPn)4$5b3JEt>kJxrtoxj+Y(1e+OW~~(NL6u7p|bHpzU>22;DGZQ3xe{l z+UsZ;@6>83v7&?1g)q#sx)j-b6bhTWbF^$K0}M(RHAoVf+pWq-2|+A+WRq zI8aNMoz*5(#JPi5gu8a%6zwd_NK4~m-oJm(B_yOhFdI5bQq)w9un`j*Iz&Zo^jT#` z{8O3)nVkR-B?s#*AgDu{T*?3Ux4*u<8kqvSoq1Eb-=-=BZ)6Spo;v`y4gZG<|XA+)_6D3de>3oeT()29uUBG*MnB04>3+)AMkB`3?Oo4M1U zFi&&aU^MGl{b)BUm-Tie8|z3)HdeK)3yulq!~T-wv2~{PkQBc#5|)-zWQ1d!vMHs@ zgIkW58-?|Bw$sfLi>7;a8>H=jBdg0pW=-L))3UhO_$1?lpo)O*0~QaV(~ryFB1(JU9+hj3LqA3I4kZc({Yva;KlC&TsZRal%5LWTXu6{Hadsy4^v3$u#zoS+7>XN z_5yU)SK-JXK#aHdt^dV8=1o3`WfABt?T!Du=E*KN7~R#V6Foi9LY_Def z{YFzP{&Bz-q@Dt<-g_f&V2cmM^lSRo<23{_miNn}aIdPo8VL9rodb8P_$? zT8@%3uC!wb=+FdpUJm2-*9qqUU2NGd*8Kz5tnrhx!?fz;DzoPQk}+?a1i%+` zxe{sH!QT%4;7wr&V6cT`cxKvReDH|{4zQl+9}z=6e-Mb#jc(rID0s_hr9RXcBV zYTr;)U>l#x(<9%P%3TN7Fu?_|=oA_4U|n&eE;3)9aLT6s49$){>}tx`05M3vSB_

0ys4=_<>jkw}F{t=!dtGy*f0Fmr*9LQw z)Yn9@A^qA@-<5v5%RSkj$HPFFUK9?>Nj>eBy;Zri(QNWMR5z^7^Z&!E#ZXzn&Ow)w z^U?qL1llw?UR00lJWsn!;+>*BxvwCj(U>UUyJt1B_ zW$qj<{lO@q`t{!T%m^x+ha8&UptngY+pco#I{V`yfCQ5q-@;9EWddjaq~FY!Yak3{ zE;ZKAkN=un%iA6+^(7G%;ZywAZ_y+K9W5|GwCe zbYfiExxlx#UwN!o%j-=PquZ|qMX?xH<9egD(t>k1U!LSB;J5GpiQQbdZLCxtLraPT zoxVudGI_Sj{>+~&P5Hooj);sXH#~uZ-eKY?gX~naX;@5d6D|U9O;UvrfkZ`M0OjKJ zfVjGHWW1qchzz*T{OMg-?J*IyOH)!xZkieKA~lpUo+`^x=Y;}mh7kRu?G1Ll1r(A* zDc*!jkm<`9q$OFqq3ci*K#WdZVLD#0J&0?g$GEw4Gj&Boc%-)ui3YVg0a0MWoBr;R zyfA-R0jK5r{Mm{-zCEn=@^nm~AZEd`3fZ-Ug!!q2L)1cK2|^~{Q9NObTqLc+rK3?bH#PhD7w#WI z8aNzJSb&b?)p;Opm=1pifNg>ncWCDHjZLGJfRlNB5JTUv|BS3R`7^n+SQz5*_X=wS z&(X=+FcU`iTFNI4cgVUX_PP0l1wk1SNNtUw7l9hZ>q)z`->5Zjdg1yUUqPUG;$gMH zu(#W~ZtQxv=;>nTQ>)AOMsOxMDMsO}YFKFacF)<*g$s1|&S5uG38~b2KfCd$pyga8WZ$X zyVPQvL$`F>V3Vc&7p}$_tNYSzD%Az&+1`*2!Q)34nr2yY?;ZrGz_GP#hO!?W6u%yq zUJ+}Gl@I%BkWexqyxBINcgJzPQ?Q~vLwzu{A83O0f(9PG%t&a70Gqi6?i^fhQ#|X3 z3u<*Z$rnKHN6(eli*GK<5ZJ|BrCNJmF%UM-Gre`e>FCEg4LM%H?r>3LuJ=`?77TYx zdB#`ou^L5+@n$kOEFH)WgUy4k8GibzleEG@TAB|u7z^m ziNHg7VY}@&70BWoM}gNu)2%t5EsT65f}I4vVeMzS!pS&|uCYjFg;0UEsVOM*10uer zjK5A;z`})Y3>d647I(P8u>tjm2j}MY>jj}i0G|mMx8+lq0obnO(K_qG$@Wkvmi*>U zkce3*P>COyy^M?W)H(NX-+eWEzsoBToLi$VNsrTj5by!UCuiQ#6jkco`-=|VDex4n z*B=iR@d#el`@NtX&5bJ;xWFMb|C-d&T8>263=|i>^beE@x~;5;4w@Wm-Cq^1^*a=N z48$7mZwVviNdEsf>CQ+x*yaekJAa488!qT(8a<97Kp*@9JpdNH4hEh|K>XZIeXm>4pNvkR`up<3 zVlS^CAT#e0A1>&cEFf3*UIu;82G(c8$$Qfpx@aY z)Kj^Rr-wpJB%JRqwE7c$in+@2(|graDN6d(xi~}aZu7yteJ@Z`6`LYu-y&##mK3f= z+Ni4{nQO(u+q^6W$>@drRzd<`t8pF>f1e^z;H0$zPFgzHEp-(6*bBZy&&{S%R&3LZ zjW&A#paEi{FF3So~^x7@HtTaYIOm{h2tO?3u zKxUcswQ;y16RbM*SQ zhQQ&k4{Z<|Yk5aIw7SD6--=xHfV^7w6z(z|8`sxa?)NqR?v0-*^=<}^e&YXUcClSo zfsOzn9tx@IFGmfK|9fO+{NIr&cYDs}JXIMEl!v~wZETLH8H^>`Ve@b92>n$WVVc#A zx(g$h0GDU6fwFQs7Tqo@6_wJb1U7DoM;{t){C_~5mb!=IEc1$3`-Lw-adoEUE`*>~ zC}{pEFuLqo>;cFxc(wUohyGQSI_|BHAOQ_pM6hzbcjmLz_qiN0rj1a1jHdCuB$7sJ zt8U++r*BygkMxKQ+%&mX*IyPo1O^Npn|BZCrKa$;$9j$=6ctOP*i0miEJ=D*`X4+t z{{H%*^U_nB?X{{(AX7P2#7I*?YL?Gr@_(# zP8)*xEEH>V{R3<01lqsMVw*>|)Dd>qMe6HzL@R?KeYOIT39u+KBCz8YRS!~<)k#_qeDgOhvXX-B~XS2VBL^>xC)dDfXK97&|?wUW}n(7fEW3? z{1dPxNivA()e~qnHz~bDFsSX|_;8;yJZnEUmGVDV8D9t7x~cY2VI!;068v$v1Vo|+ z*9C>Ho67B^#((J!_otCoI{kiqxz$0pq+Cq!Xd0;wCs_@}f%^Yp$iDxd8}rZqtzoJh zC+w!Hory7^Ger>-M^xWefX0|({IDO0IXQ0WN-${9OtyJ%jZv#Z*15RlZU;O z=G02?x0{h5H!*tXDxW)t9*{nIETF^~lajMyok$I|K z9lpKXezkd&$J$dq#mRadDL--Y>K_2fR<=>^$+>xmpUNQM6cD6!X|FkeuYOkFEZ{WT zpg`{GNf{89uvDKxJ^%dmb)1>oYZqR|#JPVGYq^KCS6$D&jg|D&kyIR}w`EPYuh?TR z-^Io8Oji9K?Yn9-A+^l?AfrbN4l9bs=@;PB5^gi=NnQ?j&%_PzslAb`Zn%@&qcU9f z>Ds?Ze8^;t+QMMFHOP3|HFPyr{lR&!ilkCLe-`K>|-D?YFo6TTQ@yZ4#L_g;ET#AEksXMl#D!WaF3t zCu3}AU=#sA%}<&#!2FTt7laMydc0ANIan#bJ2gqwS=g~XNoyI%7{w}7W9bqh{ach9 zho^-tK-xH6C{+90RHjiN+X0NR=`Sh_C0QS)>y|}MiV7l!7PJ!S?rj4i322 zDX(lh-v14G@z?y{Dt&!`*%!#EqY6uki`5WpRvdsuuW~B1LP^+1p;P+?$|d@Ob|1$H z)h5lx9_|`jXc)-yEu5T)!_{0a9V^N4>o9mvD%JOtUVhe3adnG(Uiz&fxxsVMgc4^$ z&d!)&hAE5ho_W%{j@!3ZMBXC#p{FU{6@|rf;0K#E;4V%9e z0Kh^SUs%X`aY>Ls=gP+UTu0SC90w8@;J~ByZjaz_Udf@f0G_?Mh8EQM( zX7L*QW~TmtM5ea0-0O@?rYJhZ@d24PcTq4S9!`ka?_0+FV zw_icGMD>4gH}B$@H|*gnLMQg<=i1k>t@}Zvls;sFCq56^+fu_$NACF!Ty<8@OK{-r z3h=+&slPiFPwT)fP)m=N<;OR>7bPcge(P81H0&=pmO5(4pIz2=&Ezf4SbRpdo1bp2s8j$BAFiiKrnx zWGqN5{e23Lct>?zl5{We&mn7mK_>Z|OAIm0UMX7PngPTjq74U@*8s-LO$-l)tm!L& zy}Qz~aQmpsZ$V}?cPw38jLtzIq>RhmAORig1t#KwYiGyF0M@c>{nhT_L*zIxJ=*jn zWQEYW{cU4?`(GRDE9a}Mp)l4!uH8_80iBqg&Hn(ur%i6?)38>B=$Ut?J5b!00WcwW zW2MwhG1E%`Pl-n=y{)bN2R~OFhwoL~XTbUn7LFls_ZR|7n{=EskPJ5q7mY%Vfw4~s zkL2m%+2!f}8bo-oOrd&dNNnRZ9~zAAm&Iwe_hsX)42)0WUyYuxu#*?v(TfmQ%; zX95h;Z>XbLtd8Y;2!|dKpoikzczC$-84#tIEj5RtFS!+M{=Gjl)PM&KDGl(CXr)si zTdA2?idZRBZCV^%kZB?iw#_`%YzrKS&C~kYK7SJ0kH^=aZ-fmNI}LeVd_H@lJd(6G zI6U4*x49N8C*X9W^0v$zMJQetS$dV=ceb&Kdwe1Pdn6)kcU+NjAl!?p+<}GXz~CUr z#^}edpg{LxhoBqSk^`K&`nu~7f!$k+rWTU_^j`SZJYm9IhJ`N5&T`Rq%L;jT!;J$a ziG5*EbMTUXMRMPB2aDjd+oNgC**G7$AfT>vob#ngIPsC|nopZ3LhqSw4>d zu{wNA)@LM1^??LrOaZYx;Ll|IZv&R^zXq(u;^#yDrt|l-5L2!pJzc{`Yv6C?KI=g_ zZ2xeMt`w<^&s)O{Or0Kgc9-1#l@G+nyU7H{Q&MuvLb3{8gs0Y6&tpqNMZe#F0j47TG!Z9C6xWue!~Lx&~=K^Nq%)rI2p zwSX%_1(@Bht%voFtA8;K0M`!j4!ho~!{pMvW{Q4myO2)(;Co#|<29GCOk^={Nl`T> zVoOrt3xqGf?GK0m{kXV{EBBpnvHfp=j9TR*=4@E?vD(R0wH{o1x;v?OH8~SX*v0`-^?8vNu_=4GJAbNi19q(#N73X`ofL~Wa>QC zP48vPtvo%u|F}o5nKmtnkIIzDU-Wk&m9yhbDSu{5dV7zvJ6qU=%+0*X=h(sf8@>J$ z?UPp5_pqgLF(N+n6MA)Qy$neQ-A9}ts50wh-jz6BLyivsqQhzcz@gOqq8%4No3+E3 zWx)$5k;4{`Ri*q6c`q&ISp-MnQ|t%^>rP+}qfW0g$_1pbLKSxo59q|TxQ3O&Vv)BX zCYh_8nv!g=!=xH$c*0t{erN(kbJWZM16){8OoyiPc=-z8^cs#GOwnw>GB-XLDNfOD zda=MhBnpU4GrL};s+cACgUv#?g?J+3wd1*6eP#6~^tF_%fNf53;n~?v!RLt}%8fQZ z2LsIR(bZjCY~*wQM7yf(pgZut@(0%cwxDILiXMfwUf7u4-d;On{p5b2n=p>oAVHK) zNu~4+WTsgGU@7+1EQWC06tE*>qw~N7=$<0(-fse2sleg%>2rNWAd84oKG^PfV~0mI zflBRz#IQmg`Qs%o)rSBq0HDa}!fZCSCi_)z%kejS^>*5t#GIvc!eW&9={O}C&(}{E zKa{>Q*Dx~;`{8Eui1S=5AUBLW+VeA4i=mmZa+RLiVths6%nJk>R?L^F;km_Ye~>|7 zT=fRxY*-fuKwdJcU5x-&=lo;OS__h(#9$yOMz}Fq7)Dc{AG*fl+-jg5_a z7!G`=e%ig+@C_2b@i-ymrq>(t3Y)jWhYCF~`fNWrAoK6jGX8&0OCxdDIcnkP%S+$l z;;*?4GtydUEThE)wsZolC^jA*HIUH4i+kr0k&)un?x4py`LVo@{e|!e!s2Vpv7)m# zUgm+O*Rewo;lT*?LF|>WMsly!NBP1{sN_dPMDYn&DISk?zt<&tB7ZcNd+DG^j_Pjr zl^KKiNTIHcp=M}}vE=MRE8FK=y{fNbS#a^HFHad2Z!XD2`-Nxh-q&;1c}7`sfk?vt zY7l`4_5Fq75=i05d(+L;;>QDdzpJb(?Yx;wO+_Mq3A#C()kIahm_4hncF75-uMu+F z$z@}eUzCzJ$El5BwqCf58pxE=pc~Ah4ka1#x-+~7tv_U*J-?uwtvmgmUgNdSA!E7V z+tqS%jjVuoXK-349`Lw5q;_jePyC#4k=$l{Cpytycm{m^7G^lC%HC~S^%;W9MyR?L zPOg7bZ60VZc$ouJ60q#Mk7=))DQrHrrkkbE-+G+*QNaRutq~i0m%DA^LMj(+X*#gA z6@$vR6W+$a{!M$a`n+AEheiba}{ZCqnZxZSBg=T(@PYiwi9esQ|2Zh~C#o`Q> zM|WQlZ&ct;=#UkeUiw@8TkNa*@1~s)+JsgLBO9Kn^ZbHP$Sco@8yOwp7K7-^^NL8n z_~+4M-G8F^!@|OJo<9B1l7u6GZ#g`yV+TY^h)GDS78H#vAJqB18%;f65s3=!^14Tm zL6(eNX!l`nsFK8mKG#aJFtzLmLT`YmIx1aWV$%oBPnd7KOr5{G}ZFNJCUArWWPMce!Sb2RCzS()hl7Or*R3SmM>S@agRH@ z!<>jG>U7LUYHT%z$Zh4SPdsNOg=2%a2{A`~gRt!2?O|rCxnCiE$4jjNz6Tq!>r&*M zL-Ld?CgEvha2*{V2O_jFvE$8z+0QFXI=Y~nhE=e)T&WjC`-P&97(k z@wfTu;!kljG}losz!pwtGk^^YLb=7;No-#Y*SR(o@XJanGXDCSZ$x@BGOcIwBfB0r zQ~CxdIopACsSZ4d;^k|fRDsq}&3fg@F^F|ha2>P}w0*ui)|6*-08|2$0GU?_NlwWs zWqWeYmv^ZErhspjPV=O=H&i|xIjeR%p$;Ov=VPx!$_R4@Rirt}Z!!QMBfRhR$}y-< zR$bxP;e~}f{25I2FIBk(MtW#AinFzze_t0FX$|q){B@F@|KfNvWcs?PxCs&^6c-3# zgl*nxZ8N3d3DQaXyn_KXOJe!|xK9+%--97wJJYg05 zAGGM#4<9}pam8*?#Okm(dfd`^*JAacus(%6Iul;e<}PA)&b7tQGx5M<@exk)V5a25 z&6aTT_*^lN2^Pe&MOx{y&iHMCe(CUF=t5s9xC7iY=UX3wmqXG5tm$?Uz?1I-la?Ic*@jU9pMO^#|Y9tk3&=sj` z14X&0BL@4Ek&BE+LT=86&z@9&rCSC`(6G$ivEWW95I|CGG~8}JcksSf zIW}=(q8`KMt{|dBM?HBJpOM!;1bnO;T;??!p%Z0h)phhZ7__Nk5S`OXGcs~r19;|C zk*H0)uM_SBW}II?M1aYJ7T$mvm5>iDSGK8CSg0;CgnmJr1UA>DqI{3tS3OnDFK`Np zV87ud>>FD)ArQmvC*Yxz!uKik75zxp33#Z$99R)AaDiKG0nSlM) zD^QQYMr)?|#*drr4AYJWgxM4hbUA%;0`O~`YjzwQoSu1e=lj9I!PWQf-Fw8!Dt8+;7ugl%S!kIz z)8oa3OUJ3Aw(7xdtMO<-`qyt@6R*nia3m-6P!X_A0`txXIVavF5Rj2W2@V;8xigId z6$*xf7T!OTPAvQ7ETwG{_&7?^;(4q>&rMvu3i$^d$RqYtIx*NJ*9CzLuOq{_uCSA! zo2Y=BUJ9~{huyHxz9Wq?K+q0DqT8XPc^u(J5PUwZ?|Oa;Fz+q&T$e? z91P0l>U7KHeMhvN++4VBghj4z?1npGqf^3e%`sLI)NKN|#B?BG0Xia-2{?XQO z^kYFE$mkw0@0j@IdgirhEr(c1^*wm61jOcs@Rc$}eP&UGpucnAI{G%X+X#^6uL6cs zp>`4wluKBeF8~UpKvc7tZ{mKHnkpaJh!6eglG3X0jVRP{@h&)y1Z=Z3|9n3J;J%56 zb-^J&PY(imTEE3=y`IdR64I;^ZUaGy8!+y*0zP%u#a;~vRB{{0m=AyVhzH;pq)&J7 z;*v7kEL4OU0b@pN41vyFpi+k}ZX*=UB}~1~z+uCnB+%@*0cH^MV2WnIo%VTkctpN3 z0fZ}5K~S~LV#lI_-`Bo-K|$iPz^$dD<@$U;G|=`$@$X_pf@>XdF}5>aG6a za6n|1793%@?c9~)!+DA9CCfaAeT>uQh8KZ=OnPaO2ZhI_w zI9~(S1mIscO@U7V?%?+kXdAeOD-qKdDn#D^8!?4m}!DN652tNH>c zqv^K?ECkapPg!|->)3E3lxhHe`Zu~NTOS-4_dbr>@759}+fr{y64=f2OAN+qwbcCy zqHgHZz0EimO+CoxZnl~F2N5|qN#u<8A4F5&@kQz z4ar$jPkWd>uZ)GUVBAw}3dE+qPp_(aZM;UaqGhdzKQ2B7ESxtsr&Qm%Tt6jufm&~1 zc!o}{510Y*2@UK=gM`VeFJ9i^hJ4$&Npt$XdKjt3RGC5V zp5)xHZf>{5f5HQq@-lFRfd5e6$ZfA&NZ)C@QmneJ!ScUCH&p|}% zw-3+OHVNtGE~Nh-V847ijzYKYsRs(IKUfHJVZU zlk&bTefD-%faw=T+;H4%b14B>mDRcZC>}=hbrHa)dEs{v1bz8?OD=-0Mp72D_Tt4ZFf3AGwRmMoMG6qrHI2>7yA6okL>-x1W&* zzywT5c{I+_s`EvA=ELy`{1b$KA%`3|xZq5?AmS;8S?%rm@uqc@-BhV!Q7 zM!yq^Z*=BOzfOMr7P4|Sdx{@d^%W46uKc&<`1z~Uq{eQ(DL};U)Jdy8LS3DUjW=P5 za;Z~{#X1xYAs-AEX>FgyDkTCLZ$vVv16661Rvwngd9s(pUy=td0U7c?%v9h9WJgT7 z_gY6j8>gg-Pu#sKe7h>I{2CLsj5k;Mj)cLbat)m=o#mk;3W*d=?7JVB5I|@Hl1Qz_ zYCuT%Eo^UXBvPS_^<*hhj!(YD0v@OC z4Peu;S?|fkEv+O6mHJD0RS}om9J?`n1rg&}@I93ODZ8|C!pN68xX{k@;ExicT~EP z2VShP`SPf%7Rko1UlX^sih&RbL%Mj)rx+H=2N5fcCLjQxf(4Cr zJ(~8*ex+diuBHj=FJT<49aIg81JJz_g+(*U z&B03rMLbsQ7-X3m@z~B;{qaq1B<^pGzQsD(_#KO(|6YrE@MH1mJyi;7bTu$CT4 zksc!_!51{8Yc&7_*Q`r4BDk!?tA6xHDei<8yRhwahnd}7o0yK1|N04t>7Jfrr3B}x z?Ic5QGiQ`MF)_&(WNC*sas*Jm6R&{lS-)KW8@KHSQ*nM#>9kmNB79Si zuS=6O?i-XVI4RNZagqk9 zqk+^8usu+FrCuN*OCA~;7TL$un>uSzB;4=s>t}jp!I( zFoe)g^$Zd8l|LCBGRBXfd zcArzLCZAuKv+SjOACtcJk@>qDTIt1V^ZJ__mv)CQWhEB2Ii~aPJm}3GFAY!p{iTUv z+>_efd=Sr`gD7n!!ykG5`)Dnjdpe||0zmMyDjV|q1@L3C-@iPa5zmEXJ_&d)J6RJJ zT%w$a?wa~{Ibd&OpO^@Kt_3`;RV*kjUL10q5wVC6E6aeujaQ_}l0);2v=9wXrUhNC2W&PtpJ%`k`lYc_sUXl*VGY9>ae{v8eiBtXTpeA$}5G~a~Uxuy0(8c zIv)RNKoHv(N9)HoXY-K>me$tzdWk7o_Ns!`wy*L!K0N&v8ipje#B|la${Dum9w}dR z!(~zqA+S0fw@}6MJ^rIU0BHo*`l}n?A2#~^~BMx28%9( z`0aECvGcF}CEfF?my5o~p+Y}>+$qq*C5Rsq})A$9N!ZK!@h+YGvML_z!2u^}ka4M<8DQQ5D z0)VVku+5FG#W$wET2@ z%IFfyvp|;Mj2S=p(^oNb0faiNfqa)olCG2Y#2KE?F@ z+}irs(fJz-Lbo*(oWKIMuC!WkSRSLUp4)00HiB=z1)1L6DidOtiEA3$aT!ZtnP_WF zVs9l=NlJKg(%q&7AYDjV9tN=75RxTrZ!8m&krg&H_!pP1K0+g7aET4@^@QD$z{Cbd zpK#E>PiQLRf*miem5u9REY4=%qr9EWUiwwL=HK{LkAz{Nm9QZFOP8s@f+=Gl>spQ5 zbYl?{72oE%d61HYW5iE>^Y$;!x$)W|>OFe2bt|-~Dtlx5;OSY+mu;YBS@yVPpiCj< z-J)2)yzO9CBMubKD^GJ-i)FOd1Sx`E3h9<7(`KpNfNo`0pc++PG`i*n%7k7AnTCL*thu{TGwB8e{_GhJ4uQaC z)}#76-NwQH-thX=5YukFmCHck*>D7no%q0Ha?*@ z3W~Wb_Tb^~EzHe$%ro#=IjQrVNFJsG3(a6G)*P(QpZ1bbpDz)+r+#i${_1VBQrPKE zPF~n)gnQS)U<|R_mv}`kQ-Pmw^~E#T(H8mf!qPwZMofdQ*^i_S3B7JSN^wft@06g; zskRMUzbf=cQ4iHZ5-vQB#;>cBu}E|9i$>f+g%nMdud6>>j^fW$@a0XYbDOL5TXNqS zGD+?fFoF6gMr>ZI(uJp-#l5=YKhMcPT$x~ulmK3pmAr#34sf`iZofp5 zP;fZV$>}pX+U0m)eXOEjsK!Vg$GJTf00tI4AT!^4Lh{7&)(Bpd4R^hdQ)c}`-yh5S zOwdg55{7^-ACe9LLIaZwSN&O8T z32wM=$Y`?Dg(!QpiKY`^V)C;xU<-_ka{&Z#XOHC4latsA9td{`}EVjK~G1$N}FMbtOvDlLg#Ljr&`wC|jyByq%%X_ek8F3uDRmEEh(8?WcC4d}|Z= zuHWI-2Ikj`m;I=@f^9UD7&cz_{v@!#fil#VS0zFmZ-_{+PE3Hn@y5u+=lKa!W3_Ilz+_?>whOpL z&(~Q;dr^^in8YbP`84`XYF5VQ_bnHxsVP(v8aO^p*Aj{Nuh?zL*>Rox5!NI%v)$P0 ze}ET<^QN`3o5^@*1RJaU9?9k&j?cj|UXz3-%g(~W3$l%~t(i=P?eRF-atIuPJHqsi zgzzaT)F1LRbsR!!OpKJ3Q!*5V2!}f$1X zDlF7eR0NJ%je>;*i^J1Xq&w9N>Px^zxmK)0CfU_)k62W+dug z_sG`=S-940E4tR~D3$_2#EzbDDVRrYOeQA$bE=NGhOX~v;T#zDM=FCLg6(18FSjjR zuTp~`4=?5})l`1eM~t3Em8d8Pno&NkuNm+XUoV+fQ^AGcFCp)tYl&LnXw;T=I@Fw- zJyd;taN&_Fne)P%Hzc?d18*mWo1h@mEBacp#_pD?Y^v6F*x@^ewxSI;6lY zU3;Crmad7|@?~qu=Zv>fUYi`|hp?_>%MxLwRAN&C{{u(J-2ydfu_*`thkh?a0ysl zcBII zFYX`u2^@zLcV8iwyjtmuums79%!;t!AwW`Y@RJqC(9>6}#2~UypIA5V?oJ2VVWS9BU{hX>5odr_0~N z9tkIg z^lqohd!$0o(Z1+VuPo5&-R7$A;bRW9z*Brx-!2~aD0lN$WAA>cj5lvdv&C))@MdZK z@YR^`Q_cE+O#KHq+wb=W4u4u5Y7|wJTCr+I#i~+j?;Tqx5~?<_SBF)lw%BUcOb9h% zeQFb}qQq7sR*c#s#y_9m_xV51bLG0;xsof_o%eme?{m(5&Uu~lQdJ|AMD1&}^*So} znlwFS`r(kUNU=x1-@1cx%Wl|rP6)@ol@En=8$2ASp@7A)%KwHxkr=<%ajn&Uy(zwN zd4w2k#NpJMjP4vI8S-^Ws_>OiBbbf*24|U5pf@61u2ASVd#n~M-tSy(>U8`rYSoV2 z7kKWHXx+GpeuH~m!P|w*7Nyw_F*=ZzEN)fYLA_TXL`xgoG^nMsY%F!{4_j1XQda8x z!^pqZPV}lz#z&jA8kiTIPmVH3v}<2er!w4G-4O&f3Eswe<1K9(AV2=nBBrgoC1x>r3h5NhI<-_uzBA3r^3n-c^A5 zvBiR9Mm`Nax+rUdOi(O5_|KkJC;on8h$2QOva3S@T3pG+`NFSJ8PYcpq=@$X-rp>F zV)FhkhF>PZp4D^$%aQ==4cb_ajbn7Lc1@RbAEFaskZ;{lV87oQ-BIwnt#{!EC{#32 zER^H=_qL}ZW#Px&J_JE3we*J-masjIZP{&mG8YU-c(g006P_?Xt3ibv9Ic^WFIqFq z3Ag+m7E41KdtZVon7GCmNz$e<1DjgyAJG0;|Mz~XuS?&3Ot$98*P8FLhu#;=zPFfUF?;z zI%+`HBf|1V;`JnWQ}T5oXuKO9S&q{vQZyE4{H~Es!cY;u+}MkYou=3So%Dnq#XT%{ znIrLL()@Y*oMHRv7NuLv5hAH83cF56g16mn>;jiY_5XTzS>my~Tl`h(X*+SBe&ezl zN$ffS6<^bsB0B9ZdEHhxGv)l6bh0HZ9e-r-Q?BZy;Ma|s4*e|}y$f7HooPUltCvdF z(l|hu8mT@)<@U(tnLih&^`lCoe-;HX02puNs^E40>cP00mZ^7*=b{*Z?$71P$G$Qx zb1;~vq~v@TwAHal(OJFBh%zWynu`dRlp{P46?gVdqCHJtP4b+pa?oV4vgLR;{FwC$yO5PTQ7>%ZfQhLBPR>AkwyT5~}e zd^hK^t6gy)1SKY#fZ7$T8~cL@tJWON)a$E%R#xq_bHJ{g^5N<@WvlnB8x{PWcDK7J zMPiw?W9)fWY(oSUE+%K-A{Ry-l*a1!(?Wy&A8lX)q_lyMXMARL`j(l< zi%+FNc3+^a?6Tselzn3wi0hu`N*Y^V;B@;;cd2U);>G$qb>VbM_g+hUQQ37NtEj3s z(E7Fq-?l`u%D38**qucbt|qZ?agylh?SH=uDR#jDN1G3VN6W`r99zwZ(lgmYBd7+q zCvMa2?ikL7abmSeuVrJPE~3MZeOU$`?L1mv(t4p48hCDznup@{mB_;pby=j7q^H{e z9HD;;4$s@a#yv{saxhlMW+ashT5`K?usA~KcE_y3PLCBv>8Gka+7rXt+LIMS4WAYz z6yM(vb%>@(+$;Y88+-;9VCD81dIW?E$d5LD>BBnyRxguSlcquKPbN(UQjdA-w`uBh9*chVEU=bir(aTjCgXk8 z#>m8^?dR8E-5z2=f;j0~1gxETMg+4jMZSqjdfOHeh+vuMxf9}%;mQ>I=5SeHB|7yGo)M)zAnNEibr_GBFqMrQq zq4=fz>C5MSTl}bwD@^_CNLMrZzzx{tRlusMc*1yB!bDQ|#lgKX-(NzI_9fVa;l}x6 zv{t|03)f!z7Z*=s|Cv&PYBOQZ0aYKl+%-A#?G1G;tnSkMNiEP2YL(6tHhLdi}M1 z|I*)9dw91anE}g`Rmi)h$DY0=uFiY1bZ?*oZt1>aleiSpk{G3h$YgD<`Zw80@3T%n z+lNtA4OR!qzg3mvO>O0k{qQsd6Z4*+U@IRE1xeCI{KVdHV->Nff7$yrK5f3O-S`I4 zTz;KmBS?Kd^n@+2E>t$HLW;%h8{kXw_^OHX6go|!i`AC;F-g#liWSM)s;zAE!mn-z zR_L(>o^SA!o1u^rF4H=y1j&v0ZSJ!Ie^E_ld2_WA`_>6^O_T3RjxG;-J*YYOxTEh& zrQIW5{jEMcU-coGv9(duni;5R*dKK9bspsH$zfdJIUDot#$uL?YNSgqkHs@5jPSQe zm+cB(wAVJpR6}4q1&&XqK0G>8fqX8{Q}SxGXUrSFA2=|q9N8&%DZF1&Y#v!j6|WuQ zD6eY-7wazWe+YaKC zvw5@-+1z6AZlFzL2!)uYhJ!Zj{9p_oCb2luIG%I7n3TZY9$Eh}L9VyorYsP2z zwR>ofVJR6ecz%wo*Dnnm{-DezKn-cz%-@6aDQ@L7yAp1%81;qF*d?*6gMn}-%%OGt z=lbSq&cicp@^bl9pwd#rFX|VSd+-Cta#G*F3{P#`w+rh5T$J&A8tcG-{1Xdxnt>gN zEcE+@49M={k@%|?r(utk15tS~u8HcIyQ6JH_0h}agkt6B#$w&k!~2@hB;kPMKHI1pj8`X<9WPNES@W2m&1>f2Gmli|-!o za$km>+MFL=shuC5Ti&_&8&9=CIkm~lefNU1DC$^zs=Ai@F1A>#ODC<9S*@uG7)e5i zB$;4WvD1eo=z9mAZV*&_Yqj^vFLy%h-;JVaeic7L+{&6wD&f45$$A*E)cM%R(x^E9 z6Ytl5PYzT@;tJ`H$&@aN7y`_U0V%*S(!LcvzE@6NE4Fl=i zc3X)7@TnzeCDl5p4^E14AGOCa+;V}(#*Mj+_EI6dicBy@(Hfh7-+^=<(|rg#H@tJW z?acQ~jj0oG8LTz<)+YJ6Im|_agPCkmi|FK{_{9c86H1!blAEqkyR#s`0V8dOR(2xn}fJJF60O)7F1cS9CZcMkhWN%Gk3|D`g znY5o4N4G9Crz9cu70$Zjp7hMV^JpKRhXy_Md&s+zk{9-K$S(2$Vcl^Z+S2N^yTC40 z=(}*)?_I7lcTzSuQlyqDSd4uDRL6KyW@7a7>u#RRC5RoV_FNKcIiSd$=+`gG9z@EJ zb0h}uj1x~Pz<`}#gB`K=CGSq4eJ@r`Pl_5(lxNukem}$q%x;*TdXqWN7Dv{HZtDiF z&7G_ixzFLTsB7+plXJ`D6a|v1X&>2b<`t}cgus~nWL*$t(ql`<@)vq7Mp(DNEo1kA zWlmFRlmG~xfu8$XAc*xyAts&vC+Ze}r@;V2{!w{0UYa1!qR*?=n)99|5j8q`lbfBy zcfhxt7JOC+wUrZE8_qS_c+U4Efg_3gyesVGW9>}Y#{N=W0#x_hn5;#)nE272BkG)ctjb-Z$~AheaDo85M<+Z~7BJjsXfSLW{JS&w?^^GM^ebUL^DR zfEySu-HYp3 z@ip7X2-kqbtnM7+yzuCs4k!E5pAJNC?zSjl;sO>IsIM+lt)+eZ8Rq_-g~%MYLY$5k zW}LsbLKsY_#4Ps1#M@o2^S04e9on9T(7tr){e$AY{gG%$iT2vh(V}2<$o_74wpht- z>x|)iKwTRN6lKaH;p(`$qs&KcZ1Bv-@9YyoD_(0j^rU=p_N%=^F+q$vO^Dkj%%Reg zvH(rt@iLb7q|9KhdNcz0mfR&%>)}nKlH|xHVqW-U!O7law*uJ=ri9XNAU(}a*(;%s zy-(%uFqTquLcB-(soHUMqwF9NBA=+QK-7sO1fLy_LC-GgpqWR6VZmyv!@604C!crH zeV)+t_l&8pjGirfOU_hSn`ijjydWf}I><4_zD{LY-}~UXu{XAGv(eKKL*5)}fYF#W zwhrrRXUhL_!|ceM_M*6OF`{x~LL}BDb!G|(7grgVkMqEIpS^dMAQ35BKh}xHPu5;~ zANI2|pme5Mf?J^O*UD0tNkC?1ZRpwl8QK8vGA)_{U5T*+xvsxr{%ah*fg@3=?aa-5 zw&5e$8Nnj;`wfE~H0wfbK}X)I`oqgMj$614Ix^^N*>{k$Yb+JV`#|R)ERDjmy$=_s zMf3_a-Mm0`m=d_;mT8XbS&L{zVmOee;oU3b+Yp%n1ozw8kfNOR+KZRYU`GY&eBdcMy`GZ~$ zHjk#^$2l}%gn+Kl`B%XmzO9S$9-ge16JC8acFMZaU8D9fI1`I{&%E8BokuSOP44f^ zl#kY!bf`;h_^ZW|zFZ$!UMT%?tD;DrIE&ryVX{3(MxSog4Vz5LlR9r?S9q4cEccuX zSGaj%g4SVD)~??Xhuq-!jc@n@a41o_rHQeM+`QfieR*|~*Fo4;koY@!FHH#gjnn)@ z?iG}94S!L$GuMQ|9tKuXZg}6iZ|7?j(oc>M=-s2OV3?sR-yptNe3RV4rTA{F^4**L)3G*2(7Hh3X174n1G|Cy9+ zh8;)dX=n5MowlGIn;khPt$c!h)tFmZ>(Hj7dBu{6QKD$1<4*1;KB0(O=Cxtgl(F-o z&qCuC(PBWd4~rwOEJdxPs?(1M>DWQoLHubP>$^Qm0g&S%d1j)NR&N3u4D-N#ma*3( zo=tLSQ!fKF*gO6W0FBq2SK4Ozuy{@Tc~`y6ms}a^q*|R?rgZI!kT$=fAg^KkW<8 z=RH51Z2b4>HFGh=)CBx3OfEI;JkV{ ze&$;|Vvw*h{cg_*f!A{XJgZ^`3kiRS$Bqjz9WKmxU7q-Z_1G17`gG~y+s=1A8e>gM zH;kHGo`58RhbED8vW-+MlcElN-jN|3vXlRNuOxj%}fHfhQlNYQWS zJeeyh^c5ZauHY{CPoa0gI0NmJK#LG(@wyG1Ud421^FI0Fxh+FE#UlDDu{XcP?DI@pGA-EuVO4XCzgYByfxFdvQNMO~P4UUe!TWW(Yg)ezv5C0IFlJ zv~{LDCFJ+EGD!`FYd0n+{Oa?-eo+jC>7E-+HB&Ex8#N{hbYy%(I<#gT`ib+woyU(3S%n^9ezJu!e} z%hp}q?k{-Zy)=14#w8Y-^OX0`0qV=+MOfNENVA0zr?d&sP@_A`=aX)n`TIK^+|OyB zLVvn5B?`3W<*UpJEUkr9HobCam;UuudYr0y52AN35WeW!>u;ed`8m6gW#S~7ba1ViX%LYW1Y5h7&W#!jpzcP0Z&*mZ>);Yd^Fu9EApUXq%0VBY#w)G6Qdl ztt}jgj;B0H$wNeQ1Z!Pg4L@1&ppgfjTrP{H2|oN0@VkHF@?>*6G@-vJL7q4Fxv$ik zeT$!mr2}fG7G$C~OL^l1&&K}s*G|~2L0*f1t%xIYL<=I*D!489uvP@Z&aZ zJFc=;(jpPXHkWE@O*SqkQLP6yPc|mDxy3`(6WBAPYb%SXICuy+sq_2yDT*_LyEb>6O-r4ywTM=()ne)*!})pH?hs){~PYX#=X0)s(~12L(K zqm3RM7EP~^tg{}z^h%Nc>OLNYL3$}PZJW(aMIf9czbP&9AS@-&rxaV2X$)Jf9}u)% zjt|kzd}irTrIYuikzQ?JrQUFr(OYU6aS!Cu3q1>+5Jh|L=vbg%HB|k+tk&%dsHU1~ zb}QQITIqE}iZE0gM_1oup86Wcqtrlwv>oYK%t}Sflc#DnV8De1udhc|8vePbgpijA za1cVltn-~X27}$E49jM7y~8t zIjTJmW+wdxw|UNNfQ^ed^mvGQ^q|G#$3uEjc#J#uxqtf4UGC*^O&brKO%K7u`FB&M zz_Y#IW1@pa*IMXLF0XPB<7vM(^lzk3JM*Kep_uAv*t5 zrE{BpHw-+xzF1hmhkM$V5UzKO%j^2yW_CUW(oiQgf*}RVvH_p@J09Ho@2F&dtIqnH^paPc zS-=QI!W4y(kxgNt5tL6C2pp1Liu}H3<|DdJa}`87@1TYfe zV9_JM4tlAkY8=z5EWUwFQRX~Y#05~B@uw8NV68&q$CYoa*5t!8w_Y$cK^|@2QJEuR zplOAEjntY5888U+p>P1lFj6>}JA4D?y#OFg?f@)t`#=rFD_()oJGLLCE}jMoRa6$V zN)B3EQLA`A+4EDc(&V%z@qYu+zohz=I$EfeqWW#GPGA;wM9@jN0~wVQLo;`C(MVm5*{{53buENeqP3aHiExnW+MZD`8) zua*hi4c$CdH1jWDL(BS9YK`)ZUD9NhlbEcT11;-3YH+#eL8)=7#Fe{mKk zxBr?=+=hZ45G?fYYTF}WeY>*(_Xc7a&q??hM|*>I5}817PQhISoY0JDt59>Mr=wY^Zl?KsC2VU zk)G}lV4L6I+=XxQd$d*WkCPh7U*-=(J5LSK@V#Ah*tXFW+PNeQg)~u|Be6TUAsnKQ zGxn_4^f=O4(=5Ou!Y|W>6s)u;67d*8d~365;@4!xfgmwx6pP}o^xJf}6-(H1z=s>b(k z){4%X$%U0_=)n=T2Zbetr%ugM7Y5%)9u=Q`8d`wOsm=fD*V0aI*}-6ASKv+sJTllV z4K35Dec=`YlBXctgt|8vAmm&55?#Xq7b^DbdC(EAVD6~RbdyQuZ~@S(Z%Ru26w2{) zC%8v_-R_jjXd%Sp^gl1VoSzy^yY&aPTeB)Rq* zEmReEK6vvuu*E^$_*K!R)g!{VURL942d!#_YkP<|j)Bi8Y-Qw$j*MSF)9Pa9wnCCu z5G{V0Bke9nh;?#GaDVWwZ&F9*PE3E)3r@$M)kJoqy>ll{f(adMRV)|tM75+lHc15T z6Y|$CbXz@7!r>?9dwsd1oTTbCTUSos#}X-}=V3GLSEcRO_XQK#irWS!9(%O&u|01s z0G)o+$$F}lE}X&3T*){X<*N-Ntd2X99Nk9+E{l6bEl09UOhr{jdpKZjZLfE^XBq=u zlerh2F5}Q#wX8zkd_Yp^5w;E;eD*D23G@BC1Y(XXBYs)Sfq{@a$t6v(2DUN9s4_Mq z0_}qr8Dzpb*JSeD_QHBDS1gfYGt0+TLLb*K3_-h>%{_LNj{3agu;{o3?~kZ_AFtAuvWW&!09w9rZ!2dih-$) z!q08QOoej5XD<-IfwYJLiiN5)Ei-g*bIRPPmHN|Xp$C10tja8 zK{Bj{1uJURq>xr_y&cNmu-wCC-Y3GqBH>5xI#a?%v zp#3!{g**FRg07tK$^3QVY!N6D`91?huz}dnnM!uXlFkNJ=Pc*XX|5|j%bj07W!!MrnoJ|>7da5d1 zR|c_C9LlmXP_j)?oUmzKWpEbQu1IMs`4Q<-Nk4;K=BL(elmlEyl zZXn;RWmis(G=}#^S_7>CXw^EgiMcO72O0x@0e$XzF(#Y<6 z-WcXWZ81LG`C8vx=Et#uCF@~vwFQrG5=5LWbm>%V6s0e^F?u*BJIvYqOX*I zP|vjOr3=*GI8$1!G+bWY*P4sk@BHK&|8_iZQzp<_mHcK@Y*d1r{m02J+LCBa2SIyU zP<;3omnAY6`o3sZ0hoc*AXRCx^9!cMrp&S`aM&PN5sc<$obLA?Qq&T26 z>Ek5h{ec5dM@=4 zsPu-CBMF5Fh#GcAOYFEO;m_8o$lgF_+u5%r+X`+b@TB9X|;0R!1pilLO zj-IUN_9rySR(G8I=F!tlBdQ>R>gj0GYl)dOEb{?Hi@>1b2er z;++>S$gR(M{|Sc63Sy82g{E<9wd}FBW&bMHBo4fvwd+u;iF*wwid4%T>#q##)HDm) zhdg+$899`$UE^94pEiXC*|yJ+N(66WAN4x)U@8F3Y?GrU@4_p?)6+F%x+{M@5Y?Ic zlbY06!JKEXhaT+Dm-p%i15~Az;}+{Hn6CgcQYi5`DjZDM_{_X&38t&QN8DltU9R18 zoc`EO%7>9c2uY?Q*_t2DkBXhe;V)c;w&z2vc&pm#4Qri|N)t_*J}zM>GnW2OqQ6tt z^2057w|Gg4AdsPU4L|T)&>=yATeN-hB|9na7DX}TVA{J`pq~G98BI$ow03L<{RxM} zOgIQyuFIRRO)>Fko?LEeAFcERQRCC1bc+>J938hzDH)Ka)i!DAw5W7JE4OKlzQ$=R zQ~pWfVpmwQZE0MZMTc&ZDrG4a&D$|h!QcaP>*bn4dzC=lZMlgj7l7y!k2D8$aFgEF z*ziuGwS)zdJ~{lX>f!pDl~H14r>}0p4WP=OyEX}tGQfz$>6;}&YNwLNl}z6)D&N8t zZ3KOPRJMjqdVWkYdzpl~{>Go1`Sn@7idMh(QA4c{KI(DCVl4elMZqw2B12?^b@e7PWBugBCXA z*ldJ%LXJFe1OT#LpgBG9=%yT}@+!c`mOH*qOH%Oo#5CCNAh&MFZS!dOlFDE`j6fbXoC(oRuBIZ`7!V($X4@6hZB&0&1g8r-b3yP~K`#iG5V=xi1qrnT^`G-_2-4H-Y!om z<|^4M?llg$IQ&%F@+$YMZQ@sWZtfiV4=^76Kc`@vqOs<6lQ@Ky3l$U4=N*|WK(Dy;;q8UF66|HP5hJd`Ot|f_>DECd)<`GqAoi?u(&X=$sT0$^WnqvfZJvg^}YVv=^sdm zzXkV}xK@aHR~DHk2^z#pxz;~xF=o=rS6)**u=2487Ba2D3@XbfW!s%bYrCvUXY4LX z5^d9VKH6kx>|DzA8x3>ew&x%DJY+n!T3zB*mp-ZzNnSET>Z1B&A&gipF$VJ`NIhNd zq+KsGZ?th}8~@ksve&3lk-mJUru_Fb8 zs#M4fZo{e8@G~o^FbnNBkePB9-1M1c5#zm4Z;h1|jgt8D$+F-fx87hH903{iXl9mDtF&q=T@%RsG>ooy$*) z8rDq9BaxYzS$fO=v=)?fnSA%w5VV_iv7x1|`h!NX(6dTBb%M2G8Qg-U8$0&T{ck9P zd$j>~$M16g@GCe~Q&Wq&+Z1A zK+JD;oG2LH{&s80w=1s$`#>~qt{!CL#7n#okO{xz(8_7E{>EI)YkwYMrK74Wv>e&V z!oZADJ#b>)>$DEfFbLgTsV!aN0I3(LQKgX}I7taDp`5u3!Dg0HE_}KyWw+XlZ1Lsq zv`od*s!I9D#tT(loXg)K!(-TAT!}z1@U+r?)AAUA@_1{YHn%+=_;*%g$TzMJz?hWP-d>b*=+*2E2dd z%j%|!WQuH5GWAD&(}o>HF`#{1qPAv^qFL{gGxd70NijG8tk2ATYJUIbDgbO1hVh=A z2U;yR4M9)R{W5oLl{B{B{ZIZzqNH6S$`bK^XuYq8gxPS=WC{Z;v>v|v3QVEFNfo8vdj;I^X z2)t$`oq|~Gx!~Z)8QU(mwCc5-IhpwtO9z4XNm7*43>{dCk|8vGe6Y+C*&?z5| zkSCdBx~{vL)00UcfLlb|V_BWvcxFNRL%;oqB#^It1s!s#LofYyhd!d@lOwhQe{i&G zC7dmVOk}eHK|NOQh<_%Wj_AmQdfUEi^7hdy_skt%nEiAfSmDWFOE1oWfIRCGu_i%R z-Z1^|1e5>-%ZH%V(u%Q+{HPomI>?EVP)MU!_2YiH3|2|Q>{qb&gm1OOHuk_0iMw~J zgwXIuB5Wj5Xrv5XUBHh@jcSesS$ z{n?dYW*n{^G6Oxi@3IdCOGX4(Fi?k^?VaoPxMW>OIiLpuF69EN2KaO}jQ8IEef`I8 zsmT!JeyG7L>77Bvc9?Q_btQXtOhADXuiOTI`4f)cwa$>@-E-}2bi|W|Q1$2a;l|H> z*Eu22eUtr<8j7^WiMg`Qt=zfup;nmCN!4~G#P{9yq#FuXoZQh=$$Jh)aTj(~7Sm;m zASvIBICdFxwXgSo<2VYj(b$I!NZZoSX|_%}5}n^%YbkKCfoQ4FkFJ)e&Tmr>kjlh{ z^|cyfz1&HmwV$jKoxU<8@1!k6&E2|--+Y+dSdgcwVaH+`*7we%{t#+q-M}{`5mF$ZMgDT2W<`L9-N_ zUiZgDd1y>^BQ`ecXXk`k;YM$)?*}~r^_-Am>?;LZyi0`KFn0;pGA!%5AwY&%6buq+ zirRxrC8L%iH@FS7<^_;9_MQh0Ne1p;&7nO`?oTn$ipK4sSN|&Yx{O>bK<8PZtziv) zf$?Uw%tG{IYMRsQ51D1(WbnRPHX;*qzIdGynUyLvJPg0`Y}(DI#se)(Vfau>J$NbwZVD;2a^X+20|E+ctPt8p*8Gu94|WXQfsQ#Ieu%Z z*%0Q_LSa^#BiF7TNl2tHOXsz2cB<}VmIh`5Bc-vF_|+fwmvPm?O!C1O>g46Q|6g~o z7#>M(`_8*lNY_t=3o`NO>2UC#h8ge8Q3hd4(+H%&qwNK26WZ`!UsNTVyT5OquSrOC zHAse*V8308NP{&^URBv~JsctDirZ38*#JE=a-`>R%UgSM$IM@u+Xm+N=AL*oj=C~c zj!(Zm-N{!{WunslCd?@g(U^0=$ACKGTmELZttFm-8-(#A#jF@Fu3Sp0m@to(Fum~& z_FH8I?}*E4G&l{heTgt(kOM8+5CrdkNlMo%a66Dg2UwkzaXns`tI4D;aLt`cFm);& zS$HxX*}3N6%lPk?(C)-AkoUSi=*{U%(y|x-r}-ZP74)^zY{NBEWJ83tWc(>QBY}~Rx_sxM0vMLUih_+d z0Y8S8BdZXZ=5y&NZ6zgc+gu{B1mKo(O z&FdENf1vS8kj?6~lu7zfHb4k5loW?QfI0LUONe@eDN>OQRGF0Gdo zXW-DnX|*Q;`EG%$xQRB|)?vz{$uida_z`}?%uE^T@HF(+>V}X=`hN1w@3%I2-+AxT zqF7V*1|@Gx>6HhtiZA(Ykq-_yx%9z7ScVF-Lz@A#YcR+T zgfCC&?eDG!r%bU(+Skxk(RH0?Kjo5aB4LDnt4C3736Y&&^M{&XI4$^<6`-8yR$}0M zj?%`iBho^pJ#AwvAjJQE>l$x3#ZpP+PzWm1VV6}Z)zL^J)n^QBZP3FOb8Mk!oeMmn zQ*suKZ)z`U{W4uYcy9kIXKi(~i%q4s2*w`{eDJ>7G8`~m9Q^S@=uFT$GBVJ}D5NWH z0rOFY=2}>clwK54N!M0zdd>v+#;#=+_t#}h{Ea$o_yaVNv0U;?jCR=>riOJi&9jV3 zHFv|CE)i%|pPVd*_O)Kl`E5qzRAsFDN<5?uv8Sn+;bll7fPDrb+~Ugp0{qOl{Kn0k${?zdwmt2 z@%n6h^u5LXzwdFw&R0hEXX^L%i5|w#kyd83{Q#>)-J1ee^Ew@=YFmLBX{Y|3+{gG| z?QVi;E%@KHp@Ny}Ra+A!W6A#b_tv=K;u?P2K`qKSR}&3JdHs;|3^4l%#GswL{M-NE zhWfArNzyaY*3hL#dh>y-_iR+U5HY0c5^cv9e)^wYG0d0s2dF-UDaGI_J(D#VZtQU_fgO0sKtH~A_js;+_>g?YznVpUCkl)P1=tw zEl_M$(u3&=PczXbmSIPOk!bI!n-*wK5CY4_)k@4` zeEqYwPs&{_92yOT9oS-FuGRuG;0C{KbJS>)>Sy+$RQkT-tPaAG%tP!m*ea>pRX%s* z?LZ^T_gm@4_ve$UV~5dPFxKvK==l_dTv z>r7r--pIh?5SvGYwCa6dMQ`&e)}|0XgjBE26#&375%81Ru;u%(}*%GM=OKZ{(~<5 z`-q@PjA7T2e5^x8ReJ11zaq%)H*KaIP&F(sLr@&t@L#FQf#bFCr?uf!*e9oQSCPac zm-J2If7%==nRbt6Yfe!8{tii;h$}+_+}<}z{`lx=+w91sRlBBD3mI95=nm=#1i%6H zP^{ps-F`;E3W}T*HHn)eMtOY5_gX7zn)T0eQtD@m7)|4!oC40aY``V!yR{8&wjE+J z|27u?tr#>zmQO|xA;$54bF6jiV~_H0`G-P3b3z!tY%D=8*> zeJe=-5O0fbAq9iKtSwsq8Ncr|xLfyiU@J5It?o6fb-*Z|Lsseh_;N(YUQR$nm9LbV zX$U20h<`KMlmt?}O`R<1w*NZwgYO->+LBn z_4`}(7&`U^Q73(l^iNEB8o*fSO2K2hhKCHRTF#p7sR*Y2AKAR;0%;f(EF0;Rd{se` zkM6-Sfp+Tu-~;_n0gXeM1*VBCA4oGdp8^trL)yxC%A0ql_(jomHqu+bXtV8mX-Q{F zjmrJFsh5F)F7Buz@BK%DZ1zJq8<~)Q=!HBQE7%;}O>WExlUOEFNM-%lsBc10w{xTK za<=PXO|E;pr7IUpw>v6gbfryb#KJs(l7v2;VtmW?Np?nMLU{h=C*d5~7l{Lw&8|pj z6&h`kEmb9v9O-3A^z)d&EjWTK`x17NjGxd9Hk0ZhtW*g`KLwhTgVjhZ!2Htg*6D?X zq$M<&60GZUD|amqomO1r;>r60?}@occ3n_YSpM0I@uA=1R%zAAlgo6#a4mM9aJd{- z(kt#&h;@=o`EuX`nt<-_JMOOs%rc|2q6ZOWBxsGu(|r@uoZZ0?Nb=(|hW)f`A2n~F z`E6-~n5ChC*uuwspUd8|&2ry0a1YznlckJGK6nhBS^b9g9b-u=p&DcGTAqff4%fMD-?<&|C?{3IPTVnyy&yjWKJ2KLa+^qjCKP-?d`Z<`Ksi#t{TnpnFmK@N>C<+ZUU}W<#oCBYM=I#S* zamB^!6)$$M51tAUeMjIgx>;?f*7UOi+kfW2i(r#nF4e1u$$b`Ppa-?!@;f9+e8{V> zA4yRh{J-osJCvobyAR3rOewup zzjN`-7r=WmaypkwD*=50bIt!cb)0olQJ66pU^;2FnsUAb%z+M8e^6#Rm%w=+_(k=> zWrR}{Jkre_a&&6rxyGnbR5u+l9QIp?vD+hA1i~9&1-m8hnvc)VEU{NIO!}E#uiTk^ z`lgK4CGHQ(#Ls1B$HDEq?Yjd*uWlA^vT|vkkTpMd7o_GI^TUra543oj?j!RM7a`EP zUv7Vs%jM0hc4-Pt9DAK*OvuGdu_9IvMU)=gb`zmhB54^OT4d;tOBj~zAu2<0qk@E7 zzRkBpDSL4HMwbYmY1G>SA^TjwJi6rrN27nLJrIXAOk*5r$DtKgTi)$ z+Z0}#rvPq3@%K{8=jUS5su=@h7HRJkRNBSC71zX5PA*5=Jxle%e7`!iAiU7UlhcZdA7v8W=yvp{^09F0S zfQ@ZkvsG-rZsbs=?_v8lV1&-?ez<9zo8KaVdMawM{aEYw*&q?8nUAQZ?O$Y{cuL;^qO*F)b}X-STsI!{M1U1 zut;{)Ov+5O=n`&3++NYST~W3kC2ZBuJ$o&l_zj&`XG235Ko(1s2Sh}uS>1`CRoVdk zPW6;g+>3prWwxTiWv$np9bnSu_5R^Tsr>ua+wc1Hp4mtKb*#y{AN{84k&i~HSrH1g6Am{U(f$N!$=ZhCC`cu z_#|Vmf(1&PN=u`CKv~aATJd`nD(ima2>OSpMDTbUZBp6qi2tTQK~qdQPI(VdTsmS( z8p%9;||oVKvQ|) zehB-;&jO7PD!NUZnIHKfwGaP$I%x%@x=j1qR(ET;Oz~ft8yTaYPu`6QD1Zn4l?~^j zHY(!Dg3sOmZ(s(h|94;pVir-l_mRI8XJVIn{dhbXJe>WSi={@sN4qzUxl0T}_veXm(w%Y^EhYeusmj!IPP%2c zi1ESKd`9Ror@)-Md%W%?SUTkEgf?Q%N2$W^Q+(fhK8;gycj=dsW+RzF<33iZd(5pw zUM^GU%9a@8CH*f~Y?$E710iEv~2!+pW7_M_rxj$w{|jY*PggP)>Zl7KXZ!#w_2?%Zy~fiE zHq|7a&G2LeDE?jET%rdQPkiav;o&=#EbhEr%uR~)o9S3DLYR_G%PaGQIMr+l?rm`o z5i(A`F40d)PmFKR5=g22;AY~tT;JK<1v;HwBIT`aq1gk#`&mEqXflt?To|p3(mf_F zmWzf2iNfz5!7A@RniXmw%$h2Ml*d25_Vhq#EcGa{koH)` z>6eS{>Dx$VGG|hHPo#Z}JHHd$j4+tuKL{ex)9uOUp2Qp}*>^-)VJ>XOZa_F|KcBJY z;JiccEOuVzaoty+9#2JSiIDNXUcNpe@e;FB?`11(X(*d*#P#pm=@E3CqDC@sO7MZcP9^S z?gl6D#E7O*IG<{yGH52J!%)j=IDe-)^wt)md&>|s^-eeh(6h$?*kZp`@klRvOvUOXBxF=aFOSb14dfw;ryg$5u!8<>F zKl8c1*E#1p%XQAVu5-R4uSm}!e{bn$tnaWC&D*yZ%?0npBD~+U7z>GmRT~(9BLB$E zmx79YPC2L8SKpP5F*43@_Puqx=%HWX-|X`C_^vn+!P2MGw9r}I;Hdj%rsbW)8&@#& z1~lyonfhPsrX;}kZPfRn?AF7LF{!sTj1ZzC%&)vAhP<9bX(s;7FkwCHF=21#ZpfpC zFhZh3rk>;IR64wRhE=Rpon@XDRKH{|h$X-7uB#6@-Z;cbNxmhVU#MHFMCX)qF3?=+ zaCc$V7esa6-jZH}((J(2aFuepj7#vOOlXB=aAL|>*W<5(3OQ@uSmUbu_>Rcnx;RTg zx@*%YCMYOq?U@6}p}o&_Rq*01y}jEI-zf2E$UF7deRlyNNg%UZ7;zxJ0b)6A34Lft zoWM^5Bge>V&rZ45=*VC+zP1w*?po6o^vKzMkLM6#i=C0WScLrG-<)wa_S=VF{LV-$ zFE{+C)WT-OL~Si`|M)b12QAW?f$eiqzF5fFFN8Ojc<~CsdMP8@QZ>Z1*SeIaxCp`Q zYlg>3#CxfFCkV@hzDIs;4xxBo)XF}jf0I6I&AtGg53WlbP`pZR|)HLckt@s`ribg}4G&K&_s`R3AQ{`2MviMUNjjE&*3Oz!}>=s*o{ zmO6zo(!gqA68Mxd>C{^+rPj6iT?yZ+S>uR&PIORhVY=yR?(r{DO(eF()32K?ehz_bZDU4Vs4N3!pA3HFw z-fwDSdNQ}&;wO(-4%l>F5=-j}6qJ>unfzPHCK*abq{f`F3tOFn2za3m_4#2lF3giF z9A<-xinbK)Bc;@-&gG6xLGJ~H?+$TXJQ0cDrB=P4ABkveLoPSitv~kD($5$f-)XR0 z;#SFQc8%IFJ=gbn=%F9Jy6lT$e0}i`9${iraGbQQkq*k9cy=Q!dGTy}D=bM-vfoM1 z^lH`z^=#iJiL3J6J`tUnC8YQ06I!w1th;k^yXvXT{T}@f9wbdJMSCTIkiGO}tIcRi zphb|ObgF=?&AdZ+>EXeaP5MqU2lFqXf5Z@a*fambD-sxTUMG*aq9^ryY^bPpNlcxb zdeXcOTvn3wV1-0#7D-#^i*aist7poxZfQH64<(*f$UF6XYUhGj&>eTa-jE^`K?>qz zcNnrhqMBXXpnN^LEAC6YmBpNs3$?3C^~Ae?lr7sIjT<~)Y(WXEmLq=GC-vdv5XSLi zGNNHLxS(t79}Zq6q}`Q{-FBs3mM7Y2<^z8z2_J8q7KD@rj&NQ5;LY{PIQqO`Ee=g+ zF8rP~7&Kc~5*P1VM5~uH$nsU6SA94m{@DKLOo@@ol#iI{3TgEMl_T5C#BSR=nLD|1 zt3i+WPQB$s*YZSEG>@s;_Y4O0y8G1U7d)47e%4T+V29{!E5uHft6S~8ePyiDF5#|x zde0q>k|4X|FIAf=G;|tfo~!M972iF%=@@eWHY?G}0?s6D z_GA721o{vqMj|+Pk+z+zk;8#R3I0>69LEvHC84_jp+QBefM2;L4ll^1DLPV>twTjk zO9}^imC8v7leR(;VcC1qqGZkXPjZWixQNT2XEX!pt2c}85o8O=xt%VPw7ZWjpr3+1 z@0ip`i;1nQ+TU#sf)8e;^RySiX17jmTzp5ZN>3I?MvvNmhiA7&zuQ}waBv*ml!A^0 ziigX?{-Ahj)@Xopqw?#)a|(9M%e#@Nv$n%a153A8J(>y)^RKJvk&BMN&npS@pRSNY z1O`-tVDcKXeyeqWXXMVS=(lp>0>{R`brUBDCS?uj15^b8r;yV*18Rz)#BOGI4(TE{ za9BnDDOHK%hzk~IsA`YdE9d5k6NP=AxLS#qsc9Bjb8IZd)mCxWtrYVv!KPN*)+xTPXOzE>x-L2;I^A2${W)A|e60hz5`6kO zs9W1Ndo1Ory8QOm3j6wG}Tk8VH9AoB7HB{(YL)7kW!z~jRU{cF}v$lV* z1A#BbgrEy#Hfooj`s6+V1sLWwH5x*6Y8lt1jB9w@m3GngcdGVl^4~EySN#_ZvAwsO zmHH5zk$r4#!J;Zq1WPGN46k;BrS9$c_ zB8)8ztb((|yVjh<-AlAY*5>ccA2m3zeQ3#Q)?{(A?{dZc*hUI2g48PWKmLd$Os7VJ zf`MaDE9Cqm8QQ~(_@>8x-=UHftfQH->^HVZ?S7yx6j`PfJ^&=l=s7f+uhezc-x*_j+5(FNLA&Uw3vqqk?Bc@rLu{ru{hxXTk#EH{c za{mK=>o8vlX+s7JkG%nMKvN`_eLr0*d3-n#;=2ftzR!~ar2u8PhfY*ToeoSEER?{(Sk98g80nG6gpCgK=bCvZvvF5dK#JLSC_ceJfP9!J%X4cb&&xs|#DZxhoc{%eixC8aHA@dP zsqxIzNs;A$z06l&&DKS=(l|f_gvpTnE-y7R=a%rzE;GMKs)ab}YQemJJRC10v>%$e z7T#r~IhftB6e(L1Mjf!f9M1bfYXa3m_+UWS{s2vW`rPZy#vK>wl&4;3F6d43lSCSN zYW3a$vcDsud9YRzovS)kmuBQFrU0ZfQg*woT42^_9-pmVK^A26WpZeoCHP|iFbuhM z_RnsiEfbnaDwqcF>q1l&3<9zUhiR4bLE#-f?D%;i$O1h76QF{IAOntioC4ImO7Q~2 z$u3fM7QQmzDgH<|JcGdk2FJB+pdbMuM!U?;X_fdCht~B2?+U0Mun=fl>~#=R&PvO@ zVyOm8=9Wl$i+lG-`9qja96%tZz$A($SyPog&E?3JlUm8Nv8zg$4MP4Il|mEdx5+rfsY^;C(Q`s8puTC5x( z0q7|sz2K;kk+pBt9V3od{pA@+kg3kr%%OCBh5R*a*Fm~=J}^72;0u}>;jJiSJk3rH z_0Hx(MiUwp_PMY+(^2qHQw(NA?n_-t>Cu;VuCk4EiSj7wCZ=yXrpR1O26s8R`G=dn z<#KxPn3^F9v;NIu&`<~>-~C8gPE$lQw+_yR?=Yg1gCDWQ`KV>25oas7*B{DKbW=cg zyfT~XhjmQlkAg7Hg-Sb`C|>00ujqOt?~YNH3;1MD&oJ6**}RhEN@L+?*r0vHM#^0j zd}qOC<@oDjAvVD3^!E=q=ECdqd&f9tC!3@GG_+D#4$Z@b7k>#=+~5x^6Z@!o!w%Bq zSr%UEuzAKnXIU*4dKp-i{(W&!4CSk|)6F1@`NRghSlTOj4>E)3Pc+W9f2tR4ts{94E*?TvnR%*@h3LpRtTp>r31%?bS$c0 zpz2YsK_9p@^ZPxEH+{u-P%m!iTSj8x4d2e@B+Q{eB8dTCQ^o1V@CKrcEmMa7F9Z_U zh-96hIux6ii$lZ{oUpfnZ<3~=?egP{m#Hm$j8bJlw?xmo7?)K2)6J+i1CK+X@WZsi ze+;|^D@k|HvKGj{jKQ&z<=Luy;oo1G}YetkqSBuUPwMX);hBfn8|q|Jh5 z?80<|s5^wtnNk1&K3^uMjH~~~h;=q>&&(O{n2&)Wh7hOG0xYT<3j~Js(I&fT5wq`< ztr+ID(Z@U8)sZv)nm}2jS!wu0D@SuhR2hq7^cSyGN#l~8pEda!I;K27nRD3E=W)3%E>~|BPje|haGw^4!KhbU*iqGPLQbfxNx4ladU^l$F(#3({F=(8m7LKzsqt#Q z@ee&aphG~8Hlv3Gmwi8@r9^Yt51aPm<5Zsa@|YNLtZ<%dBecuNClYWO% zuX z4+F%RD!XJ z?dX@e#I3M-#PUxS_LT;=X;lp400bCXu$4jL{{Qj+S_fgVy%TSK!aor}3Y-c2^wCB- JC0Y)V{{p}2rGWqd literal 0 HcmV?d00001 diff --git a/demo/myAGVPro_Composite_Kit/composite_kit.py b/demo/myAGVPro_Composite_Kit/composite_kit.py new file mode 100644 index 00000000..bc7d3623 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/composite_kit.py @@ -0,0 +1,236 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import os +import time +from core import Number +from core.joystick import InputJoystick, Hotkey +from core.drive import AGVDriveAPI +from core.controller import BaseControllerApi + + +class AGVProCompositeKit(object): + agvHorizontalSpeed: Number = Number(0.5, 0.1, 0.1) + agvVerticalSpeed: Number = Number(0.75, 0.15, 0.15) + agvRotationSpeed: Number = Number(1.5, 0.2, 0.1) + + joystick = InputJoystick(raw_mapping=False) + + def __init__(self, agv_pro_driver: AGVDriveAPI, arm_controller: BaseControllerApi): + self.arm_controller = arm_controller + self.agv_pro = agv_pro_driver + + if self.agv_pro.is_power_on() is False: + self.agv_pro.power_on() + print(f" # Start the AGVPRO power supply.") + else: + print(f" # AGVPRO is already powered on.") + + self.joystick.inject_caller(self) + + self._agv_motion_control = False + self._arm_motion_control = False + + def init_joystick(self) -> bool: + device = InputJoystick.get_gamepad(0) + if device is not None: + self.joystick.set_device(device) + return device is not None + + @joystick.register(hotkey=Hotkey.L1) + def L1(self, value: int): + if value == 1 and not self._agv_motion_control: + self.agv_pro.rotate_right(self.agvRotationSpeed.value) + self._agv_motion_control = True + print(f" # Rotate right.") + return + + if value == 0 and self._agv_motion_control: + self.agv_pro.stop() + self._agv_motion_control = False + print(f" # Stop rotating.") + return + + @joystick.register(hotkey=Hotkey.R1) + def R1(self, value: int): + if value == 1 and not self._agv_motion_control: + self.agv_pro.rotate_left(self.agvRotationSpeed.value) + self._agv_motion_control = True + print(f" # Rotate left.") + return + + if value == 0 and self._agv_motion_control: + self._agv_motion_control = False + self.agv_pro.stop() + print(f" # Stop rotating.") + return + + @joystick.register(hotkey=Hotkey.L2, value_filter=lambda value: value == 0) + def L2(self, _: int): + hs = self.agvHorizontalSpeed.decrease() + vs = self.agvVerticalSpeed.decrease() + rs = self.agvRotationSpeed.decrease() + print(f" # Speed decreases {hs = :.2f} {vs = :.2f} {rs = :.2f}") + + @joystick.register(hotkey=Hotkey.R2, value_filter=lambda value: value == 0) + def R2(self, _: int): + hs = self.agvHorizontalSpeed.increase() + vs = self.agvVerticalSpeed.increase() + rs = self.agvRotationSpeed.increase() + print(f" # Speed increases {hs = :.2f} {vs = :.2f} {rs = :.2f}") + + @joystick.register(hotkey=Hotkey.RIGHT_Y_AXIS) + def RIGHT_X_AXIS(self, value: int): + if value < 128 and not self._agv_motion_control: + self.agv_pro.forward(self.agvVerticalSpeed.value) + self._agv_motion_control = True + print(f" # Move forward.") + + elif value > 128 and not self._agv_motion_control: + self.agv_pro.backward(self.agvVerticalSpeed.value) + self._agv_motion_control = True + print(f" # Move backward.") + + elif value == 128 and self._agv_motion_control: + self.agv_pro.stop() + self._agv_motion_control = False + print(f" # Stop moving.") + + @joystick.register(hotkey=Hotkey.RIGHT_X_AXIS) + def RIGHT_Y_AXIS(self, value: int): + if value < 128 and not self._agv_motion_control: + self._agv_motion_control = True + self.agv_pro.pan_left(self.agvHorizontalSpeed.value) + print(f" # Pan left.") + + elif value > 128 and not self._agv_motion_control: + self._agv_motion_control = True + self.agv_pro.pan_right(self.agvHorizontalSpeed.value) + print(f" # Pan right.") + + elif value == 128 and self._agv_motion_control: + self._agv_motion_control = False + print(f" # Stop panning.") + self.agv_pro.stop() + + @joystick.register(hotkey=Hotkey.STARTUP, value_filter=lambda value: value == 0) + def STARTUP(self, _): + hs = self.agvHorizontalSpeed.reset() + vs = self.agvVerticalSpeed.reset() + rs = self.agvRotationSpeed.reset() + + print(f" # Speed reset {hs = :.2f} {vs = :.2f} {rs = :.2f}") + + if self.agv_pro.is_power_on() is False: + print(f" # Abnormal power-off of AGVPRO has been detected, and it is trying to power on...") + self.agv_pro.power_on() + time.sleep(1) + self.agv_pro.open_strip_light_diy_mode() + self.agv_pro.set_strip_light_color([0, 1], (0, 255, 0), 255) + else: + self.agv_pro.stop() + print(f" # Stop moving.") + + self.arm_controller.go_home() + self.arm_controller.close_suction_pump() + + @joystick.register(hotkey=Hotkey.Y) + def Y(self, value: int): + print(f"{Hotkey.Y} {value}") + if value == 1: + print(f" # Open gripper.") + self.arm_controller.open_gripper(1) + else: + self.arm_controller.stop() + print(f" # Stop opening the gripper.") + + @joystick.register(hotkey=Hotkey.A) + def A(self, value: int): + if value == 1: + print(f" # Close gripper.") + self.arm_controller.close_gripper(1) + else: + self.arm_controller.stop() + print(f" # Stop closing the gripper.") + + @joystick.register(hotkey=Hotkey.X, value_filter=lambda value: value == 0) + def X(self, _: int): + try: + self.arm_controller.open_suction_pump() + print(f"Open suction pump.") + except NotImplementedError as e: + print(e) + + @joystick.register(hotkey=Hotkey.B, value_filter=lambda value: value == 0) + def B(self, _: int): + try: + self.arm_controller.close_suction_pump() + print(f"Close suction pump.") + except NotImplementedError as e: + print(e) + + @joystick.register(hotkey=Hotkey.HORIZONTAL) + def HORIZONTAL(self, value: int): + if value == 1: + print(f" # The end is rotated counterclockwise.") + self.arm_controller.set_end_rotate(direction=-1, speed=1) + + elif value == -1: + print(f" # The end is rotate clockwise.") + self.arm_controller.set_end_rotate(direction=1, speed=1) + + else: + print(" # Stop spinning.") + self.arm_controller.stop() + + @joystick.register(hotkey=Hotkey.VERTICAL) + def VERTICAL(self, value: int): + if value == -1: + print(f"axis z +.") + self.arm_controller.coordinate(axis=3, direction=1) + elif value == 1: + print(f"axis Z -.") + self.arm_controller.coordinate(axis=3, direction=0) + else: + print("axis z stop.") + self.arm_controller.stop() + + @joystick.register(hotkey=Hotkey.LEFT_X_AXIS) + def LEFT_X_AXIS(self, value: int): + if value > 128 and not self._arm_motion_control: + print(f"axis y -.") # Y+ + self.arm_controller.coordinate(axis=2, direction=0) + self._arm_motion_control = True + + elif value < 128 and not self._arm_motion_control: + print(f"axis y +.") # Y- + self.arm_controller.coordinate(axis=2, direction=1) + self._arm_motion_control = True + + elif value == 128 and self._arm_motion_control: + self._arm_motion_control = False + print(f"axis y stop.") + self.arm_controller.stop() + + @joystick.register(hotkey=Hotkey.LEFT_Y_AXIS) + def LEFT_Y_AXIS(self, value: int): + if value < 128 and not self._arm_motion_control: + print(f"axis x +.") # X+ + self.arm_controller.coordinate(axis=1, direction=1) + self._arm_motion_control = True + + elif value > 128 and not self._arm_motion_control: + print(f"axis x -.") # X- + self.arm_controller.coordinate(axis=1, direction=0) + self._arm_motion_control = True + + elif value == 128 and self._arm_motion_control: + self._arm_motion_control = False + print(f"axis x stop.") + self.arm_controller.stop() + + def mainloop(self): + self.joystick.run_with_loop() + + + + diff --git a/demo/myAGVPro_Composite_Kit/core/__init__.py b/demo/myAGVPro_Composite_Kit/core/__init__.py new file mode 100644 index 00000000..68cff946 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/core/__init__.py @@ -0,0 +1,44 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import os +import socket + + +class Number(object): + def __init__(self, maximum: float, minimum: float, step: float): + self.maximum = maximum + self.minimum = minimum + self.step = step + self.value = minimum + + def increase(self, digits: int = 2) -> float: + self.value = round(self.value + self.step, digits) + if self.value > self.maximum: + self.value = self.maximum + return self.value + + def decrease(self, digits: int = 2) -> float: + self.value = round(self.value - self.step, digits) + if self.value < self.minimum: + self.value = self.minimum + return self.value + + def reset(self) -> float: + self.value = self.minimum + return self.value + + +def get_local_host() -> str: + return socket.gethostbyname(socket.gethostname()) + + +def find_esp32_drive(): + paths = [] + for i in os.listdir('/dev'): + if not i.startswith("ttyACM"): + continue + paths.append(os.path.join('/dev', i)) + + paths.sort(key=lambda p: int(p[-1])) + return paths + diff --git a/demo/myAGVPro_Composite_Kit/core/controller.py b/demo/myAGVPro_Composite_Kit/core/controller.py new file mode 100644 index 00000000..f09b2387 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/core/controller.py @@ -0,0 +1,153 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +from pymycobot import MyArmMControl, MyCobot320, ElephantRobot + + +class BaseControllerApi: + def open_suction_pump(self): + raise NotImplementedError("Not implemented") + + def close_suction_pump(self): + raise NotImplementedError("Not implemented") + + def set_end_rotate(self, direction: int, speed: float): + raise NotImplementedError("Not implemented") + + def open_gripper(self, speed: int = 1): + raise NotImplementedError("Not implemented") + + def close_gripper(self, speed: int = 1): + raise NotImplementedError("Not implemented") + + def coordinate(self, axis: int, direction: int): + raise NotImplementedError("Not implemented") + + def go_home(self): + raise NotImplementedError("Not implemented") + + def stop(self): + raise NotImplementedError("Not implemented") + + +class M750Controller(BaseControllerApi): + def __init__(self, port: str, debug: bool = False): + self._arm = MyArmMControl(port, baudrate=1000000, debug=debug) + + def go_home(self): + self._arm.write_angles([0, 0, 0, 0, 90, 0], 10) + + def open_suction_pump(self): + print(" # (Warning) M750 not support suction pump") + + def close_suction_pump(self): + print(" # (Warning) M750 not support suction pump") + + def stop(self): + self._arm.stop() + + def set_end_rotate(self, direction: int, speed: float): + self._arm.write_angle(6, 180 * direction, speed) + + def open_gripper(self, speed: int = 1): + self._arm.set_gripper_value(100, speed) + + def close_gripper(self, speed: int = 1): + self._arm.set_gripper_value(2, speed) + + def coordinate(self, axis: int, direction: int): + self._arm.jog_coord(axis, direction, 10) + + +class MyCobot320Controller(BaseControllerApi): + def __init__(self, port: str, debug: bool = False): + self._cobot = MyCobot320(port, baudrate=115200, debug=debug) + + def open_suction_pump(self): + try: + self._cobot.set_basic_output(1, 0) + except Exception as e: + print(f" # (Error) MyCobot320 open suction pump: {e}") + + def close_suction_pump(self): + try: + self._cobot.set_basic_output(1, 1) + except Exception as e: + print(f" # (Error) MyCobot320 close suction pump: {e}") + + def set_end_rotate(self, direction: int, speed: float): + self._cobot.send_angle(6, 160 * direction, speed) + + def open_gripper(self, speed: int = 1): + self._cobot.set_pro_gripper_angle(14, 100) + + def close_gripper(self, speed: int = 1): + self._cobot.set_pro_gripper_angle(14, 0) + + def coordinate(self, axis: int, direction: int): + self._cobot.jog_coord(axis, direction, 10) + + def go_home(self): + self._cobot.send_angles([-90, 0, -90, 0, 90, 0], 10) + + def stop(self): + self._cobot.stop() + + +class MyCobot630Controller(BaseControllerApi): + def __init__(self, host: str, port: int = 5001, debug: bool = False): + self._cobot = ElephantRobot(host=host, port=port, debug=debug) + self._cobot.start_client() + + def open_suction_pump(self): + print(" # (Warning) MyCobot360 not support suction pump") + + def close_suction_pump(self): + print(" # (Warning) MyCobot360 not support suction pump") + + def set_end_rotate(self, direction: int, speed: float): + self._cobot.write_angle(4, 180 * direction, 1000) + + def open_gripper(self, speed: int = 1): + self._cobot.force_gripper_full_open() + + def close_gripper(self, speed: int = 1): + self._cobot.force_gripper_full_close() + + def coordinate(self, axis: int, direction: int): + axis_dir_table = ["x", "y", "z"] + if direction == 0: + direction = -1 + self._cobot.jog_coord(axis_dir_table[axis - 1], direction, 3000) + + def go_home(self): + self._cobot.write_angles([0, -97.509, 39.049, -120.34, -95.609, 66.717], 3000) + + def stop(self): + self._cobot.task_stop() + + +class UndefinedController(BaseControllerApi): + + def open_suction_pump(self): + print(" # UndefinedController not support suction pump") + + def close_suction_pump(self): + print(" # UndefinedController not support suction pump") + + def set_end_rotate(self, direction: int, speed: float): + print(" # UndefinedController not support set_end_rotate") + + def open_gripper(self, speed: int = 1): + print(" # UndefinedController not support open_gripper") + + def close_gripper(self, speed: int = 1): + print(" # UndefinedController not support close_gripper") + + def coordinate(self, axis: int, direction: int): + print(" # UndefinedController not support coordinate") + + def go_home(self): + print(" # UndefinedController not support go_home") + + def stop(self): + print(" # UndefinedController not support stop") diff --git a/demo/myAGVPro_Composite_Kit/core/drive.py b/demo/myAGVPro_Composite_Kit/core/drive.py new file mode 100644 index 00000000..2f2ba108 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/core/drive.py @@ -0,0 +1,129 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import dataclasses +import typing as T +import pymycobot + + +@dataclasses.dataclass +class AutoReportMessage: + rx: float + ry: float + rw: float + emergency_stop: bool + is_power_on: bool + error_motor: list + left_bumper_strip: bool + right_bumper_strip: bool + power_voltage: float + motor_enable: bool + + +class AGVDriveAPI(object): + __version__ = pymycobot.__version__ + + def __init__(self, comport: str, debug: bool = False): + self._agv_pro = pymycobot.MyAGVPro(comport, debug=debug) + + def set_strip_light_color(self, locations: T.List[int], color: T.Tuple[int, int, int], brightness: int = 255): + for location in locations: + print(f" # Set strip light color {location} to {color} with brightness {brightness}") + self._agv_pro.set_led_color(location, color=color, brightness=brightness) + + def open_strip_light_diy_mode(self): + self._agv_pro.set_led_mode(1) + + def close_strip_light_diy_mode(self): + self._agv_pro.set_led_mode(0) + + def get_firmware_version(self): + system_version = self._agv_pro.get_system_version() + modify_version = self._agv_pro.get_modify_version() + + if system_version is None or modify_version is None: + return None + + return f"{system_version}.{modify_version}" + + def get_communication_state(self): + return self._agv_pro.get_communication_state() + + def get_motor_enable_status(self): + return self._agv_pro.get_motor_enable_status() + + def get_motor_temps(self): + return self._agv_pro.get_motor_temps() + + def get_motor_torques(self): + return self._agv_pro.get_motor_torques() + + def get_motor_speeds(self): + return self._agv_pro.get_motor_speeds() + + def get_auto_report_state(self) -> bool: + return self._agv_pro.get_auto_report_state() == 1 + + def get_auto_report_message(self) -> T.Optional[AutoReportMessage]: + report_message = self._agv_pro.get_auto_report_message() + if report_message is None: + return None + + if report_message[3] == 0: + report_message[3] = [0, 0, 0, 0] + + print(f" # Get auto report message {report_message}") + return AutoReportMessage( + rx=report_message[0], + ry=report_message[1], + rw=report_message[2], + emergency_stop=report_message[3][0] == 1, + is_power_on=report_message[3][1] == 1, + left_bumper_strip=report_message[3][2] == 1, + right_bumper_strip=report_message[3][3] == 1, + error_motor=report_message[4], + power_voltage=report_message[5], + motor_enable=report_message[6] == 1 + ) + + def get_emergency_stop_state(self) -> bool: + return self._agv_pro.get_estop_state() == 1 + + def set_auto_report_state(self, state: bool): + return self._agv_pro.set_auto_report_state(int(state)) + + def forward(self, speed: float): + self._agv_pro.move_forward(speed) + + def backward(self, speed: float): + self._agv_pro.move_backward(speed) + + def pan_left(self, speed: float): + self._agv_pro.move_left_lateral(speed) + + def pan_right(self, speed: float): + self._agv_pro.move_right_lateral(speed) + + def rotate_left(self, speed: float): + self._agv_pro.turn_left(speed) + + def rotate_right(self, speed: float): + self._agv_pro.turn_right(speed) + + def power_on(self) -> bool: + return self._agv_pro.power_on() == 1 + + def is_power_on(self) -> bool: + is_power_on = self._agv_pro.is_power_on() + return is_power_on == 1 + + def power_off(self) -> bool: + return self._agv_pro.power_off() == 1 + + def stop(self): + self._agv_pro.stop() + + def close(self): + self._agv_pro.close() + + def open(self): + self._agv_pro.open() diff --git a/demo/myAGVPro_Composite_Kit/core/joystick.py b/demo/myAGVPro_Composite_Kit/core/joystick.py new file mode 100644 index 00000000..2e78878d --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/core/joystick.py @@ -0,0 +1,202 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +import logging +import queue +import threading +import time +import enum +import typing as T +from inputs import GamePad, DeviceManager + + +class Hotkey(enum.Flag): + # hat + HORIZONTAL = enum.auto() + VERTICAL = enum.auto() + CENTER = enum.auto() + + # button + A = enum.auto() + B = enum.auto() + X = enum.auto() + Y = enum.auto() + L1 = enum.auto() + R1 = enum.auto() + SELECT = enum.auto() + STARTUP = enum.auto() + LEFT_STICK = enum.auto() + RIGHT_STICK = enum.auto() + MODEL = enum.auto() + + # axis + LEFT_X_AXIS = enum.auto() + LEFT_Y_AXIS = enum.auto() + RIGHT_X_AXIS = enum.auto() + RIGHT_Y_AXIS = enum.auto() + L2 = enum.auto() + R2 = enum.auto() + + +BindingCallbackT = T.Callable[[int], None] +HotkeyT = T.Union[Hotkey, int] + + +class InputJoystick(object): + """InputJoystick""" + hotkey_map = { + "Key::BTN_TL": Hotkey.L1, + "Absolute::ABS_BRAKE": Hotkey.L2, + "Key::BTN_TR": Hotkey.R1, + "Absolute::ABS_GAS": Hotkey.R2, + "Absolute::ABS_HAT0Y": Hotkey.VERTICAL, + "Absolute::ABS_HAT0X": Hotkey.HORIZONTAL, + "Key::BTN_SELECT": Hotkey.SELECT, + "Key::BTN_START": Hotkey.STARTUP, + "Key::BTN_NORTH": Hotkey.X, + "Key::BTN_SOUTH": Hotkey.A, + "Key::BTN_WEST": Hotkey.Y, + "Key::BTN_EAST": Hotkey.B, + "Key::BTN_THUMBL": Hotkey.LEFT_STICK, + "Key::BTN_THUMBR": Hotkey.RIGHT_STICK, + "Key::BTN_MODE": Hotkey.MODEL, + "Absolute::ABS_X": Hotkey.LEFT_X_AXIS, + "Absolute::ABS_Y": Hotkey.LEFT_Y_AXIS, + "Absolute::ABS_Z": Hotkey.RIGHT_X_AXIS, + "Absolute::ABS_RZ": Hotkey.RIGHT_Y_AXIS + } + + def __init__(self, device: T.Optional[GamePad] = None, ignore_types: T.List[str] = None, raw_mapping: bool = True): + self._device = device + self._raw_mapping = raw_mapping + self._ignore_types = ignore_types or ["Sync", "Misc"] + self._bindings: T.Dict[HotkeyT, BindingCallbackT] = {} + self._value_filter_table: T.Dict[HotkeyT, T.Callable[[int], bool]] = {} + self._logger = logging.getLogger("joystick") + self._caller: T.Optional[object] = None + + def __repr__(self) -> str: + return f"InputJoystick({self._device.name})" + + @property + def name(self): + return self._device.name + + @property + def device(self) -> GamePad: + return self._device + + def set_device(self, device: GamePad) -> None: + self._device = device + self._logger.debug(f"Set device {device.name}") + + def binding(self, hotkey: HotkeyT, callback: BindingCallbackT) -> None: + self._logger.debug(f"Bind {hotkey} -> {callback.__name__}") + self._bindings[hotkey] = callback + + def register(self, hotkey: HotkeyT, value_filter: T.Callable[[int], bool] = None): + def wrapper(callback: BindingCallbackT): + self.binding(hotkey, callback) + + if value_filter is None: + return + + self._value_filter_table[hotkey] = value_filter + + return wrapper + + # 添加调用者 + def inject_caller(self, caller: object) -> None: + self._logger.debug(f"Inject caller {caller.__class__.__name__}") + self._caller = caller + + def read(self) -> T.Iterator[T.Tuple[HotkeyT, int]]: + for event in self._device.read(): + if event.ev_type in self._ignore_types: + continue + + hotkey = f"{event.ev_type}::{event.code}" + if self._raw_mapping is False: + hotkey = self.hotkey_map.get(hotkey, hotkey) + yield hotkey, event.state + + def _trigger_hotkey_callback(self, hotkey: HotkeyT, value: int) -> None: + self._logger.debug(f"{hotkey} -> {value}") + if hotkey not in self._bindings.keys(): + self._logger.debug(f"Unbind {hotkey} -> {value}") + return + + if hotkey in self._value_filter_table.keys() and not self._value_filter_table[hotkey](value): + self._logger.debug(f"Filter {hotkey} -> {value}") + return + + self._logger.debug(f"Bind {hotkey} -> {value}") + + if self._caller is not None: + self._bindings[hotkey](self._caller, value) + else: + self._bindings[hotkey](value) + + def monitoring(self): + for hotkey, value in self.read(): + self._trigger_hotkey_callback(hotkey, value) + + def run_with_loop(self, delay: float = 0.01) -> None: + try: + while True: + self.monitoring() + time.sleep(delay) + except KeyboardInterrupt: + return + + def _thread_loop(self, hotkey_queue: queue.Queue) -> None: + while True: + try: + hotkey, value = hotkey_queue.get() + if all([hotkey, value]) is False: + break + self._trigger_hotkey_callback(hotkey, value) + except queue.Empty: + continue + + except KeyboardInterrupt: + print(" # exit") + break + except Exception as e: + self._logger.error(e) + + def run_with_thread(self, loop_caller: T.Callable[[], bool] = None, delay: float = 0.01) -> None: + hotkey_queue = queue.Queue() + thread = threading.Thread(target=self._thread_loop, args=(hotkey_queue,)) + thread.start() + while loop_caller() if loop_caller is not None else True: + for hotkey, value in self.read(): + hotkey_queue.put((hotkey, value)) + time.sleep(delay) + hotkey_queue.put((None, None)) + thread.join() + + @staticmethod + def get_gamepad(index: int = 0, _filter: T.Callable[[GamePad], bool] = None) -> T.Optional[GamePad]: + device_manager = DeviceManager() + gamepads = device_manager.gamepads + if _filter is not None: + gamepads = list(filter(_filter, gamepads)) + + if index >= len(gamepads): + return None + return gamepads[index] + + @classmethod + def create_by_index(cls, index: int, ignore_types: T.List[str] = None, raw_mapping: bool = True) -> "InputJoystick": + ignore_types = ignore_types or [] + joystick = cls.get_gamepad(index=index) + if joystick is None: + raise FileNotFoundError("No joystick found") + return cls(joystick, ignore_types=ignore_types, raw_mapping=raw_mapping) + + @classmethod + def create_by_name(cls, name: str, ignore_types: T.List[str] = None, raw_mapping: bool = True) -> "InputJoystick": + joystick = cls.get_gamepad(_filter=lambda j: j.name == name) + if joystick is not None: + return cls(joystick, ignore_types=ignore_types, raw_mapping=raw_mapping) + raise FileNotFoundError(f"No joystick named {name}") diff --git a/demo/myAGVPro_Composite_Kit/main.py b/demo/myAGVPro_Composite_Kit/main.py new file mode 100644 index 00000000..905cad92 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/main.py @@ -0,0 +1,63 @@ +#!/usr/bin/env python +# -*- coding: UTF-8 -*- +from composite_kit import AGVProCompositeKit +from core.controller import UndefinedController, MyCobot630Controller, MyCobot320Controller, MyArmMControl +from core.drive import AGVDriveAPI + +# ############################################################################################## +# MyCobot Pro630 Configuration +# ############################################################################################## +COMPOSITE_KIT_HOST = "192.168.1.100" +COMPOSITE_KIT_PORT = 5001 + +# ############################################################################################## +# MyCobot M750 and MyCobot 320 Configuration +# ############################################################################################## +COMPOSITE_KIT_COMPORT = "/dev/ttyACM2" + +# ############################################################################################## +# MyAGV Pro Configuration +# ############################################################################################## +AGVPRO_DRIVE_COMPORT = "/dev/ttyACM0" + +# ############################################################################################## +# Composite kit configuration +# ############################################################################################## +COMPOSITE_KIT_TYPE = "Undefined" # MyCobotPro630, MyCobot320, MyArmM750, Undefined +DEBUG = False + + +def main(): + agvpro_driver = AGVDriveAPI(comport=AGVPRO_DRIVE_COMPORT, debug=DEBUG) + + if COMPOSITE_KIT_TYPE == "MyCobotPro630": + print(f" # Connecting to MyCobot Pro630 at {COMPOSITE_KIT_HOST}:{COMPOSITE_KIT_PORT}...") + arm_controller = MyCobot630Controller(host=COMPOSITE_KIT_HOST, port=COMPOSITE_KIT_PORT, debug=DEBUG) + + elif COMPOSITE_KIT_TYPE == "MyCobot320": + print(f" # Connecting to MyCobot 320 at {COMPOSITE_KIT_COMPORT}...") + arm_controller = MyCobot320Controller(port=COMPOSITE_KIT_COMPORT, debug=DEBUG) + + elif COMPOSITE_KIT_TYPE == "MyArmM750": + print(f" # Connecting to MyArm M750 at {COMPOSITE_KIT_COMPORT}...") + arm_controller = MyArmMControl(port=COMPOSITE_KIT_COMPORT, debug=DEBUG) + + else: + print(" # Undefined composite kit type.") + arm_controller = UndefinedController() + + composite_kit = AGVProCompositeKit(arm_controller=arm_controller, agv_pro_driver=agvpro_driver) + + if composite_kit.init_joystick(): + print(" # Joystick initialized.") + else: + print(" # (Error) Joystick initialization failed.") + print(" # (Error) Please check the connection of the joystick.") + return + + composite_kit.mainloop() + print(" # Exit.") + + +if __name__ == '__main__': + main() diff --git a/demo/myAGVPro_Composite_Kit/requirements.txt b/demo/myAGVPro_Composite_Kit/requirements.txt new file mode 100644 index 00000000..6c068a21 --- /dev/null +++ b/demo/myAGVPro_Composite_Kit/requirements.txt @@ -0,0 +1 @@ +inputs~=0.5 \ No newline at end of file From 0c48e0a1eed76a6a51bb9443621f453b8def14b6 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 4 Aug 2025 19:36:48 +0800 Subject: [PATCH 40/57] feat(MercuryX1): Compatible with dock firmware version 1.2 --- pymycobot/mercurychassis_api.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pymycobot/mercurychassis_api.py b/pymycobot/mercurychassis_api.py index 0b29d9c0..99a3fbc6 100644 --- a/pymycobot/mercurychassis_api.py +++ b/pymycobot/mercurychassis_api.py @@ -82,7 +82,7 @@ def _request(self, flag=""): elif flag == "ultrasonic": receive_data = self._extract_frame(receive_all_data, ProtocolCode.ultrasound_header, - ProtocolCode.ultrasound_footer, expected_lengths) + ProtocolCode.ultrasound_footer, 19) # print(receive_data, len(receive_data)) if receive_data: self._debug(receive_data) From ebe8a0c1fc40bcd8bb06e34dd4217c1e7485acc3 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 5 Aug 2025 10:59:47 +0800 Subject: [PATCH 41/57] feat(mercurychassis_api): Dynamically matching instruction length --- pymycobot/mercurychassis_api.py | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/pymycobot/mercurychassis_api.py b/pymycobot/mercurychassis_api.py index 99a3fbc6..390a8559 100644 --- a/pymycobot/mercurychassis_api.py +++ b/pymycobot/mercurychassis_api.py @@ -62,14 +62,17 @@ def _request(self, flag=""): :param flag: Data type parameter variable :return: """ - return_data = '' - expected_lengths = 26 + expected_lengths_map = { + "voltage": 26, + "ultrasonic": 19, + "version": 26 + } + expected_lengths = expected_lengths_map.get(flag, None) for _ in range(3): receive_all_data = self._read() receive_all_data = [byte for byte in receive_all_data] if flag == "voltage": - receive_data = self._extract_frame(receive_all_data, ProtocolCode.header, ProtocolCode.footer, - expected_lengths) + receive_data = self._extract_frame(receive_all_data, ProtocolCode.header, ProtocolCode.footer, expected_lengths) # print(receive_data, len(receive_data)) if receive_data: self._debug(receive_data) @@ -81,18 +84,15 @@ def _request(self, flag=""): return return_data elif flag == "ultrasonic": - receive_data = self._extract_frame(receive_all_data, ProtocolCode.ultrasound_header, - ProtocolCode.ultrasound_footer, 19) + receive_data = self._extract_frame(receive_all_data, ProtocolCode.ultrasound_header, ProtocolCode.ultrasound_footer, expected_lengths) # print(receive_data, len(receive_data)) if receive_data: self._debug(receive_data) - return_data = [receive_data[1] * 256 + receive_data[2], receive_data[3] * 256 + receive_data[4], - receive_data[5] * 256 + receive_data[6]] + return_data = [receive_data[1] * 256 + receive_data[2], receive_data[3] * 256 + receive_data[4], receive_data[5] * 256 + receive_data[6]] return return_data elif flag == "version": - receive_data = self._extract_frame(receive_all_data, ProtocolCode.header, ProtocolCode.footer, - expected_lengths) + receive_data = self._extract_frame(receive_all_data, ProtocolCode.header, ProtocolCode.footer, expected_lengths) # print(receive_data, len(receive_data)) if receive_data: self._debug(receive_data) From e9a410228743c61b6c0fb9ba6eafbb0fc40fb6ac Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 5 Aug 2025 11:31:30 +0800 Subject: [PATCH 42/57] feat(mercurychassis_api): Optimize voltage reading accuracy --- pymycobot/mercurychassis_api.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pymycobot/mercurychassis_api.py b/pymycobot/mercurychassis_api.py index 390a8559..7bf738d5 100644 --- a/pymycobot/mercurychassis_api.py +++ b/pymycobot/mercurychassis_api.py @@ -79,7 +79,7 @@ def _request(self, flag=""): transition_16 = 0 transition_16 |= receive_data[20] << 8 transition_16 |= receive_data[21] - return_data = round(transition_16 / 1000 + (transition_16 % 1000) * 0.001, 3) + return_data = round(transition_16 / 1000, 3) return return_data From e9fab2df0ec26681dc052cb8c1175951bd455b9f Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 12 Aug 2025 19:23:59 +0800 Subject: [PATCH 43/57] feat(ConveyorApi): Separate the set_motor_speed interface --- pymycobot/conveyor_api.py | 33 +++++++++++++++------------------ 1 file changed, 15 insertions(+), 18 deletions(-) diff --git a/pymycobot/conveyor_api.py b/pymycobot/conveyor_api.py index 7a9c3aba..10198506 100644 --- a/pymycobot/conveyor_api.py +++ b/pymycobot/conveyor_api.py @@ -59,7 +59,7 @@ def __bytes__(self): @classmethod def packing(cls, genre: int, addr: int, *params): check_code = cls.check_digit(genre, params) - return cls(genre=genre, address=addr, check_digit=(check_code, ), params=(*params,)) + return cls(genre=genre, address=addr, check_digit=(check_code,), params=(*params,)) @classmethod def parsing(cls, buffer: bytes): @@ -69,7 +69,8 @@ def parsing(cls, buffer: bytes): if buffer[0] != cls.HEADER or buffer[1] != cls.HEADER: return None length = buffer[3] - return cls(genre=buffer[-2], address=buffer[2], length=length, params=(*buffer[4:4+length], ), check_digit=buffer[4+length:4+length+1]) + return cls(genre=buffer[-2], address=buffer[2], length=length, params=(*buffer[4:4 + length],), + check_digit=buffer[4 + length:4 + length + 1]) @classmethod def unpack_args(cls, *parameters): @@ -136,10 +137,10 @@ class MotorModel: STEPPER_MOTOR_42 = 0x30 STEPPER_MOTOR_57 = 0x31 - def __init__(self, comport, baudrate="115200", timeout=0.1, debug=False): + def __init__(self, comport, baudrate="115200", timeout=0.1, debug=False, motor_model=MotorModel.STEPPER_MOTOR_57): super().__init__(comport, baudrate, timeout) self._debug = debug - self.open() + self._motor_model = motor_model self._mutex = threading.Lock() self._log = logging.getLogger("conveyor_api") self._log.setLevel(logging.DEBUG if debug else logging.INFO) @@ -199,22 +200,18 @@ def get_motor_speed(self, motor_model=MotorModel.STEPPER_MOTOR_57): """Get the speed of the conveyor belt""" return self._merge(CommandGenre.GET_SERVO_SPEED, motor_model, has_reply=True) - def set_motor_speed(self, status, speed: int, motor_model=MotorModel.STEPPER_MOTOR_57): - """Modify the speed of the conveyor belt""" - if status not in (0, 1): - raise ValueError("status must be 0 or 1") + def set_speed(self, speed): + """modify the speed of the conveyor belt""" + if not 1 <= speed <= 100: + raise ValueError("speed must be in range [1, 100]") + return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 1, speed) - if not 0 <= speed <= 100: - raise ValueError("speed must be in range [0, 100]") - return self._merge(CommandGenre.SET_SERVO_SPEED, motor_model, status, speed) - - # def write_motor_angle(self, carry, angle: int, speed, motor_model=MotorModel.STEPPER_MOTOR_57): - # return self._merge(CommandGenre.WRITE_SERVO_ANGLE, motor_model, carry, angle, speed) - # - # def write_motor_step(self, carry, step: int, speed, direction, motor_model=MotorModel.STEPPER_MOTOR_57): - # return self._merge(CommandGenre.WRITE_SERVO_STEP, motor_model, carry, step, speed, direction) + def set_motor_state(self, state): + """Modify the state of the conveyor belt""" + if state not in (0, 1): + raise ValueError("state must be 0 or 1") + return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, state, 0) def read_firmware_version(self, motor_model=MotorModel.STEPPER_MOTOR_57): """Get the firmware version of the conveyor belt""" return self._merge(CommandGenre.READ_FIRMWARE_VERSION, motor_model, has_reply=True) - From 90bf9aea800380b32302941b97026fe376f7c677 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Tue, 12 Aug 2025 19:27:37 +0800 Subject: [PATCH 44/57] feat(ConveyorApi): Specify the motor type during initialization --- pymycobot/conveyor_api.py | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/pymycobot/conveyor_api.py b/pymycobot/conveyor_api.py index 10198506..1e59adac 100644 --- a/pymycobot/conveyor_api.py +++ b/pymycobot/conveyor_api.py @@ -186,19 +186,19 @@ def _merge(self, genre, address, *parameters, has_reply=False): return result / 10 return result - def set_motor_direction(self, direction, motor_model=MotorModel.STEPPER_MOTOR_57): + def set_motor_direction(self, direction): """Modify the direction of movement of the conveyor belt""" if direction not in (0, 1): raise ValueError("direction must be 0 or 1") - self._merge(CommandGenre.SET_SERVO_DIRECTION, motor_model, direction) + self._merge(CommandGenre.SET_SERVO_DIRECTION, self._motor_model, direction) - def get_motor_direction(self, motor_model=MotorModel.STEPPER_MOTOR_57): + def get_motor_direction(self): """Get the direction of movement of the conveyor belt""" - return self._merge(CommandGenre.GET_SERVO_DIRECTION, motor_model, has_reply=True) + return self._merge(CommandGenre.GET_SERVO_DIRECTION, self._motor_model, has_reply=True) - def get_motor_speed(self, motor_model=MotorModel.STEPPER_MOTOR_57): + def get_motor_speed(self): """Get the speed of the conveyor belt""" - return self._merge(CommandGenre.GET_SERVO_SPEED, motor_model, has_reply=True) + return self._merge(CommandGenre.GET_SERVO_SPEED, self._motor_model, has_reply=True) def set_speed(self, speed): """modify the speed of the conveyor belt""" @@ -212,6 +212,6 @@ def set_motor_state(self, state): raise ValueError("state must be 0 or 1") return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, state, 0) - def read_firmware_version(self, motor_model=MotorModel.STEPPER_MOTOR_57): + def read_firmware_version(self): """Get the firmware version of the conveyor belt""" - return self._merge(CommandGenre.READ_FIRMWARE_VERSION, motor_model, has_reply=True) + return self._merge(CommandGenre.READ_FIRMWARE_VERSION, self._motor_model, has_reply=True) From bab72c167c1107df82194737dd4b716dfec14cb1 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Fri, 15 Aug 2025 13:40:35 +0800 Subject: [PATCH 45/57] refactor(conveyorApi): add stop interface --- pymycobot/conveyor_api.py | 15 +++++++-------- pymycobot/mercury.py | 2 ++ 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/pymycobot/conveyor_api.py b/pymycobot/conveyor_api.py index 1e59adac..7e4430a9 100644 --- a/pymycobot/conveyor_api.py +++ b/pymycobot/conveyor_api.py @@ -10,9 +10,9 @@ def setup_serial_connect(port, baudrate, timeout=None): serial_api.port = port serial_api.baudrate = baudrate serial_api.timeout = timeout - serial_api.rts = False - serial_api.dtr = False serial_api.open() + serial_api.rts = False + serial_api.dtr = True return serial_api @@ -139,6 +139,7 @@ class MotorModel: def __init__(self, comport, baudrate="115200", timeout=0.1, debug=False, motor_model=MotorModel.STEPPER_MOTOR_57): super().__init__(comport, baudrate, timeout) + time.sleep(2) # If the Arduino mega 2560 is reset, you need to wait for the reset to complete self._debug = debug self._motor_model = motor_model self._mutex = threading.Lock() @@ -200,17 +201,15 @@ def get_motor_speed(self): """Get the speed of the conveyor belt""" return self._merge(CommandGenre.GET_SERVO_SPEED, self._motor_model, has_reply=True) - def set_speed(self, speed): + def set_motor_speed(self, speed): """modify the speed of the conveyor belt""" if not 1 <= speed <= 100: raise ValueError("speed must be in range [1, 100]") return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 1, speed) - def set_motor_state(self, state): - """Modify the state of the conveyor belt""" - if state not in (0, 1): - raise ValueError("state must be 0 or 1") - return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, state, 0) + def stop(self): + """stop the conveyor belt""" + return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 0, 0) def read_firmware_version(self): """Get the firmware version of the conveyor belt""" diff --git a/pymycobot/mercury.py b/pymycobot/mercury.py index 580b971c..4b2c189b 100644 --- a/pymycobot/mercury.py +++ b/pymycobot/mercury.py @@ -45,3 +45,5 @@ def open(self): def close(self): self._serial_port.close() + +Mercury.go_home() \ No newline at end of file From 9de0bda8f6655469d83a09d39a92e07a240285ec Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:30:14 +0800 Subject: [PATCH 46/57] feat(conveyor_api): Adapt to Conveyor 1.1 firmware, all interfaces return uniform values --- pymycobot/conveyor_api.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/pymycobot/conveyor_api.py b/pymycobot/conveyor_api.py index 7e4430a9..80b8aa85 100644 --- a/pymycobot/conveyor_api.py +++ b/pymycobot/conveyor_api.py @@ -177,7 +177,7 @@ def _merge(self, genre, address, *parameters, has_reply=False): if not has_reply: return - reply_command = self._wait_for_reply(timeout=0.07) # WaitForAReply + reply_command = self._wait_for_reply(timeout=0.2) # WaitForAReply self._log.debug(f"read < {reply_command}") if not reply_command: return None @@ -191,7 +191,7 @@ def set_motor_direction(self, direction): """Modify the direction of movement of the conveyor belt""" if direction not in (0, 1): raise ValueError("direction must be 0 or 1") - self._merge(CommandGenre.SET_SERVO_DIRECTION, self._motor_model, direction) + return self._merge(CommandGenre.SET_SERVO_DIRECTION, self._motor_model, direction, has_reply=True) def get_motor_direction(self): """Get the direction of movement of the conveyor belt""" @@ -205,11 +205,11 @@ def set_motor_speed(self, speed): """modify the speed of the conveyor belt""" if not 1 <= speed <= 100: raise ValueError("speed must be in range [1, 100]") - return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 1, speed) + return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 1, speed, has_reply=True) def stop(self): """stop the conveyor belt""" - return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 0, 0) + return self._merge(CommandGenre.SET_SERVO_SPEED, self._motor_model, 0, 0, has_reply=True) def read_firmware_version(self): """Get the firmware version of the conveyor belt""" From 3239e49a8ff36d8a966df8b59c0f675a80ac0b4e Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:33:32 +0800 Subject: [PATCH 47/57] feat(AGVPRO): Adapt to CH340 serial port chip --- pymycobot/myagvapi.py | 1 + 1 file changed, 1 insertion(+) diff --git a/pymycobot/myagvapi.py b/pymycobot/myagvapi.py index fec6d2ca..96d81be2 100644 --- a/pymycobot/myagvapi.py +++ b/pymycobot/myagvapi.py @@ -35,6 +35,7 @@ def setup_serial_connect(port, baudrate, timeout=None): serial_api.baudrate = baudrate serial_api.timeout = timeout serial_api.rts = False + serial_api.dtr = False serial_api.open() return serial_api From 7b748c26fb8808019224f81dfcff7d17f27c0130 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:36:55 +0800 Subject: [PATCH 48/57] feat(AGVPRO): Automatically upload the adapter firmware v1.0.10 --- pymycobot/myagvpro.py | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 1ab63df4..8729552d 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -292,16 +292,25 @@ def _parsing_data(cls, genre, reply_data): for index, data in enumerate(reply_data): if index < 3: respond.append(round(data / 100, 2)) + elif index in (3, 4): if data == 0: rank = data else: rank = Utils.get_bits(data) respond.append(rank) + elif index == 5: respond.append(round(data / 10, 1)) + elif index == 6: respond.append(data) + + elif index > 7 and index % 2 == 0: + piece = reply_data[index - 1:index + 1] + int16 = Utils.decode_int16(piece) + respond.append(round(int16 / 100, 2)) + return respond if ProtocolCode.GET_MOTOR_ENABLE_STATUS.equal(genre): From 6c4c83a7b4e7bb8db8502ded42f2a9b822b1156a Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:40:01 +0800 Subject: [PATCH 49/57] feat(AGVPRO): Added the control interface for opening and closing the handle --- pymycobot/myagvpro.py | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 8729552d..02aaa90d 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -52,6 +52,8 @@ class ProtocolCode(enum.Enum): GET_BLUETOOTH_UUID = 0x52 GET_BLUETOOTH_ADDRESS = 0x53 + SET_HANDLE_CONTROL_STATE = 0x3D + def equal(self, other): if isinstance(other, ProtocolCode): return self.value == other.value @@ -822,6 +824,17 @@ def get_bluetooth_address(self): return self._merge(ProtocolCode.GET_BLUETOOTH_ADDRESS) + def set_handle_control_state(self, state): + """Set the handle control switch status + Args: + state(int): 0: Disable, 1: Enable + + Returns: + int: 1: Success, 0: Failed + """ + if state not in (0, 1): + raise ValueError("state must be 0 or 1") + return self._merge(ProtocolCode.SET_HANDLE_CONTROL_STATE, state) class MyAGVPro(MyAGVProCommandApi): From cbcd0f444951ec43c871f074e868bea21f50dcb3 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:43:15 +0800 Subject: [PATCH 50/57] feat(AGVPRO): Added an interface for reading handle control status --- pymycobot/myagvpro.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 02aaa90d..fdd82c0b 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -53,6 +53,7 @@ class ProtocolCode(enum.Enum): GET_BLUETOOTH_ADDRESS = 0x53 SET_HANDLE_CONTROL_STATE = 0x3D + GET_HANDLE_CONTROL_STATE = 0x3F def equal(self, other): if isinstance(other, ProtocolCode): @@ -836,6 +837,15 @@ def set_handle_control_state(self, state): raise ValueError("state must be 0 or 1") return self._merge(ProtocolCode.SET_HANDLE_CONTROL_STATE, state) + def get_handle_control_state(self): + """Get the handle control switch status + + Returns: + int: 0: Disable, 1: Enable + """ + return self._merge(ProtocolCode.GET_HANDLE_CONTROL_STATE) + + class MyAGVPro(MyAGVProCommandApi): def __init__(self, port, baudrate=1000000, timeout=0.1, debug=False, save_serial_log=False): From 8e354a527efb177cb1e9927f85b750f79e5a6a1c Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 16:47:18 +0800 Subject: [PATCH 51/57] feat(AGVPRO): Bluetooth adapter handle control interface --- pymycobot/myagvpro_bluetooth.py | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index 18667046..21660a87 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -462,6 +462,26 @@ async def get_bluetooth_address(self): return await self._merge(ProtocolCode.GET_BLUETOOTH_ADDRESS) + async def set_handle_control_state(self, state): + """Set the handle control switch status + Args: + state(int): 0: Disable, 1: Enable + + Returns: + int: 1: Success, 0: Failed + """ + if state not in (0, 1): + raise ValueError("state must be 0 or 1") + return await self._merge(ProtocolCode.SET_HANDLE_CONTROL_STATE, state) + + async def get_handle_control_state(self): + """Get the handle control switch status + + Returns: + int: 0: Disable, 1: Enable + """ + return await self._merge(ProtocolCode.GET_HANDLE_CONTROL_STATE) + class MyAGVProBluetooth(MyAGVProCommandApi): def __init__(self, address, service_uuid, char_uuid, debug=False, save_serial_log=False): From 338077925664573eb7e8026c5cb032ee0f2f623d Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 28 Aug 2025 17:02:04 +0800 Subject: [PATCH 52/57] fix(mercury): Fix the redundant code in the previous commit --- pymycobot/mercury.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/pymycobot/mercury.py b/pymycobot/mercury.py index 4b2c189b..580b971c 100644 --- a/pymycobot/mercury.py +++ b/pymycobot/mercury.py @@ -45,5 +45,3 @@ def open(self): def close(self): self._serial_port.close() - -Mercury.go_home() \ No newline at end of file From 5d1060b9387604e1dfd39df6d1a1ed0e09df3183 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Thu, 4 Sep 2025 16:30:19 +0800 Subject: [PATCH 53/57] fix(Mercury): Resolved server communication issues affecting both arms --- pymycobot/close_loop.py | 7 ++- pymycobot/mercury_arms_socket.py | 78 +++++++++++++++++++++----------- 2 files changed, 57 insertions(+), 28 deletions(-) diff --git a/pymycobot/close_loop.py b/pymycobot/close_loop.py index 52e2053f..d774e70d 100644 --- a/pymycobot/close_loop.py +++ b/pymycobot/close_loop.py @@ -105,11 +105,16 @@ def _mesg(self, genre, *args, **kwargs): need_break = False data = None - timeout = 0.5 + if self.__class__.__name__ == "MercurySocket": timeout = 1 elif self.__class__.__name__ == "Pro450Client": timeout = 3 + elif self.__class__.__name__ == "MercuryArmsSocket": + timeout = 1 + else: + timeout = 0.5 + interval_time = time.time() is_moving = 0 check_is_moving_t = 1 diff --git a/pymycobot/mercury_arms_socket.py b/pymycobot/mercury_arms_socket.py index 32af5c5e..e4eb701c 100644 --- a/pymycobot/mercury_arms_socket.py +++ b/pymycobot/mercury_arms_socket.py @@ -3,7 +3,10 @@ import json import struct import socket +import sys import threading +import time +import traceback from pymycobot.mercury_api import MercuryCommandGenerator from pymycobot.error import calibration_parameters @@ -11,6 +14,21 @@ for mercury x1 robot arms (six-axis or seven-axis), using socket to communicate with the robot """ +SYS_VERSION_INFO = sys.version_info.major + + +def format_hex_log(data): + if SYS_VERSION_INFO == 2: + command_log = "" + for d in data: + command_log += hex(ord(d))[2:] + " " + else: + command_log = "" + for d in data: + command_log += hex(d)[2:] + " " + + return command_log + class MercuryArmsSocket(MercuryCommandGenerator): def __init__(self, arm, ip, netport=9000, debug=False): @@ -23,17 +41,39 @@ def __init__(self, arm, ip, netport=9000, debug=False): debug: debug mode """ super(MercuryArmsSocket, self).__init__(debug) + self.crc_robot_class.append(self.__class__.__name__) self.arm = arm self.calibration_parameters = calibration_parameters self.SERVER_IP = ip self.SERVER_PORT = netport self.sock = self.connect_socket() - self.read_threading = threading.Thread(target=self.read_thread, args=("socket", )) + self.read_threading = threading.Thread(target=self.read_thread, args=("socket",)) self.read_threading.daemon = True self.read_threading.start() self.get_limit_switch() + def read_thread(self, method=None): + self.sock.settimeout(3) + while True: + try: + data = self.sock.recv(1024) + result = self._process_received(data) + + self.log.debug(f"_read :{format_hex_log(result)}") + if not result: + continue + + with self.lock: + self.read_command.append([result, time.time()]) + + except socket.timeout: + time.sleep(0.1) + + except Exception as e: + print(e) + traceback.print_exc() + def connect_socket(self): sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) sock.connect((self.SERVER_IP, self.SERVER_PORT)) @@ -53,33 +93,17 @@ def __format(self, command: str) -> bytes: return b''.join([date_length, data_byter]) def _write(self, command, method=None): - log_command = " ".join(map(lambda n: hex(n)[2:], command)) - self.log.debug("_write: {}".format(log_command)) + self.log.debug("_write: {}".format(format_hex_log(command))) self.sock.sendall(self.__format(command)) + def _send_command(self, genre, real_command): + self.write_command.append(genre) + self._write(self._flatten(real_command), method="socket") - - - - - - - - - - - - - - - - - - - - - - - - +if __name__ == '__main__': + mercury_socket = MercuryArmsSocket("left_arm", ip="192.168.1.216", debug=True) + mercury_socket.send_angle(1, 20, 10) + # while True: + # print(mercury_socket.get_angles()) + # time.sleep(0.1) From 6e1e35c24db93b804acd868cdad8240a543e8fe4 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 22 Sep 2025 17:19:45 +0800 Subject: [PATCH 54/57] fix(MyAGVPro): Fixed the issue that some interfaces did not return --- pymycobot/myagvpro_bluetooth.py | 34 +++++++++++++++++++++++++++------ 1 file changed, 28 insertions(+), 6 deletions(-) diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index 21660a87..f3d7e7c1 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -1,12 +1,13 @@ #!/usr/bin/env python # -*- coding: UTF-8 -*- +import asyncio from .myagvpro import MyAGVProCommandProtocolApi, ProtocolCode, PLAINTEXT_REPLY_PROTOCOL_CODE class MyAGVProCommandApi(MyAGVProCommandProtocolApi): async def _match_protocol_data(self, genre, timeout=0.1): - for _ in range(20): + for _ in range(5): reply_data = await self.read() if len(reply_data) == 0: @@ -197,7 +198,7 @@ async def turn_right(self, speed): """ if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") - return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1)]) + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, 0x00, int(speed * 100 * 1), 0x00]) async def stop(self): """Stop moving @@ -411,14 +412,13 @@ async def get_pin_input(self, pin): """Get the input IO Args: - pin(int): 1, 2, 3, 4, 5, 6, 7, 8, 254 + pin(int): 1 - 6 Returns: int: 0: Low, 1: High, -1: There is no such pin """ - supported_pins = [1, 2, 3, 4, 5, 6, 7, 8, 254] - if pin not in supported_pins: - raise ValueError(f"Pin must be in {supported_pins}") + if not 1 <= pin <= 6: + raise ValueError("Pin must be between 1 and 6") return await self._merge(ProtocolCode.GET_INPUT_IO, pin) def get_estop_state(self): @@ -493,6 +493,7 @@ def __init__(self, address, service_uuid, char_uuid, debug=False, save_serial_lo self._service_uuid = service_uuid self._serial_filename = 'agvpro_bluetooth_serial.log' self._communication_mode = 2 + self._queue = asyncio.Queue() # Async Context managers async def __aenter__(self): @@ -503,6 +504,8 @@ async def __aexit__(self, *args, **kwargs): await self.disconnect() async def read(self, size=1): + if not self._queue.empty(): + return self._queue.get_nowait() return await self._bluetooth.read_gatt_char(self._char_uuid, size=size) async def write(self, data): @@ -510,10 +513,29 @@ async def write(self, data): async def connect(self): await self._bluetooth.connect() + await self._bluetooth.start_notify(self._char_uuid, self._handle_notification) + + async def _handle_notification(self, _, data): + await self._queue.put(data) async def disconnect(self): + await self._bluetooth.stop_notify(self._char_uuid) await self._bluetooth.disconnect() async def is_connected(self): return self._bluetooth.is_connected + @classmethod + async def connect_by_name(cls, name, service_uuid, char_uuid, debug=False, save_serial_log=False): + from bleak import BleakScanner + device = await BleakScanner.find_device_by_name(name=name) + if device is None: + return None + + return cls( + address=device, + service_uuid=service_uuid, + char_uuid=char_uuid, + debug=debug, + save_serial_log=save_serial_log + ) From ae878cd46a2d068d3e8492dc6fb739249fccf2c1 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 22 Sep 2025 17:28:10 +0800 Subject: [PATCH 55/57] fix(MyAGVPro): Fixed the interface parameter verification error issue --- pymycobot/myagvpro.py | 8 ++++---- pymycobot/myagvpro_bluetooth.py | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index fdd82c0b..182e4ffa 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -514,7 +514,7 @@ def move_left_lateral(self, speed): if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") - return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) def move_right_lateral(self, speed): """Pan the robot right @@ -526,11 +526,11 @@ def move_right_lateral(self, speed): int: 1: Success, 0: Failed """ if not 0.01 <= speed <= 1.00: - raise ValueError("Speed must be between 0.00 and 1.00") + raise ValueError("Speed must be between 0.01 and 1.00") if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") - return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) + return self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) def turn_left(self, speed): """Rotate to the left @@ -624,7 +624,7 @@ def set_motor_enable(self, motor_id, state): int: 1: Success, 0: Failed """ if motor_id not in (1, 2, 3, 4, 254): - raise ValueError("Motor ID must be 0 or 1") + raise ValueError("Motor id must be in (1, 2, 3, 4, 254)") if state not in (0, 1): raise ValueError("State must be 0 or 1") diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index f3d7e7c1..ca44ee71 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -262,7 +262,7 @@ async def set_motor_enable(self, motor_id, state): int: 1: Success, 0: Failed """ if motor_id not in (1, 2, 3, 4, 254): - raise ValueError("Motor ID must be 0 or 1") + raise ValueError("Motor id must be 0 or 1") if state not in (0, 1): raise ValueError("State must be 0 or 1") From 8baa8ed933603c7b345fb74b4b3e08bcf75d6f38 Mon Sep 17 00:00:00 2001 From: K-Shuffler <2220138602@qq.com> Date: Mon, 22 Sep 2025 17:38:43 +0800 Subject: [PATCH 56/57] refactor(MyAGVPro): Optimize get_robot_statuts interface return --- pymycobot/myagvpro.py | 6 ++++-- pymycobot/myagvpro_bluetooth.py | 4 ++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/pymycobot/myagvpro.py b/pymycobot/myagvpro.py index 182e4ffa..64cb0339 100644 --- a/pymycobot/myagvpro.py +++ b/pymycobot/myagvpro.py @@ -282,13 +282,15 @@ def _parsing_data(cls, genre, reply_data): return respond if ProtocolCode.GET_ROBOT_STATUS.equal(genre): + machine_states = [0] * 8 machine_status = reply_data[0] if machine_status != 0: - machine_status = Utils.get_bits(machine_status) + for index in Utils.get_bits(machine_status): + machine_states[index] = 1 battery_voltage = round(reply_data[1] / 10, 2) - return machine_status, battery_voltage + return machine_states, battery_voltage if ProtocolCode.GET_AUTO_REPORT_MESSAGE.equal(genre): respond = [] diff --git a/pymycobot/myagvpro_bluetooth.py b/pymycobot/myagvpro_bluetooth.py index ca44ee71..11d2a703 100644 --- a/pymycobot/myagvpro_bluetooth.py +++ b/pymycobot/myagvpro_bluetooth.py @@ -156,7 +156,7 @@ async def move_left_lateral(self, speed): if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") - return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) async def move_right_lateral(self, speed): """Pan the robot right @@ -172,7 +172,7 @@ async def move_right_lateral(self, speed): if self.get_significant_bit(speed) > 2: raise ValueError(f"speed must be a number with 2 significant bits, but got {speed}") - return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * -1)]) + return await self._merge(ProtocolCode.AGV_MOTION_CONTROL, [0x00, int(speed * 100 * 1)]) async def turn_left(self, speed): """Rotate to the left From d78dcd24ac76c488f8b3e1699576937b5f78a458 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E8=93=9D=E5=90=AF=E7=90=A8?= Date: Fri, 5 Dec 2025 10:46:07 +0800 Subject: [PATCH 57/57] feat(MyArmM): Add SD card detection interface. --- pymycobot/common.py | 3 +++ pymycobot/myarm_api.py | 5 ++++- pymycobot/myarmm.py | 8 ++++++++ 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/pymycobot/common.py b/pymycobot/common.py index 28a2cb29..85d98c2d 100644 --- a/pymycobot/common.py +++ b/pymycobot/common.py @@ -517,6 +517,9 @@ class ProtocolCode(object): SET_JOINT_DISABLE = '*7' SET_JOINT_ENABLE = '*8' + # MyArm M750 + IS_SD_INSERT = 0xC4 + class DataProcessor(object): crc_robot_class = ["Mercury", "MercurySocket", "Pro630", "Pro630Client", "Pro400Client", "Pro400", "MercuryTest", "Pro450Client"] diff --git a/pymycobot/myarm_api.py b/pymycobot/myarm_api.py index 76fa3f5a..426ea4f8 100644 --- a/pymycobot/myarm_api.py +++ b/pymycobot/myarm_api.py @@ -77,6 +77,8 @@ def _read(self, genre): timeout = 0.4 elif genre == ProtocolCode.POWER_ON: timeout = 2 + elif genre == ProtocolCode.IS_SD_INSERT: + timeout = 1 else: timeout = 0.1 @@ -132,7 +134,8 @@ def _mesg(self, genre, *args, **kwargs): ProtocolCode.POWER_ON, ProtocolCode.GET_MASTER_PIN_STATUS, ProtocolCode.GET_ATOM_PIN_STATUS, - ProtocolCode.GET_SERVO_D + ProtocolCode.GET_SERVO_D, + ProtocolCode.IS_SD_INSERT ] if genre in return_single_genres: diff --git a/pymycobot/myarmm.py b/pymycobot/myarmm.py index ce51d151..2906f0d7 100644 --- a/pymycobot/myarmm.py +++ b/pymycobot/myarmm.py @@ -162,3 +162,11 @@ def is_tool_btn_clicked(self): def clear_recv_queue(self): """Clear the queue for receiving commands""" self._mesg(ProtocolCode.CLEAR_RECV_QUEUE) + + def is_sd_insert(self): + """Check if the SD card is inserted + + Returns: + int: 0/1, 1: insert, 0: no insert + """ + return self._mesg(ProtocolCode.IS_SD_INSERT, has_reply=True)