diff --git a/cri_lib/__init__.py b/cri_lib/__init__.py index 5f3f04c..eec1630 100644 --- a/cri_lib/__init__.py +++ b/cri_lib/__init__.py @@ -2,7 +2,7 @@ .. include:: ../README.md """ -from .cri_controller import CRIController +from .cri_controller import CRIController, MotionType from .cri_errors import CRICommandTimeOutError, CRIConnectionError, CRIError from .cri_protocol_parser import CRIProtocolParser from .robot_state import ( diff --git a/cri_lib/cri_controller.py b/cri_lib/cri_controller.py index efbccb6..8bae446 100644 --- a/cri_lib/cri_controller.py +++ b/cri_lib/cri_controller.py @@ -15,6 +15,15 @@ logger = logging.getLogger(__name__) +class MotionType(Enum): + """Robot Motion Type for Jogging""" + + Joint = "Joint" + CartBase = "CartBase" + CartTool = "CartTool" + Platform = "Platform" + + class CRIController: """ Class implementing the CRI network protocol for igus Robot Control. @@ -25,14 +34,6 @@ class CRIController: RECEIVE_TIMEOUT_SEC = 5 DEFAULT_ANSWER_TIMEOUT = 10.0 - class MotionType(Enum): - """Robot Motion Type for Jogging""" - - Joint = "Joint" - CartBase = "CartBase" - CartTool = "CartTool" - Platform = "Platform" - def __init__(self) -> None: self.robot_state: RobotState = RobotState() self.robot_state_lock = threading.Lock() @@ -692,6 +693,7 @@ def move_joints_relative( acceleration: float | None = None, ) -> bool: """Relative joint move + Parameters ---------- A1-A6, E1-E3 : float @@ -764,6 +766,7 @@ def move_cartesian( acceleration: float | None = None, ) -> bool: """Cartesian move + Parameters ---------- X,Y,Z,A,B,C,E1-E3 : float @@ -838,6 +841,7 @@ def move_base_relative( acceleration: float | None = None, ) -> bool: """Relative cartesian move in base coordinate system + Parameters ---------- X,Y,Z,A,B,C,E1-E3 : float @@ -914,6 +918,7 @@ def move_tool_relative( acceleration: float | None = None, ) -> bool: """Relative cartesian move in tool coordinate system + Parameters ---------- X,Y,Z,A,B,C,E1-E3 : float @@ -1508,3 +1513,7 @@ def get_motor_temperatures( return True else: return False + + +# Monkey patch to maintain backward compatibility +CRIController.MotionType = MotionType # type: ignore diff --git a/cri_lib/cri_protocol_parser.py b/cri_lib/cri_protocol_parser.py index ddec120..bdd0a4c 100644 --- a/cri_lib/cri_protocol_parser.py +++ b/cri_lib/cri_protocol_parser.py @@ -33,13 +33,14 @@ def parse_message( self, message: str ) -> dict[str, str] | dict[str, str | None] | None: """Parses a message to the RobotState of the class. - Parameters: - ----------- + + Parameters + ---------- message: str Message to be parsed including `CRISTART` and `CRIEND` - Returns: - -------- + Returns + ------- None | dict[str, str] None if no Notification in necessary or a dict indicating which answer event to notify (key: "answer") and optionally an error message (key: "error") @@ -113,10 +114,10 @@ def _parse_status(self, parameters: list[str]) -> None: """ Parses a state message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `STATUS` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `STATUS` and `CRIEND` """ segment_start_idx = 0 @@ -289,10 +290,10 @@ def _parse_runstate(self, parameters: list[str]) -> None: """ Parses a runstate message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `RUNSTATE` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `RUNSTATE` and `CRIEND` """ with self.robot_state_lock: if parameters[0] == "MAIN": @@ -314,10 +315,10 @@ def _parse_cyclestat(self, parameters: list[str]) -> None: """ Parses a cyclestat message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `CYCLESTAT` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `CYCLESTAT` and `CRIEND` """ with self.robot_state_lock: self.robot_state.cycle_time = float(parameters[0]) @@ -327,10 +328,10 @@ def _parse_gripperstate(self, parameters: list[str]) -> None: """ Parses a gripperstate message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `GRIPPERSTATE` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `GRIPPERSTATE` and `CRIEND` """ with self.robot_state_lock: self.robot_state.gripper_state = float(parameters[0]) @@ -339,10 +340,10 @@ def _parse_variables(self, parameters: Sequence[str]) -> None: """ Parses a variables message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `VARIABLES` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `VARIABLES` and `CRIEND` """ variables: dict[str, float | PosVariable] = {} idx = 0 @@ -370,10 +371,10 @@ def _parse_opinfo(self, parameters: Sequence[str]) -> None: """ Parses a opinfo message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `OPINFO` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `OPINFO` and `CRIEND` """ values = [] for i in range(7): @@ -386,13 +387,13 @@ def _parse_cmd(self, parameters: Sequence[str]) -> str | None: """ Parses a cmd message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `CMD` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `CMD` and `CRIEND` - Returns: - -------- + Returns + ------- str: id of answer event """ @@ -414,10 +415,10 @@ def _parse_message_message(self, parameters: Sequence[str]) -> None: """ Parses a message message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `MESSAGE` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `MESSAGE` and `CRIEND` """ if parameters[0] == "RobotControl": if parameters[1] == "Version": @@ -468,15 +469,15 @@ def _parse_can_bridge(self, parameters: Sequence[str]) -> dict[str, Any] | None: parameters: list[str] List of splitted strings between `CANBridge` and `CRIEND` - Returns: - -------- + Returns + ------- dict[str, any] | None dict with the following keys: - id: CAN id - length: length of CAN packet - data: bytearray with can message - time: timestamp from CRI, 0 at the moment - system_time: system timestamp vrom CRI + - id: CAN id + - length: length of CAN packet + - data: bytearray with can message + - time: timestamp from CRI, 0 at the moment + - system_time: system timestamp vrom CRI """ if parameters[0] != "Msg": return None @@ -521,10 +522,10 @@ def _parse_config(self, parameters: Sequence[str]) -> None: """ Parses a config message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `CONFIG` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `CONFIG` and `CRIEND` """ if parameters[0] == "ProjectFile": with self.robot_state_lock: @@ -533,13 +534,13 @@ def _parse_config(self, parameters: Sequence[str]) -> None: def _parse_cmderror(self, parameters: Sequence[str]) -> dict[str, str]: """Parses a CMDERROR message to notify calling function - Parameters: - ----------- + Parameters + ---------- parameters: list[str] List of splitted strings between `CMDERROR` and `CRIEND` - Returns: - -------- + Returns + ------- dict[str, str] A dict indicating which message id to notify (key: "answer") and the error message (key: "error") """ @@ -550,10 +551,10 @@ def _parse_info(self, parameters: list[str]) -> str | None: """ Parses a info message to the robot state. - Parameters: - ----------- - parameters: list[str] - List of splitted strings between `INFO` and `CRIEND` + Parameters + ---------- + parameters: list[str] + List of splitted strings between `INFO` and `CRIEND` """ if parameters[0] == "ReferencingInfo": # handle bug in RobotControl with missing space before 'Mandatory' @@ -603,13 +604,13 @@ def _parse_info(self, parameters: list[str]) -> str | None: def _parse_execerror(self, parameters: Sequence[str]) -> dict[str, str]: """Parses a EXECERROR message to notify calling function - Parameters: - ----------- + Parameters + ---------- parameters: list[str] List of splitted strings between `EXECERROR` and `CRIEND` - Returns: - -------- + Returns + ------- dict[str, str] A dict indicating which message id to notify (key: "answer") and the error message (key: "error") """ @@ -621,15 +622,15 @@ def _split_quotes_aware(msg: str) -> Sequence[str]: """ Splits a string at whitespaces but ignores whitespace whithin quotes. - Parameters: - ----------- - msg: str - String to be splitted + Parameters + ---------- + msg: str + String to be splitted - Returns: - -------- - list[str] - list containing the splitted parts of the string + Returns + ------- + list[str] + list containing the splitted parts of the string """ parts = [] current_part = "" diff --git a/cri_lib/py.typed b/cri_lib/py.typed new file mode 100644 index 0000000..e69de29 diff --git a/pyproject.toml b/pyproject.toml index 8777b6b..5ce7654 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -12,5 +12,8 @@ dependencies = [] [tool.setuptools] packages = ["cri_lib"] +[tool.setuptools.package-data] +"cri_lib" = ["py.typed"] + [tool.isort] profile = "black"