From 118ca7af9c7bae6d25d580e0838363b69924afe0 Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 14:53:18 -0500 Subject: [PATCH 1/6] Add sphinx doc files and documents rws.py --- docs/Makefile | 20 ++ docs/abb_robot_client/api/rws.rst | 9 + docs/abb_robot_client/api_reference.rst | 7 + docs/conf.py | 37 ++ docs/index.rst | 20 ++ docs/make.bat | 35 ++ src/abb_robot_client/rws.py | 428 ++++++++++++++++++++++-- 7 files changed, 526 insertions(+), 30 deletions(-) create mode 100644 docs/Makefile create mode 100644 docs/abb_robot_client/api/rws.rst create mode 100644 docs/abb_robot_client/api_reference.rst create mode 100644 docs/conf.py create mode 100644 docs/index.rst create mode 100644 docs/make.bat diff --git a/docs/Makefile b/docs/Makefile new file mode 100644 index 0000000..d0c3cbf --- /dev/null +++ b/docs/Makefile @@ -0,0 +1,20 @@ +# Minimal makefile for Sphinx documentation +# + +# You can set these variables from the command line, and also +# from the environment for the first two. +SPHINXOPTS ?= +SPHINXBUILD ?= sphinx-build +SOURCEDIR = source +BUILDDIR = build + +# Put it first so that "make" without argument is like "make help". +help: + @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +.PHONY: help Makefile + +# Catch-all target: route all unknown targets to Sphinx using the new +# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). +%: Makefile + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/docs/abb_robot_client/api/rws.rst b/docs/abb_robot_client/api/rws.rst new file mode 100644 index 0000000..41779a4 --- /dev/null +++ b/docs/abb_robot_client/api/rws.rst @@ -0,0 +1,9 @@ +RWS (Robot Web Services) +======================== + +abb_robot_client.rws +-------------------- + +.. automodule:: abb_robot_client.rws + :members: + \ No newline at end of file diff --git a/docs/abb_robot_client/api_reference.rst b/docs/abb_robot_client/api_reference.rst new file mode 100644 index 0000000..43b37b6 --- /dev/null +++ b/docs/abb_robot_client/api_reference.rst @@ -0,0 +1,7 @@ +API Reference +================ + +.. toctree:: + :maxdepth: 2 + + api/rws \ No newline at end of file diff --git a/docs/conf.py b/docs/conf.py new file mode 100644 index 0000000..917aaa9 --- /dev/null +++ b/docs/conf.py @@ -0,0 +1,37 @@ +# Configuration file for the Sphinx documentation builder. +# +# For the full list of built-in configuration values, see the documentation: +# https://www.sphinx-doc.org/en/master/usage/configuration.html + +# -- Project information ----------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#project-information + +project = 'abb_robot_client' +copyright = '2022, Wason Technology, LLC' +author = 'John Wason' + +import abb_robot_client + +# The short X.Y version. +# version = abb_robot_client.__version__ +# The full version, including alpha/beta/rc tags. +# release = abb_robot_client.__version__ + +# -- General configuration --------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#general-configuration + +extensions = [ + "sphinx.ext.autodoc", + "sphinx_autodoc_typehints" +] + +templates_path = ['_templates'] +exclude_patterns = [] + + + +# -- Options for HTML output ------------------------------------------------- +# https://www.sphinx-doc.org/en/master/usage/configuration.html#options-for-html-output + +html_theme = "sphinx_rtd_theme" +html_static_path = ['_static'] diff --git a/docs/index.rst b/docs/index.rst new file mode 100644 index 0000000..e1eb68e --- /dev/null +++ b/docs/index.rst @@ -0,0 +1,20 @@ +.. abb_robot_client documentation master file, created by + sphinx-quickstart on Tue Dec 27 02:14:13 2022. + You can adapt this file completely to your liking, but it should at least + contain the root `toctree` directive. + +Welcome to abb_robot_client's documentation! +============================================ + +.. toctree:: + :maxdepth: 2 + :caption: Contents: + + abb_robot_client/api_reference + +Indices and tables +================== + +* :ref:`genindex` +* :ref:`modindex` +* :ref:`search` diff --git a/docs/make.bat b/docs/make.bat new file mode 100644 index 0000000..76b4a46 --- /dev/null +++ b/docs/make.bat @@ -0,0 +1,35 @@ +@ECHO OFF + +pushd %~dp0..\ + +REM Command file for Sphinx documentation + +if "%SPHINXBUILD%" == "" ( + set SPHINXBUILD=sphinx-build +) +set SOURCEDIR=docs +set BUILDDIR=build + +%SPHINXBUILD% >NUL 2>NUL +if errorlevel 9009 ( + echo. + echo.The 'sphinx-build' command was not found. Make sure you have Sphinx + echo.installed, then set the SPHINXBUILD environment variable to point + echo.to the full path of the 'sphinx-build' executable. Alternatively you + echo.may add the Sphinx directory to PATH. + echo. + echo.If you don't have Sphinx installed, grab it from + echo.https://www.sphinx-doc.org/ + exit /b 1 +) + +if "%1" == "" goto help + +%SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% +goto end + +:help +%SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% + +:end +popd diff --git a/src/abb_robot_client/rws.py b/src/abb_robot_client/rws.py index 74e4dc8..b5624f4 100644 --- a/src/abb_robot_client/rws.py +++ b/src/abb_robot_client/rws.py @@ -8,97 +8,176 @@ import websocket import threading -from typing import Callable, NamedTuple, Any, List, Union +from typing import Callable, NamedTuple, Any, List, Union, Optional from enum import IntEnum class ABBException(Exception): + """ + Exception returned from ABB controller + """ def __init__(self, message, code): super(ABBException, self).__init__(message) self.code=code class RAPIDExecutionState(NamedTuple): + """ + Execution state of RAPID tasks on controller. See :meth:`.RWS.get_execution_state()` + """ ctrlexecstate: Any + """Current controller execution state""" cycle: Any + """Current controller cycle state""" class EventLogEntry(NamedTuple): + """Entry within an event log. See :meth:`.RWS.read_event_log()`""" seqnum: int + """Sequence number of the entry""" msgtype: int - code: int + """Message type of the entry. 1 for info, 2 for warning, 3 for error""" + code: int + """The error code of the entry""" tstamp: datetime.datetime + """Entry timestamp in controller clock""" args: List[Any] + """Arguments specified when entry created""" title: str + """Entry title""" desc: str + """Entry description""" conseqs: str + """Consequences of the event""" causes: str + """Potential causes of the event""" actions: str + """Actions to correct the event""" class EventLogEntryEvent(NamedTuple): + """ + Event returned by subscription when event log entry created + """ seqnum: int + """seqnum of created event log entry""" class TaskState(NamedTuple): + """ + Current state of task running on controller. See :meth:`.RWS.get_tasks()` + """ name: str + """Name of the controller task""" type_: str + """The type of the task""" taskstate: str + """The curret task state""" excstate: str + """The current execution state""" active: bool + """True if the task is currently active""" motiontask: bool + """True if the task is a motion task""" class JointTarget(NamedTuple): + """Joint target in degrees or millimeters""" robax: np.array + """Robot axes positions. Six entry array""" extax: np.array + """Extra axes positions. Six entry array""" class RobTarget(NamedTuple): + """Robtarget""" trans: np.array + """Translation in millimeters. Three entry array""" rot: np.array + """Rotation in quaternion units [w,x,y,z]""" robconf: np.array + """4 entry configuration of robot. See `confdata` datatype in the ABB RAPID manuals for explanation""" extax: np.array - + """Extra axes positions. Six entry array""" class IpcMessage(NamedTuple): + """IPC queue message. Also used for RMQ. See :meth:`.RMQ.try_create_ipc_queue()`""" data: str + """Message data encoded as string""" userdef: str + """User defined message content encoded as string""" msgtype: str + """Type of messag""" cmd: str + """Message command""" queue_name: str + """Queue containing message""" class Signal(NamedTuple): + """Signal state""" name: str + """Name of the signal""" lvalue: str + """Logical value of the signal""" class ControllerState(NamedTuple): + """Controller state. See :meth:`.RWS.get_controller_state()`""" state: str + """The controller state""" class OperationalMode(NamedTuple): + """Operational mode. See :meth:`.RWS.get_operation_mode()`""" mode: str + """The operational mode""" class VariableValue(NamedTuple): + """RAPID variable value""" name: str + """The name of the RAPId variable""" value: str + """The variable value encoded as string""" task: str = None + """The task containing the variable""" class SubscriptionResourceType(IntEnum): + """Enum to select resource to subscribe. See :meth:`.RWS.subscribe()`""" ControllerState = 1 + """Subscribe to controller state resource""" OperationalMode = 2 + """Subsribe to operational mode resource""" ExecutionState = 3 + """Subscribe to executio state resource""" PersVar = 4 + """Subscribe to RAPID pers variable resource""" IpcQueue = 5 + """Subscribe to IPC queue resource""" Elog = 6 + """Subscribe to Event Log resource""" Signal = 7 + """Subscribe to signal resource""" class SubscriptionResourcePriority(IntEnum): + """Priority of subscribed resource. Only Signal and PersVar support high priority. See :meth:`.RWS.subscribe()`""" Low = 0 Medium = 1 High = 2 class SubscriptionResourceRequest(NamedTuple): + """Specify resource to subscribe. See :meth:`.RWS.subscribe()`""" resource_type: SubscriptionResourceType + """Type of resource to subscribe""" priority: SubscriptionResourcePriority + """Subscription priority""" param: Any = None - + """Parameter for subscription request""" class RWS: - def __init__(self, base_url='http://127.0.0.1:80', username=None, password=None): + """ + Robot Web Services synchronous client. This class uses ABB Robot Web Services HTTP REST interface to interact + with robot controller. Subscriptions can be created to provide streaming information. See the ABB + documentation for more information: https://developercenter.robotstudio.com/api/rwsApi/ + + :param base_url: Base URL of the robot. For Robot Studio instances, this should be http://127.0.0.1:80, + the default value. For a real robot, 127.0.0.1 should be replaced with the IP address + of the robot controller. The WAN port ethernet must be used, not the maintenance port. + :param username: The HTTP username for the robot. Defaults to 'Default User' + :param password: The HTTP password for the robot. Defaults to 'robotics' + """ + def __init__(self, base_url: str='http://127.0.0.1:80', username: str=None, password: str=None): self.base_url=base_url if username is None: username = 'Default User' @@ -167,7 +246,13 @@ def _process_response(self, response): raise ABBException(error_message, error_code) - def start(self, cycle: str='asis',tasks: List[str]=['T_ROB1']) -> None: + def start(self, cycle: Optional[str]='asis',tasks: Optional[List[str]]=['T_ROB1']): + """ + Start one or more RAPID tasks + + :param cycle: The cycle mode of the robot. Can be `asis`, `once`, or `forever`. + :param tasks: One or more tasks to start. + """ rob_tasks = self.get_tasks() for t in tasks: @@ -186,26 +271,52 @@ def start(self, cycle: str='asis',tasks: List[str]=['T_ROB1']) -> None: payload={"regain": "continue", "execmode": "continue" , "cycle": cycle, "condition": "none", "stopatbp": "disabled", "alltaskbytsp": "true"} res=self._do_post("rw/rapid/execution?action=start", payload) - def activate_task(self, task: str) -> None: + def activate_task(self, task: str): + """ + Activate a RAPID task + + :param task: The name of the task to activate + """ payload={} self._do_post(f"rw/rapid/tasks/{task}?action=activate",payload) def deactivate_task(self, task: str) -> None: + """ + Deactivate a RAPID task + + :param task: The name of the task to activate + """ payload={} self._do_post(f"rw/rapid/tasks/{task}?action=deactivate",payload) - def stop(self) -> None: + def stop(self): + """ + Stop RAPID execution of normal tasks + """ payload={"stopmode": "stop"} res=self._do_post("rw/rapid/execution?action=stop", payload) - def resetpp(self) -> None: + def resetpp(self): + """ + Reset RAPID program pointer to main in normal tasks + """ res=self._do_post("rw/rapid/execution?action=resetpp") def get_ramdisk_path(self) -> str: + """ + Get the path of the RAMDISK variable on the controller + + :return: The RAMDISK path + """ res_json = self._do_get("ctrl/$RAMDISK") return res_json["_embedded"]["_state"][0]["_value"] def get_execution_state(self) -> RAPIDExecutionState: + """ + Get the RAPID execution state + + :return: The RAPID execution state + """ res_json = self._do_get("rw/rapid/execution") state = res_json["_embedded"]["_state"][0] ctrlexecstate=state["ctrlexecstate"] @@ -213,6 +324,15 @@ def get_execution_state(self) -> RAPIDExecutionState: return RAPIDExecutionState(ctrlexecstate, cycle) def get_controller_state(self) -> str: + """ + Get the controller state. The controller state can have the following values: + + `init`, `motoroff`, `motoron`, `guardstop`, `emergencystop`, `emergencystopreset`, `sysfail` + + RAPID can only be executed and the robot can only be moved in the `motoron` state. + + :return: The controller state + """ res_json = self._do_get("rw/panel/ctrlstate") state = res_json["_embedded"]["_state"][0] return state['ctrlstate'] @@ -222,30 +342,77 @@ def set_controller_state(self, ctrl_state): res=self._do_post("rw/panel/ctrlstate?action=setctrlstate", payload) def get_operation_mode(self) -> str: + """ + Get the controller operational mode. The controller operational mode can have the following values: + + `INIT`, `AUTO_CH`, `MANF_CH`, `MANR`, `MANF`, `AUTO`, `UNDEF` + + Typical values returned by the controller are `AUTO` for auto mode, and `MANR` for manual reduced-speed mode. + + :return: The controller operational mode. + """ res_json = self._do_get("rw/panel/opmode") state = res_json["_embedded"]["_state"][0] return state["opmode"] def get_digital_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> int: + """ + Get the value of a digital IO signal. + + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + :return: The value of the signal. Typically 1 for ON and 0 for OFF + """ res_json = self._do_get("rw/iosystem/signals/" + network + "/" + unit + "/" + signal) state = res_json["_embedded"]["_state"][0]["lvalue"] return int(state) - def set_digital_io(self, signal: str, value: Union[bool,int], network: str='Local', unit: str='DRV_1') -> None: + def set_digital_io(self, signal: str, value: Union[bool,int], network: str='Local', unit: str='DRV_1'): + """ + Set the value of an digital IO signal. + + :param value: The value of the signal. Bool or bool convertible input + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + """ lvalue = '1' if bool(value) else '0' payload={'lvalue': lvalue} res=self._do_post("rw/iosystem/signals/" + network + "/" + unit + "/" + signal + "?action=set", payload) def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> int: + """ + Get the value of an analog IO signal. + + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + :return: The value of the signal + """ res_json = self._do_get("rw/iosystem/signals/" + network + "/" + unit + "/" + signal) state = res_json["_embedded"]["_state"][0]["lvalue"] return int(state) - def set_analog_io(self, signal: str, value: int, network: str='Local', unit: str='DRV_1') -> None: + def set_analog_io(self, signal: str, value: Union[int,float], network: str='Local', unit: str='DRV_1'): + """ + Set the value of an analog IO signal. + + :param value: The value of the signal + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + """ payload={"mode": "value",'lvalue': value} res=self._do_post("rw/iosystem/signals/" + network + "/" + unit + "/" + signal + "?action=set", payload) - def get_rapid_variables(self, task: str="T_ROB1") -> str: + def get_rapid_variables(self, task: str="T_ROB1") -> List[str]: + """ + Get a list of the persistent variables in a task + + :param task: The RAPID task to query + :return: List of persistent variables in task + """ payload={ "view": "block", "vartyp": "any", @@ -263,6 +430,13 @@ def get_rapid_variables(self, task: str="T_ROB1") -> str: return state def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: + """ + Get a RAPID pers variable + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a string + """ if task is not None: var1 = f"{task}/{var}" else: @@ -272,6 +446,13 @@ def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: return state def set_rapid_variable(self, var: str, value: str, task: str = "T_ROB1"): + """ + Set a RAPID pers variable + + :param var: The pers variable name + :param value: The new variable value encoded as a string + :param task: The task containing the pers variable + """ payload={'value': value} if task is not None: var1 = f"{task}/var" @@ -280,6 +461,12 @@ def set_rapid_variable(self, var: str, value: str, task: str = "T_ROB1"): res=self._do_post("rw/rapid/symbol/data/RAPID/" + var1 + "?action=set", payload) def read_file(self, filename: str) -> bytes: + """ + Read a file off the controller + + :param filename: The filename to read + :return: The file bytes + """ url="/".join([self.base_url, "fileservice", filename]) res=self._session.get(url, auth=self.auth) assert res.ok, f"File not found {filename}" @@ -288,23 +475,46 @@ def read_file(self, filename: str) -> bytes: finally: res.close() - def upload_file(self, filename: str, contents: bytes) -> None: + def upload_file(self, filename: str, contents: bytes): + """ + Upload a file to the controller + + :param filename: The filename to write + :param contents: The file content bytes + """ url="/".join([self.base_url, "fileservice" , filename]) res=self._session.put(url, contents, auth=self.auth) assert res.ok, res.reason res.close() - def delete_file(self, filename: str) -> None: + def delete_file(self, filename: str): + """ + Delete a file on the controller + + :param filename: The filename to delete + """ url="/".join([self.base_url, "fileservice" , filename]) res=self._session.delete(url, auth=self.auth) res.close() def list_files(self, path: str) -> List[str]: + """ + List files at a path on a controller + + :param path: The path to list + :return: The filenames in the path + """ res_json = self._do_get("fileservice/" + str(path) + "") state = res_json["_embedded"]["_state"] return [f["_title"] for f in state] def read_event_log(self, elog: int=0) -> List[EventLogEntry]: + """ + Read the controller event log + + :param elog: The event log id to read + :return: The event log entries + """ o=[] res_json = self._do_get("rw/elog/" + str(elog) + "/?lang=en") state = res_json["_embedded"]["_state"] @@ -329,6 +539,11 @@ def read_event_log(self, elog: int=0) -> List[EventLogEntry]: return o def get_tasks(self) -> List[TaskState]: + """ + Get controller tasks and task state + + :return: The tasks and task state + """ o = {} res_json = self._do_get("rw/rapid/tasks") state = res_json["_embedded"]["_state"] @@ -351,7 +566,13 @@ def get_tasks(self) -> List[TaskState]: return o - def get_jointtarget(self, mechunit="ROB_1"): + def get_jointtarget(self, mechunit="ROB_1") -> JointTarget: + """ + Get the current jointtarget for specified mechunit + + :param mechunit: The mechanical unit to read + :return: The current jointtarget + """ res_json=self._do_get("rw/motionsystem/mechunits/" + mechunit + "/jointtarget") state = res_json["_embedded"]["_state"][0] assert state["_type"] == "ms-jointtarget" @@ -362,7 +583,17 @@ def get_jointtarget(self, mechunit="ROB_1"): return JointTarget(robjoint,extjoint) - def get_robtarget(self, mechunit='ROB_1', tool='tool0', wobj='wobj0', coordinate='Base'): + def get_robtarget(self, mechunit='ROB_1', tool='tool0', wobj='wobj0', coordinate='Base') -> RobTarget: + """ + Get the current robtarget (cartesian pose) for the specified mechunit + + :param mechunit: The mechanical unit to read + :param tool: The tool to use to compute robtarget + :param wobj: The wobj to use to compute robtarget + :param coordinate: The coordinate system to use to compute robtarget. Can be `Base`, `World`, `Tool`, or `Wobj` + :return: The current robtarget + + """ res_json=self._do_get(f"rw/motionsystem/mechunits/{mechunit}/robtarget?tool={tool}&wobj={wobj}&coordinate={coordinate}") state = res_json["_embedded"]["_state"][0] assert state["_type"] == "ms-robtargets" @@ -387,11 +618,25 @@ def _jointtarget_to_rws_value(self, val): rws_value="[[" + robax + "],[" + extax + "]]" return rws_value - def get_rapid_variable_jointtarget(self, var, task: str = "T_ROB1"): + def get_rapid_variable_jointtarget(self, var, task: str = "T_ROB1") -> JointTarget: + """ + Get a RAPID pers variable and convert to JointTarget + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a JointTarget + """ v = self.get_rapid_variable(var, task) return self._rws_value_to_jointtarget(v) - def set_rapid_variable_jointtarget(self,var,value, task: str = "T_ROB1"): + def set_rapid_variable_jointtarget(self,var: str, value: JointTarget, task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a JointTarget + + :param var: The pers variable name + :param value: The new variable JointTarget value + :param task: The task containing the pers variable + """ rws_value=self._jointtarget_to_rws_value(value) self.set_rapid_variable(var, rws_value, task) @@ -411,31 +656,80 @@ def _rws_value_to_jointtarget_array(self,val): def _jointtarget_array_to_rws_value(self, val): return "[" + ','.join([self._jointtarget_to_rws_value(v) for v in val]) + "]" - def get_rapid_variable_jointtarget_array(self, var, task: str = "T_ROB1"): + def get_rapid_variable_jointtarget_array(self, var: str, task: str = "T_ROB1") -> List[JointTarget]: + """ + Get a RAPID pers variable and convert to JointTarget list + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a list of JointTarget + """ v = self.get_rapid_variable(var, task) return self._rws_value_to_jointtarget_array(v) - def set_rapid_variable_jointtarget_array(self,var,value, task: str = "T_ROB1"): + def set_rapid_variable_jointtarget_array(self,var: str,value: List[JointTarget], task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a JointTarget list + + :param var: The pers variable name + :param value: The new variable JointTarget value + :param task: The task containing the pers variable + """ rws_value=self._jointtarget_array_to_rws_value(value) self.set_rapid_variable(var, rws_value, task) - def get_rapid_variable_num(self, var, task: str = "T_ROB1"): + def get_rapid_variable_num(self, var: str, task: str = "T_ROB1") -> float: + """ + Get a RAPID pers variable and convert to float + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a float + """ return float(self.get_rapid_variable(var,task)) - def set_rapid_variable_num(self, var, val, task: str = "T_ROB1"): + def set_rapid_variable_num(self, var: str, val: float, task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a float + + :param var: The pers variable name + :param value: The new variable float value + :param task: The task containing the pers variable + """ self.set_rapid_variable(var, str(val), task) def get_rapid_variable_num_array(self, var, task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a float + + :param var: The pers variable name + :param value: The new variable float value + :param task: The task containing the pers variable + """ val1=self.get_rapid_variable(var,task) m=re.match("^\\[([^\\]]*)\\]$", val1) val2=m.groups()[0].strip() return np.fromstring(val2,sep=',') - def set_rapid_variable_num_array(self, var, val, task: str = "T_ROB1"): + def set_rapid_variable_num_array(self, var: str, val: List[float], task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a float list or array + + :param var: The pers variable name + :param value: The new variable float array value + :param task: The task containing the pers variable + """ self.set_rapid_variable(var, "[" + ','.join([str(s) for s in val]) + "]", task) - def read_ipc_message(self, queue_name, timeout=0): - + def read_ipc_message(self, queue_name: str, timeout: float=0) -> List[IpcMessage]: + """ + Read IPC message. IPC is used to communicate with RMQ in controller tasks. Create IPC using + try_create_ipc_queue(). + + :param queue_name: The name of the queue created using try_create_ipc_queue() + :param timeout: The timeout to receive a message in seconds + :return: Messages received from IPC queue + """ o=[] timeout_str="" @@ -452,16 +746,41 @@ def read_ipc_message(self, queue_name, timeout=0): #o.append(RAPIDEventLogEntry(msg_type,code,tstamp,args,title,desc,conseqs,causes,actions)) return o - def send_ipc_message(self, target_queue, data, queue_name, cmd=111, userdef=1, msgtype=1 ): + def send_ipc_message(self, target_queue: str, data: str, queue_name: str, cmd: int=111, userdef: int=1, msgtype: int=1 ): + """ + Send an IPC message to the specified queue + + :param target_queue: The target IPC queue. Can also be the name of a task to send to RMQ of controller task. + :param data: The data to send to the controller. Encoding must match the expected type of RMQ + :param queue_name: The queue to send message from. Must be created with try_create_ipc_queue() + :param cmd: The cmd entry in the message + :param userdef: User defined value + :param msgtype: The type of message. Must be 0 or 1 + """ payload={"dipc-src-queue-name": queue_name, "dipc-cmd": str(cmd), "dipc-userdef": str(userdef), \ "dipc-msgtype": str(msgtype), "dipc-data": data} res=self._do_post("rw/dipc/" + target_queue + "?action=dipc-send", payload) - def get_ipc_queue(self, queue_name): + def get_ipc_queue(self, queue_name: str) -> Any: + """ + Get the IPC queue + + :param queue_name: The name of the queue + """ res=self._do_get("rw/dipc/" + queue_name + "?action=dipc-read") return res - def try_create_ipc_queue(self, queue_name, queue_size=4440, max_msg_size=444): + def try_create_ipc_queue(self, queue_name: str, queue_size: int=4440, max_msg_size: int=444) -> bool: + """ + Try creating an IPC queue. Returns True if the queue is created, False if queue already exists. Raises + exception for all other errors. + + :param queue_name: The name of the new IPC queue + :param queue_size: The buffer size of the queue + :param max_msg_size: The maximum message size of the queue + :return: True if queue created, False if queue already exists + + """ try: payload={"dipc-queue-name": queue_name, "dipc-queue-size": str(queue_size), "dipc-max-msg-size": str(max_msg_size)} self._do_post("rw/dipc?action=dipc-create", payload) @@ -471,7 +790,14 @@ def try_create_ipc_queue(self, queue_name, queue_size=4440, max_msg_size=444): return False raise - def request_rmmp(self, timeout=5): + def request_rmmp(self, timeout: float=5): + """ + Request Remote Mastering. Required to alter pers variables in manual control mode. The teach pendant + will prompt to enable remote mastering, and the user must confirm. Once remote mastering is enabled, + poll_rmmp() must be executed periodically to maintain rmmp. + + :param timeout: The request timeout in seconds + """ t1=time.time() self._do_post('users/rmmp?json=1', {'privilege': 'modify'}) while time.time() - t1 < timeout: @@ -489,6 +815,9 @@ def request_rmmp(self, timeout=5): raise Exception("User did not grant remote access") def poll_rmmp(self): + """ + Poll rmmp to maintain remote mastering. Call periodically after rmmp enabled using request_rmmp() + """ # A "persistent session" can only make 400 calls before # being disconnected. Once this connection is lost, @@ -532,8 +861,41 @@ def poll_rmmp(self): return state["status"] == "GRANTED" - def subscribe(self, resources: List[SubscriptionResourceRequest], handler: Callable): + def subscribe(self, resources: List[SubscriptionResourceRequest], handler: Callable[[Any],None]) -> "RWSSubscription": + """ + Create subscription that will receive real-time updates from the controller. handler will be called + with the new values. RWS subscriptions are relatively slow, with delays in the hundreds of milliseconds. + Use EGM for faster real-time updates. + + A list of `SubscriptionResourceRequest` are used to specify what resources to subscribe. The following are + supported: + + * Controller State: `SubscriptionResourceRequest(SubscriptionResourceType.ControllerState, rws.SubscriptionResourcePriority.Medium)` + * Operational Mode: `SubscriptionResourceRequest(SubscriptionResourceType.OperationalMode, rws.SubscriptionResourcePriority.Medium)` + * Execution State: `SubscriptionResourceRequest(SubscriptionResourceType.ExecutionState, rws.SubscriptionResourcePriority.Medium)` + * Variable: `SubscriptionResourceRequest(SubscriptionResourceType.PersVar, rws.SubscriptionResourcePriority.High, "variable_name")` + * IPC Queue: SubscriptionResourceRequest(SubscriptionResourceType.IpcQueue, rws.SubscriptionResourcePriority.Medium, "queue_name")` + * Event Log: SubscriptionResourceRequest(SubscriptionResourceType.Elog, rws.SubscriptionResourcePriority.Medium) + * Signal: SubscriptionResourceRequest(SubscriptionResourceType.Signal, rws.SubscriptionResourcePriority.High, "signal_name") + + The `handler` parameter will be called on each event from the controller. The passed parameter will + have the following type: + + * Controller State: :class:`.ControllerState` + * Operational Mode: :class:`.OperationalMode` + * Execution State: :class:`.RAPIDExecutionState` + * Variable: :class:`.PersVar` + * IPC Queue: :class:`.IpcMessage` + * Event Log: :class:`.EventLogEntry` + * Signal: :class:`.Signal` + + The returned `RWSSubscription` creates a persistent websocket connection to the controller. It must + be closed with the close() method when no longer in use. + :param resources: Controller resources to subscribe + :param handler: Callable to call on resource events + :return: Active subscription + """ payload = {} payload_ind = 0 for r in resources: @@ -606,6 +968,9 @@ class SubscriptionClosed(NamedTuple): msg: str class RWSSubscription: + """ + Subscription returned from :meth:`RWS.subscribe()` + """ def __init__(self, ws_url, header, handler): self.handler = handler @@ -680,4 +1045,7 @@ def _on_open(self, ws): pass def close(self): + """ + Close the subscription + """ self.ws.close() From 9d7fe3e91e24570d27bcb77039055b73d2e3a2c9 Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 15:59:09 -0500 Subject: [PATCH 2/6] Document rws_aio end egm --- docs/abb_robot_client/api/egm.rst | 9 + docs/abb_robot_client/api/rws_aio.rst | 11 + docs/abb_robot_client/api_reference.rst | 4 +- src/abb_robot_client/egm.py | 53 +++- src/abb_robot_client/rws.py | 14 +- src/abb_robot_client/rws_aio.py | 321 ++++++++++++++++++++++-- 6 files changed, 378 insertions(+), 34 deletions(-) create mode 100644 docs/abb_robot_client/api/egm.rst create mode 100644 docs/abb_robot_client/api/rws_aio.rst diff --git a/docs/abb_robot_client/api/egm.rst b/docs/abb_robot_client/api/egm.rst new file mode 100644 index 0000000..670d814 --- /dev/null +++ b/docs/abb_robot_client/api/egm.rst @@ -0,0 +1,9 @@ +EGM (Externally Guided Motion) +======================== + +abb_robot_client.egm +-------------------- + +.. automodule:: abb_robot_client.egm + :members: + \ No newline at end of file diff --git a/docs/abb_robot_client/api/rws_aio.rst b/docs/abb_robot_client/api/rws_aio.rst new file mode 100644 index 0000000..b29c929 --- /dev/null +++ b/docs/abb_robot_client/api/rws_aio.rst @@ -0,0 +1,11 @@ +RWS (Robot Web Services) AsyncIO +================================ + +abb_robot_client.rws_aio +------------------------ + +The `rws_aio` module implements asyncio methods. To use, the `abb_robot_client[aio]` option must be installed with pip. + +.. automodule:: abb_robot_client.rws_aio + :members: + \ No newline at end of file diff --git a/docs/abb_robot_client/api_reference.rst b/docs/abb_robot_client/api_reference.rst index 43b37b6..a6938f7 100644 --- a/docs/abb_robot_client/api_reference.rst +++ b/docs/abb_robot_client/api_reference.rst @@ -4,4 +4,6 @@ API Reference .. toctree:: :maxdepth: 2 - api/rws \ No newline at end of file + api/rws + api/rws_aio + api/egm \ No newline at end of file diff --git a/src/abb_robot_client/egm.py b/src/abb_robot_client/egm.py index 7e8ce9a..354cd11 100644 --- a/src/abb_robot_client/egm.py +++ b/src/abb_robot_client/egm.py @@ -7,15 +7,31 @@ from typing import Tuple, NamedTuple, Any class EGMRobotState(NamedTuple): + """ + State information returned from robot through EGM + """ joint_angles: np.array + """Joint angles of robot in radians. Length is 6 or 7 depending on robot""" rapid_running: bool + """True if RAPID program is running on controller""" motors_on: bool + """True if motors are on""" robot_message: Any + """Full message returned from robot""" cartesian: Tuple[np.array,np.array] + """Cartesian position of robots, in ([x,y,z],[w,x,y,z]) format""" class EGM(object): + """ + ABB EGM (Externally Guided Motion) client. EGM provides a real-time streaming connection to the robot using + UDP, typically at a rate of 250 Hz. The robot controller initiates the connection. The IP address and port of the + client must be configured on the robot controller side. The EGM client will send commands to the port it receives + packets from. + + :param port: The port to receive UDP packets. Defaults to 6510 + """ def __init__(self, port : int=6510): @@ -26,7 +42,13 @@ def __init__(self, port : int=6510): self.count=0 def receive_from_robot(self, timeout : float=0) -> Tuple[bool,EGMRobotState]: + """ + Receive feedback from the robot. Specify an optional timeout. Returns a tuple with success and the current + robot state. + :param timeout: Timeout in seconds. May be zero to immediately return if there is no new data. + :return: Success and robot state as a tuple + """ s=self.socket s_list=[s] try: @@ -72,6 +94,13 @@ def receive_from_robot(self, timeout : float=0) -> Tuple[bool,EGMRobotState]: return True, EGMRobotState(joint_angles, rapid_running, motors_on, robot_message, cartesian) def send_to_robot(self, joint_angles: np.array) -> bool: + """ + Send a joint command to robot. Returns False if no data has been received from the robot yet. The EGM + operation must have been started with EGMActJoint and EGMRunJoint. + + :param joint_angles: Joint angle command in radians + :return: True if successful, False if no data received from robot yet + """ if not self.egm_addr: return False @@ -100,7 +129,16 @@ def send_to_robot(self, joint_angles: np.array) -> bool: return True - def send_to_robot_cart(self, pos, orient): + def send_to_robot_cart(self, pos: np.ndarray, orient: np.ndarray): + """ + Send a cartesian command to robot. Returns False if no data has been received from the robot yet. The pose + is relative to the tool, workobject, and frame specified when the EGM operation is initialized. The EGM + operation must have been started with EGMActPose and EGMRunPose. + + :param pos: The position of the TCP in millimeters [x,y,z] + :param orient: The orientation of the TCP in quaternions [w,x,y,z] + :return: True if successful, False if no data received from robot yet + """ if not self.egm_addr: return False @@ -137,8 +175,17 @@ def send_to_robot_cart(self, pos, orient): return True - def send_to_robot_path_corr(self, pos, age=1): - + def send_to_robot_path_corr(self, pos: np.ndarray, age: float=1): + """ + Send a path correction command. Returns False if no data has been received from the robot yet. The path + correction is a displacement [x,y,z] in millimeters in **path coordinates**. The displacement uses + "path coordinates", which relate the direction of movement of the end effector. See `CorrConn` command in + *Technical reference manual RAPID Instructions, Functions and Data types* for a detailed description of path + coordinates. The EGM operation must have been started with EGMActMove, and use EGMMoveL and EGMMoveC commands. + + :param pos: The displacement in path coordinates in millimeters [x,y,z] + :return: True if successful, False if no data received from robot yet + """ self.send_sequence_number+=1 sensorMessage=egm_pb2.EgmSensorPathCorr() diff --git a/src/abb_robot_client/rws.py b/src/abb_robot_client/rws.py index b5624f4..7eaf0f4 100644 --- a/src/abb_robot_client/rws.py +++ b/src/abb_robot_client/rws.py @@ -381,7 +381,7 @@ def set_digital_io(self, signal: str, value: Union[bool,int], network: str='Loca payload={'lvalue': lvalue} res=self._do_post("rw/iosystem/signals/" + network + "/" + unit + "/" + signal + "?action=set", payload) - def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> int: + def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> float: """ Get the value of an analog IO signal. @@ -392,7 +392,7 @@ def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> """ res_json = self._do_get("rw/iosystem/signals/" + network + "/" + unit + "/" + signal) state = res_json["_embedded"]["_state"][0]["lvalue"] - return int(state) + return float(state) def set_analog_io(self, signal: str, value: Union[int,float], network: str='Local', unit: str='DRV_1'): """ @@ -431,7 +431,7 @@ def get_rapid_variables(self, task: str="T_ROB1") -> List[str]: def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: """ - Get a RAPID pers variable + Get value of a RAPID pers variable :param var: The pers variable name :param task: The task containing the pers variable @@ -447,7 +447,7 @@ def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: def set_rapid_variable(self, var: str, value: str, task: str = "T_ROB1"): """ - Set a RAPID pers variable + Set value of a RAPID pers variable :param var: The pers variable name :param value: The new variable value encoded as a string @@ -698,13 +698,13 @@ def set_rapid_variable_num(self, var: str, val: float, task: str = "T_ROB1"): """ self.set_rapid_variable(var, str(val), task) - def get_rapid_variable_num_array(self, var, task: str = "T_ROB1"): + def get_rapid_variable_num_array(self, var, task: str = "T_ROB1") -> np.ndarray: """ - Set a RAPID pers variable from a float + Get a RAPID pers variable float array :param var: The pers variable name - :param value: The new variable float value :param task: The task containing the pers variable + :return: The variable value as an array """ val1=self.get_rapid_variable(var,task) m=re.match("^\\[([^\\]]*)\\]$", val1) diff --git a/src/abb_robot_client/rws_aio.py b/src/abb_robot_client/rws_aio.py index 9f88e6f..3d4b059 100644 --- a/src/abb_robot_client/rws_aio.py +++ b/src/abb_robot_client/rws_aio.py @@ -16,6 +16,16 @@ SubscriptionResourcePriority, SubscriptionResourceRequest, SubscriptionException, SubscriptionClosed class RWS_AIO: + """ + Robot Web Services asyncio client. This class has the same functionality as :class:`abb_robot_client.rws.RWS`, but + uses asyncio instead of synchronous interface. + + :param base_url: Base URL of the robot. For Robot Studio instances, this should be http://127.0.0.1:80, + the default value. For a real robot, 127.0.0.1 should be replaced with the IP address + of the robot controller. The WAN port ethernet must be used, not the maintenance port. + :param username: The HTTP username for the robot. Defaults to 'Default User' + :param password: The HTTP password for the robot. Defaults to 'robotics' + """ def __init__(self, base_url='http://127.0.0.1:80', username=None, password=None): self.base_url=base_url if username is None: @@ -87,8 +97,13 @@ def _process_response(self, response): raise ABBException(error_message, error_code) - async def start(self, cycle: str='asis',tasks: List[str]=['T_ROB1']) -> None: + async def start(self, cycle: str='asis',tasks: List[str]=['T_ROB1']): + """ + Start one or more RAPID tasks + :param cycle: The cycle mode of the robot. Can be `asis`, `once`, or `forever`. + :param tasks: One or more tasks to start. + """ rob_tasks = await self.get_tasks() for t in tasks: assert t in rob_tasks, f"Cannot start unknown task {t}" @@ -106,26 +121,52 @@ async def start(self, cycle: str='asis',tasks: List[str]=['T_ROB1']) -> None: payload={"regain": "continue", "execmode": "continue" , "cycle": cycle, "condition": "none", "stopatbp": "disabled", "alltaskbytsp": "true"} res=await self._do_post("rw/rapid/execution?action=start", payload) - async def activate_task(self, task: str) -> None: + async def activate_task(self, task: str): + """ + Activate a RAPID task + + :param task: The name of the task to activate + """ payload={} await self._do_post(f"rw/rapid/tasks/{task}?action=activate",payload) - async def deactivate_task(self, task: str) -> None: + async def deactivate_task(self, task: str): + """ + Deactivate a RAPID task + + :param task: The name of the task to activate + """ payload={} await self._do_post(f"rw/rapid/tasks/{task}?action=deactivate",payload) - async def stop(self) -> None: + async def stop(self): + """ + Stop RAPID execution of normal tasks + """ payload={"stopmode": "stop"} res=await self._do_post("rw/rapid/execution?action=stop", payload) - async def resetpp(self) -> None: + async def resetpp(self): + """ + Reset RAPID program pointer to main in normal tasks + """ res=await self._do_post("rw/rapid/execution?action=resetpp") async def get_ramdisk_path(self) -> str: + """ + Get the path of the RAMDISK variable on the controller + + :return: The RAMDISK path + """ res_json = await self._do_get("ctrl/$RAMDISK") return res_json["_embedded"]["_state"][0]["_value"] async def get_execution_state(self) -> RAPIDExecutionState: + """ + Get the RAPID execution state + + :return: The RAPID execution state + """ res_json = await self._do_get("rw/rapid/execution") state = res_json["_embedded"]["_state"][0] ctrlexecstate=state["ctrlexecstate"] @@ -133,6 +174,15 @@ async def get_execution_state(self) -> RAPIDExecutionState: return RAPIDExecutionState(ctrlexecstate, cycle) async def get_controller_state(self) -> str: + """ + Get the controller state. The controller state can have the following values: + + `init`, `motoroff`, `motoron`, `guardstop`, `emergencystop`, `emergencystopreset`, `sysfail` + + RAPID can only be executed and the robot can only be moved in the `motoron` state. + + :return: The controller state + """ res_json = await self._do_get("rw/panel/ctrlstate") state = res_json["_embedded"]["_state"][0] return state['ctrlstate'] @@ -142,30 +192,77 @@ async def set_controller_state(self, ctrl_state): res=await self._do_post("rw/panel/ctrlstate?action=setctrlstate", payload) async def get_operation_mode(self) -> str: + """ + Get the controller operational mode. The controller operational mode can have the following values: + + `INIT`, `AUTO_CH`, `MANF_CH`, `MANR`, `MANF`, `AUTO`, `UNDEF` + + Typical values returned by the controller are `AUTO` for auto mode, and `MANR` for manual reduced-speed mode. + + :return: The controller operational mode. + """ res_json = await self._do_get("rw/panel/opmode") state = res_json["_embedded"]["_state"][0] return state["opmode"] async def get_digital_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> int: + """ + Get the value of a digital IO signal. + + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + :return: The value of the signal. Typically 1 for ON and 0 for OFF + """ res_json = await self._do_get("rw/iosystem/signals/" + network + "/" + unit + "/" + signal) state = res_json["_embedded"]["_state"][0]["lvalue"] return int(state) - async def set_digital_io(self, signal: str, value: Union[bool,int], network: str='Local', unit: str='DRV_1') -> None: + async def set_digital_io(self, signal: str, value: Union[bool,int], network: str='Local', unit: str='DRV_1'): + """ + Set the value of an digital IO signal. + + :param value: The value of the signal. Bool or bool convertible input + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + """ lvalue = '1' if bool(value) else '0' payload={'lvalue': lvalue} res=await self._do_post("rw/iosystem/signals/" + network + "/" + unit + "/" + signal + "?action=set", payload) - async def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> int: + async def get_analog_io(self, signal: str, network: str='Local', unit: str='DRV_1') -> float: + """ + Get the value of an analog IO signal. + + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + :return: The value of the signal + """ res_json = await self._do_get("rw/iosystem/signals/" + network + "/" + unit + "/" + signal) state = res_json["_embedded"]["_state"][0]["lvalue"] - return int(state) + return float(state) - async def set_analog_io(self, signal: str, value: int, network: str='Local', unit: str='DRV_1') -> None: + async def set_analog_io(self, signal: str, value: int, network: str='Local', unit: str='DRV_1'): + """ + Set the value of an analog IO signal. + + :param value: The value of the signal + :param signal: The name of the signal + :param network: The network the signal is on. The default `Local` will work for most signals. + :param unit: The drive unit of the signal. The default `DRV_1` will work for most signals. + """ payload={"mode": "value",'lvalue': value} res=await self._do_post("rw/iosystem/signals/" + network + "/" + unit + "/" + signal + "?action=set", payload) async def get_rapid_variables(self, task: str="T_ROB1") -> str: + """ + Get a list of the persistent variables in a task + + :param task: The RAPID task to query + :return: List of persistent variables in task + """ payload={ "view": "block", "vartyp": "any", @@ -183,6 +280,13 @@ async def get_rapid_variables(self, task: str="T_ROB1") -> str: return state async def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: + """ + Get value of a RAPID pers variable + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a string + """ if task is not None: var1 = f"{task}/{var}" else: @@ -192,6 +296,13 @@ async def get_rapid_variable(self, var: str, task: str = "T_ROB1") -> str: return state async def set_rapid_variable(self, var: str, value: str, task: str = "T_ROB1"): + """ + Set value of a RAPID pers variable + + :param var: The pers variable name + :param value: The new variable value encoded as a string + :param task: The task containing the pers variable + """ payload={'value': value} if task is not None: var1 = f"{task}/var" @@ -200,6 +311,12 @@ async def set_rapid_variable(self, var: str, value: str, task: str = "T_ROB1"): res=await self._do_post("rw/rapid/symbol/data/RAPID/" + var1 + "?action=set", payload) async def read_file(self, filename: str) -> bytes: + """ + Read a file off the controller + + :param filename: The filename to read + :return: The file bytes + """ url="/".join([self.base_url, "fileservice", filename]) res=await self._session.get(url) assert res.is_success, f"File not found {filename}" @@ -209,22 +326,45 @@ async def read_file(self, filename: str) -> bytes: await res.aclose() async def upload_file(self, filename: str, contents: bytes) -> None: + """ + Upload a file to the controller + + :param filename: The filename to write + :param contents: The file content bytes + """ url="/".join([self.base_url, "fileservice" , filename]) res=await self._session.put(url, content=contents) assert res.is_success, res.reason_phrase await res.aclose() async def delete_file(self, filename: str) -> None: + """ + Delete a file on the controller + + :param filename: The filename to delete + """ url="/".join([self.base_url, "fileservice" , filename]) res=await self._session.delete(url) await res.aclose() async def list_files(self, path: str) -> List[str]: + """ + List files at a path on a controller + + :param path: The path to list + :return: The filenames in the path + """ res_json = await self._do_get("fileservice/" + str(path) + "") state = res_json["_embedded"]["_state"] return [f["_title"] for f in state] async def read_event_log(self, elog: int=0) -> List[EventLogEntry]: + """ + Read the controller event log + + :param elog: The event log id to read + :return: The event log entries + """ o=[] res_json = await self._do_get("rw/elog/" + str(elog) + "/?lang=en") state = res_json["_embedded"]["_state"] @@ -249,6 +389,11 @@ async def read_event_log(self, elog: int=0) -> List[EventLogEntry]: return o async def get_tasks(self) -> List[TaskState]: + """ + Get controller tasks and task state + + :return: The tasks and task state + """ o = {} res_json = await self._do_get("rw/rapid/tasks") state = res_json["_embedded"]["_state"] @@ -271,7 +416,13 @@ async def get_tasks(self) -> List[TaskState]: return o - async def get_jointtarget(self, mechunit="ROB_1"): + async def get_jointtarget(self, mechunit: str="ROB_1"): + """ + Get the current jointtarget for specified mechunit + + :param mechunit: The mechanical unit to read + :return: The current jointtarget + """ res_json=await self._do_get("rw/motionsystem/mechunits/" + mechunit + "/jointtarget") state = res_json["_embedded"]["_state"][0] assert state["_type"] == "ms-jointtarget" @@ -282,7 +433,17 @@ async def get_jointtarget(self, mechunit="ROB_1"): return JointTarget(robjoint,extjoint) - async def get_robtarget(self, mechunit='ROB_1', tool='tool0', wobj='wobj0', coordinate='Base'): + async def get_robtarget(self, mechunit: str='ROB_1', tool: str='tool0', wobj: str='wobj0', coordinate: str='Base'): + """ + Get the current robtarget (cartesian pose) for the specified mechunit + + :param mechunit: The mechanical unit to read + :param tool: The tool to use to compute robtarget + :param wobj: The wobj to use to compute robtarget + :param coordinate: The coordinate system to use to compute robtarget. Can be `Base`, `World`, `Tool`, or `Wobj` + :return: The current robtarget + + """ res_json=await self._do_get(f"rw/motionsystem/mechunits/{mechunit}/robtarget?tool={tool}&wobj={wobj}&coordinate={coordinate}") state = res_json["_embedded"]["_state"][0] assert state["_type"] == "ms-robtargets" @@ -307,11 +468,25 @@ def _jointtarget_to_rws_value(self, val): rws_value="[[" + robax + "],[" + extax + "]]" return rws_value - async def get_rapid_variable_jointtarget(self, var, task: str = "T_ROB1"): + async def get_rapid_variable_jointtarget(self, var: str, task: str = "T_ROB1"): + """ + Get a RAPID pers variable and convert to JointTarget + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a JointTarget + """ v = await self.get_rapid_variable(var, task) return self._rws_value_to_jointtarget(v) - async def set_rapid_variable_jointtarget(self,var,value, task: str = "T_ROB1"): + async def set_rapid_variable_jointtarget(self,var: str, value: JointTarget, task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a JointTarget + + :param var: The pers variable name + :param value: The new variable JointTarget value + :param task: The task containing the pers variable + """ rws_value=self._jointtarget_to_rws_value(value) await self.set_rapid_variable(var, rws_value, task) @@ -332,29 +507,79 @@ def _jointtarget_array_to_rws_value(self, val): return "[" + ','.join([self._jointtarget_to_rws_value(v) for v in val]) + "]" async def get_rapid_variable_jointtarget_array(self, var, task: str = "T_ROB1"): + """ + Get a RAPID pers variable and convert to JointTarget list + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a list of JointTarget + """ v = await self.get_rapid_variable(var, task) return self._rws_value_to_jointtarget_array(v) - async def set_rapid_variable_jointtarget_array(self,var,value, task: str = "T_ROB1"): + async def set_rapid_variable_jointtarget_array(self,var: str, value: List[JointTarget], task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a JointTarget list + + :param var: The pers variable name + :param value: The new variable JointTarget value + :param task: The task containing the pers variable + """ rws_value=self._jointtarget_array_to_rws_value(value) await self.set_rapid_variable(var, rws_value, task) - async def get_rapid_variable_num(self, var, task: str = "T_ROB1"): + async def get_rapid_variable_num(self, var: str, task: str = "T_ROB1"): + """ + Get a RAPID pers variable and convert to float + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The pers variable encoded as a float + """ return float(await self.get_rapid_variable(var,task)) - async def set_rapid_variable_num(self, var, val, task: str = "T_ROB1"): + async def set_rapid_variable_num(self, var: str, val: float, task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a float + + :param var: The pers variable name + :param value: The new variable float value + :param task: The task containing the pers variable + """ await self.set_rapid_variable(var, str(val), task) - async def get_rapid_variable_num_array(self, var, task: str = "T_ROB1"): + async def get_rapid_variable_num_array(self, var, task: str = "T_ROB1") -> np.ndarray: + """ + Get a RAPID pers variable float array + + :param var: The pers variable name + :param task: The task containing the pers variable + :return: The variable value as an array + """ val1=await self.get_rapid_variable(var,task) m=re.match("^\\[([^\\]]*)\\]$", val1) val2=m.groups()[0].strip() return np.fromstring(val2,sep=',') - async def set_rapid_variable_num_array(self, var, val, task: str = "T_ROB1"): + async def set_rapid_variable_num_array(self, var: str, val: List[float], task: str = "T_ROB1"): + """ + Set a RAPID pers variable from a float list or array + + :param var: The pers variable name + :param value: The new variable float array value + :param task: The task containing the pers variable + """ await self.set_rapid_variable(var, "[" + ','.join([str(s) for s in val]) + "]", task) - async def read_ipc_message(self, queue_name, timeout=0): + async def read_ipc_message(self, queue_name: str, timeout: float=0) -> List[IpcMessage]: + """ + Read IPC message. IPC is used to communicate with RMQ in controller tasks. Create IPC using + try_create_ipc_queue(). + + :param queue_name: The name of the queue created using try_create_ipc_queue() + :param timeout: The timeout to receive a message in seconds + :return: Messages received from IPC queue + """ o=[] @@ -372,16 +597,42 @@ async def read_ipc_message(self, queue_name, timeout=0): #o.append(RAPIDEventLogEntry(msg_type,code,tstamp,args,title,desc,conseqs,causes,actions)) return o - async def send_ipc_message(self, target_queue, data, queue_name, cmd=111, userdef=1, msgtype=1 ): + async def send_ipc_message(self, target_queue: str, data: str, queue_name: str, cmd: int=111, userdef: int=1, msgtype: int=1 ): + """ + Send an IPC message to the specified queue + + :param target_queue: The target IPC queue. Can also be the name of a task to send to RMQ of controller task. + :param data: The data to send to the controller. Encoding must match the expected type of RMQ + :param queue_name: The queue to send message from. Must be created with try_create_ipc_queue() + :param cmd: The cmd entry in the message + :param userdef: User defined value + :param msgtype: The type of message. Must be 0 or 1 + """ + payload={"dipc-src-queue-name": queue_name, "dipc-cmd": str(cmd), "dipc-userdef": str(userdef), \ "dipc-msgtype": str(msgtype), "dipc-data": data} res=await self._do_post("rw/dipc/" + target_queue + "?action=dipc-send", payload) async def get_ipc_queue(self, queue_name): + """ + Get the IPC queue + + :param queue_name: The name of the queue + """ res=await self._do_get("rw/dipc/" + queue_name + "?action=dipc-read") return res - async def try_create_ipc_queue(self, queue_name, queue_size=4440, max_msg_size=444): + async def try_create_ipc_queue(self, queue_name: str, queue_size: int=4440, max_msg_size: int=444): + """ + Try creating an IPC queue. Returns True if the queue is created, False if queue already exists. Raises + exception for all other errors. + + :param queue_name: The name of the new IPC queue + :param queue_size: The buffer size of the queue + :param max_msg_size: The maximum message size of the queue + :return: True if queue created, False if queue already exists + + """ try: payload={"dipc-queue-name": queue_name, "dipc-queue-size": str(queue_size), "dipc-max-msg-size": str(max_msg_size)} await self._do_post("rw/dipc?action=dipc-create", payload) @@ -391,7 +642,14 @@ async def try_create_ipc_queue(self, queue_name, queue_size=4440, max_msg_size=4 return False raise - async def request_rmmp(self, timeout=5): + async def request_rmmp(self, timeout: float=5): + """ + Request Remote Mastering. Required to alter pers variables in manual control mode. The teach pendant + will prompt to enable remote mastering, and the user must confirm. Once remote mastering is enabled, + poll_rmmp() must be executed periodically to maintain rmmp. + + :param timeout: The request timeout in seconds + """ t1=time.time() await self._do_post('users/rmmp?json=1', {'privilege': 'modify'}) while time.time() - t1 < timeout: @@ -409,6 +667,9 @@ async def request_rmmp(self, timeout=5): raise Exception("User did not grant remote access") async def poll_rmmp(self): + """ + Poll rmmp to maintain remote mastering. Call periodically after rmmp enabled using request_rmmp() + """ # A "persistent session" can only make 400 calls before # being disconnected. Once this connection is lost, @@ -461,7 +722,19 @@ async def logout(self): pass async def subscribe(self, resources: List[SubscriptionResourceRequest]): - + """ + Create subscription that will receive real-time updates from the controller. handler will be called + with the new values. RWS subscriptions are relatively slow, with delays in the hundreds of milliseconds. + Use EGM for faster real-time updates. + + See :meth:`abb_robot_client.RWS.subscribe()` for more information on `resources` parameter. + + The asyncio version of subscribe() returns an async generator. Use `async for` to receive events. + + :param resources: Controller resources to subscribe + :param handler: Callable to call on resource events + :return: Generator to use with `async for`. + """ self._init_subscription_convert_message() payload = {} @@ -587,4 +860,6 @@ def _convert_subscription_message(self, message): return UnknownSubscriptionMessage(message) class UnknownSubscriptionMessage(NamedTuple): + """Contents of an unknown subscription resource type""" xml: str + """Raw xml returned by controller""" From f12416106a6d8ee618e90117566909ab846d675e Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 16:28:18 -0500 Subject: [PATCH 3/6] Improve readme and add to sphinx --- .gitignore | 4 ++- README.md | 43 +++++++++++++++++++++++++++++- docs/abb_robot_client/api/egm.rst | 2 +- docs/conf.py | 33 ++++++++++++++++++++++- docs/figures/arm_logo.jpg | Bin 0 -> 15048 bytes docs/figures/nys_logo.jpg | Bin 0 -> 14902 bytes docs/index.rst | 1 + 7 files changed, 79 insertions(+), 4 deletions(-) create mode 100644 docs/figures/arm_logo.jpg create mode 100644 docs/figures/nys_logo.jpg diff --git a/.gitignore b/.gitignore index ca4f2a7..401f37d 100644 --- a/.gitignore +++ b/.gitignore @@ -157,4 +157,6 @@ cython_debug/ # be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore # and can be added to the global gitignore or merged into this file. For a more nuclear # option (not recommended) you can uncomment the following to ignore the entire idea folder. -#.idea/ \ No newline at end of file +#.idea/ + +docs/readme.md \ No newline at end of file diff --git a/README.md b/README.md index 500d9bb..8a82033 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,44 @@ # abb_robot_client -Python package to access ABB robots using Robot Web Services and EGM. \ No newline at end of file +[![Python](https://img.shields.io/badge/python-3.6+-blue.svg)](https://github.com/rpiRobotics/abb_robot_client) +![PyPI](https://img.shields.io/pypi/v/abb-robot-client) + +Python package providing clients for ABB robots using RWS (Robot Web Services) and Externally Guided Motion (EGM). +This package currently supports IRC5 controllers running RobotWare 6.xx. It does not support RobotWare 7+. + +This package is typically used with [abb-motion-program-exec](https://pypi.org/project/abb-motion-program-exec/), +which provides a higher level interface to generate motion programs. `abb-motion-program-exec` includes the ability +to initialize EGM operations, using this package to communicate with EGM. + +`abb_robot_client` includes three modules: `rws`, `rws_aio`, and `egm`. `rws` provides a synhronous client for Robot +Web Services (RWS) using HTTP REST, and the ability to create subscriptions using websockets. `rws_aio` provides +identical functionality to `rws`, but uses asyncio, with each method being `async`. `egm` provides an Externally +Guided Motion (EGM) client. + +Documentation can be found at: https://abb_robot_client.readthedocs.org + +## Installation + +`abb-robot-client` is avaliable on PyPi. Use the `[aio]` option to include support for asyncio: + +``` +pip install abb-robot-client[aio] +``` + +## Examples + +See the `examples/` directory for examples using the modules. + +## License + +Apache 2.0 + +## Acknowledgment + +This work was supported in part by Subaward No. ARM-TEC-21-02-F19 from the Advanced Robotics for Manufacturing ("ARM") Institute under Agreement Number W911NF-17-3-0004 sponsored by the Office of the Secretary of Defense. ARM Project Management was provided by Christopher Adams. The views and conclusions contained in this document are those of the authors and should not be interpreted as representing the official policies, either expressed or implied, of either ARM or the Office of the Secretary of Defense of the U.S. Government. The U.S. Government is authorized to reproduce and distribute reprints for Government purposes, notwithstanding any copyright notation herein. + +This work was supported in part by the New York State Empire State Development Division of Science, Technology and Innovation (NYSTAR) under contract C160142. + +![](docs/figures/arm_logo.jpg) ![](docs/figures/nys_logo.jpg) + + diff --git a/docs/abb_robot_client/api/egm.rst b/docs/abb_robot_client/api/egm.rst index 670d814..41b44f8 100644 --- a/docs/abb_robot_client/api/egm.rst +++ b/docs/abb_robot_client/api/egm.rst @@ -1,5 +1,5 @@ EGM (Externally Guided Motion) -======================== +============================== abb_robot_client.egm -------------------- diff --git a/docs/conf.py b/docs/conf.py index 917aaa9..1617895 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -22,9 +22,12 @@ extensions = [ "sphinx.ext.autodoc", - "sphinx_autodoc_typehints" + "sphinx_autodoc_typehints", + "recommonmark" ] +source_suffix = [".rst", ".md"] + templates_path = ['_templates'] exclude_patterns = [] @@ -35,3 +38,31 @@ html_theme = "sphinx_rtd_theme" html_static_path = ['_static'] + +# https://www.lieret.net/2021/05/20/include-readme-sphinx/ +import pathlib + +# The readme that already exists +readme_path = pathlib.Path(__file__).parent.resolve().parent / "README.md" +# We copy a modified version here +readme_target = pathlib.Path(__file__).parent / "readme.md" + +with readme_target.open("w") as outf: + # Change the title to "Readme" + outf.write( + "\n".join( + [ + "Readme", + "======", + ] + ) + ) + lines = [] + for line in readme_path.read_text().split("\n"): + if line.startswith("# "): + # Skip title, because we now use "Readme" + # Could also simply exclude first line for the same effect + continue + line = line.replace("docs/figures/", "figures/") + lines.append(line) + outf.write("\n".join(lines)) diff --git a/docs/figures/arm_logo.jpg b/docs/figures/arm_logo.jpg new file mode 100644 index 0000000000000000000000000000000000000000..efeee11df24c7b00d5b432b2764257ac59374560 GIT binary patch literal 15048 zcmbWd2_Tf=_b>jAZLHaM8L|_y3mK9vNt6^Z$xckREDe)=PZY9FM3R{7iHu#MMA>DV z3PolrW0)~>U*GTl_x*nF{oi~4_kSOr*T=KG?>Xl=&w0){?@OPdF9SShEvzj72w09o zjspOF1vq9N>E{gqwzhyW0069DA0NO7A_(~Nk3!!9j$iOah9N_Jk+-C@)J_2Ur>$)n zxBk(|b9k4-vH$g#zRG#U+RO}b!NJbL`kXn~0RWs<=lp_@3_Ji37!(%bV0l{V%2j76 z=m&rSU;|hH4FGWW2)$){(c;qKJ*~~nq(Z?#|G59ZE~Ke{((_5x>VlNizncHg0I$cb zkT8(U3*c}qPp?o95GR88W<=Pn!*&9Q1#Sc!Vg{x|90C#uVv$4a^G|%pr@)PWVv|Gc z85raVjya_HmS>>nA?^op>g{kZ5Hp?waq?|HuLux-2C?kT@IXHhlR+#H=;a;?08E^R z?O|RXz92pUV$P6D4rU-W0vCeQ=Rfd`|G;5hkszG_V1~RE72@aP8z!abp(Leo@}$0$ zl~=?~udp!H3+^5P?jfF1X2`%>?mN^ z55E~EbtqI122 zhys#;44??80-AsxU67+z!wMvLVySW1;hc#Kn8Fh$ODQ13{VNw z0QEp4&<1n@J-{F^0(=A}fq7sV_y+t02mlG7fR+&o;ezl(L?JMU97F}83DJibL(C!P zAP$hLkn0d1NDw3(f`TMKG9bB-B1k!;2GRg&hx9;(A>)u)$O>cw@*A?xz{tSKAi!{x zL7qXKL7%~t!G_@ygDZm%Loh=$Ln6aHhDQt)3@;d38G0B-7$zB(8GbVCFanGmj6#gk zjH-jLwYSj3JD%jOmQ|j1`RajISAo7(X#CGj1~OF|jc5Gf6S2G8r;iF*!1M zFa)8j`7uf%BaBv*sILTqp;m2{8;}OS8j<*~u9DAI6 zoXVVLoYy$RIqz{+b9Qsia{l4s;*#ew;d15*8_1i< z`6MNCAz zMAAjDB9kKfqEe#fq5+~gqHUsI#F)gC#q7l*#LC15#5TnR#0|wg#M8wa#pfg#B$Oo_ zB<@H&krC5@b703<2>VNlUk@lz>P89&Z^{N(YV;}yrJRXJ5nRd1`-s;;OBshv}cS8G%Ir7o-P zte&Gjq)t1bbK>TS$`kV%d>Usp;x%4t{MJ;~^w2EU{H(>LWub-EdZk6wR?+s-F4LaT z;n%U%Nzv)mIndS94biRF-O!WOyRKKFH?1$Ae?dP}|LsZUlc!IjPj;T%Gte~%GiWr} zHdHkXFnn&fZlqx3WmIW|KXvSs`>FC%%f?d1*Nq<=FTw=r^!>3HB%*1 zf72JHzfPYx9df$m^sbqKS&Uit8OAe~XVTAnFy}LOG%qq=v^ZwrV^M2Cu+*`NAk)Y`+k#+qb=NCzrPG8EtH1DYB81C46nfvm! z%QcsGoz6JrIxSyOzY=q0#&=c z+fBDO2yTQsqUk#Gb*JmkuT$Oa+$-F7Zdl(axk2zS^C1pEm&~wA+CQ$7!THhkf}`M#TeW`0F}M1L!PjQ?(cT|jjJ{if4RY#?jk^}zNZzMz1hexxKa z5;=ZLazs-kZ)8y9 zXq0kPTGU#!MRe62raK;YdQsA-IMhmvX-s)6B=$yZFIonji2ioh^6s-Z_PBt!_wgs< zbL0OeI3>JJJeqhn5uaq4RGWMxIV5>H#V`ev%9QGt`XNm#tuT$2?wS5B<3vV&1~tfY?}>B09RdguGD^nLEP@Bc7h zGw^oMVz6(>bO`tM)Z5NsgW>jf`tRCCbVpi8bw*p>>%4FIp!=b9OmFPf$CDplj~k75 zO~5C5KArhA_}TjN$mIFS@hQitndxiO%QK!c>$5j!iF3E-DD!t0m>1H&@O;T%lvu1- zQd+_;>n^`pIkPgldU16g?}7jMHS{a>TjF=F@A+%6wVHL!_0A28jgLQEeti3R>nCM1 zd5d?eF=53ShQNk6%H)05p{yX!J=%4Dp+JAd@F6=Cl0!ftJbh0S<*`EI1(7x0D z8YO}Xr9L`PI(SX9p)Jq@>2&%$U7Vx+ND=QlZ8!Ib2 zD-_Dk#m>&b2^J{Z5pFKdBZv6#CWq4xXMw+*tWeg&5&!=Ry&K?V1)70EM#wRMffvHa z3!(P|Fwm!AK8&mmL!N&Y2m>P%GYd!(I|n$Rg$E>`k&yu;mYE6kXCN_PKfuJx%qOj3 z%EE8&4m}nupc$7_&MI@dp-0eRoFJ=pBP5=UT}W6&R7_4@K~YIrTSr$<|D=K08FLFu zE9_7d$E~s(4aa^|bm~ z&GW{l=9bpBSM9HR`}zk4hu#jqoA~s3a%y^Jc5Y=A|MlDVwe^i3#NU7Z?vQrLd;5oc zK>)^ovh^>{{s+EzLB1HkHDH1s@&#dt04pOe6SK4i3!kYy)IFI0m}VTS!0DXwh8{K< zEeC?&jgWD6AzAGeIpQH}|KRNZjIsFtE6)DK*uVLj12`EW;Nmgz0&w7fT9K{@{8xRk zBof&;*1ag&IoZNyRBI?Qnk%{XkvrrTw7pK5U^m}32=gLLWjwZ6(tUDk`oUfFw}&PG z>u!Vtd_m{;webF0skgx=TT4FUe^ob?6lGrg{oSADbgB&Yjt(@3id`|zjow#9ESF}V zAku*?`_*l6{}5}RXSR=LzV7Lg5>=A6-Vk$_&Oxs2Qq{6W(I02AbYS^veKiSvP^{La zDf7drjo)vMQ#0y@RrjCznV1zxQ;6m1e#uB+dAieu_I8PTrQx@WnV*Y@=9{lHKjV%z zBKf-0Z)3CWF6m$|*j7Pip8n@4wJPVF@2+?eCFfJk>8%a6u*UBarhQRHw2Egn`s<(F zg^^D3^^_k=F?Jbgx0W-9bz6^WN&UR-Ew-t5bR&AqS?|7hQrVn+9^j@<`x~ zA&oT62d9TrnG&|8_oH{2oW|fVoR=^eS!r9huC;*h)1?DC?>mRWrfLod-Ke*QYxhsC zvDC%(8SBtSiBIbuza?i}zUw;wl@5$tA>TSRD*~(Z?yBxXQPN%^(#!iKY)+mnjgc8s z(5~DbR0N#|w=cST)p>1N7{Xu1yUI;!JIc|#35f1Rxyb5AL@%`WwjG!7uZwnAYukgG zSl-!iq!*9KQR@rVRBQRR z+F`U8cjoOb1A=O6R;cDs-Fic+Y})+ySE;vhvCoE}9}|9P{d7E7>1l6;Y7U>6>1@Y( zuL$H)bglKfKB!*B%Is|$_DuKUe~kAp6&EfZ1Z|@&+qn)NM(1Tt{ZSs~>eUWFoC;L&)mor$-HiN{nbo+~DYxQ6E{=!G*aTrEaTVQJ+N1-NbF(PN z_)~fgzr*MNuSMrTiDe{|XkJEp9woW@<}%JmCa1hmHf!;u%=Pv4`KuyfQuj4iyZ>2@hDguJb>W1* zmAU#d+WD#%HY6)KSTv-$Ao!O+@UKvWWbW13!on}Z-rk0VX+Nxg+116UQXGK{&h5`CW_^-^pF0EUEUW!=LlJK8I9TyC!J}8xR!nwu zFo^TC-e~4#NrovMb4R^`qPVt*Ar%SV4yTO*5At*`8QDWzy-CVdpg4wq@5tR9yipU19Cpd4 zb-r|h3l0R+^!Sl4E>sx?zUP>q*xVDpa*$^%8<}9A`}-geiIieCr z9O~N&Sm}D+8aJ6yRhA$!!jYZt3_@ba&CAY$3ODpV6&S~bEo*@4eP zYg~xix$I7!?k29?y=oz>FyQ@&eJ7?x@!b_hO#eed_Mqu`RrK3z4Ey<=;6}arNIqqjT5A_VEGWCz!D0t1eU12fh zC-b9Q?TajL*@wC&G|FDdOuTvB<#CYMZ2gpY?@di0vZ>GSXzQD^Yx?;x^*@FGO5j*1*M{mB}@Svl^}oMb(U*#j7Zo=m%<97p3{Nq^W65hhp_m-eZGM4jfOKX&pb;P1=sdXLaJg# zI`CgrrJoK2ZZm=x6ufErSa#T)1RdyUElfby=%@o@q@xN)lO9!GvYG{r>VGT^Z>X`-U zcKh#-IWm6Udx`nVg=QvOJ3QsjI$`u~;$pDh-|v}^r&rNt!I>T|$NF6^tzs5F7krIz zHy3c)*GFq4MXGOYJliB>ryQpPYxNa>@CR>Q(WI(7lPEj|bxw@Z8@%@YQpXMBE-TpE z>2Gd&H;ziO556;OVFp#qF&>@ZGfgHaFQUU_$1nlw>N8H=w7{u`RcnvEOI*gY zsr%ZAu=;Vb*dB4-Um|=95k?gvXi`s-Ju3ZNZolV*{L=sWZb@s6s83bdD_Gy@gU=aR zAC%kQd35Cudj5Ck^{!uj>iSQ1;CxzkwO(kajNRuQ==oZwef7f6_U3{Ii)iB{0echB zd-?AwOd)ob4saLu!T4pS%G2_P5NW8vp?7VHx-Ur!aYqdAe}6R=kLD9zvFo>Sb+d_h zo#EkP)n)mMd6o=)uCxzyQ&VZNVRWwrjUFVB4@p@@Lwr}a2k zYhz|;GP6P5n>HgcAIdNWIVI6s*so|FBbikR1wLch6<_6&PmWO+(;q6_c_TaV&`UKe z@W-di*0|Zo(9FiU*&FZv`039X6*Tz`c|Gs2RW-I=Y8%ga+c@~5I^^YBT>cUeod~S>4x0BVm z3vZega4H1ushxrX*Y}-fQmRlJbbwRuPAxh4$MyxHtVUmWu3HGAtA$1%{U4A6XM1x2z}`F-g6{c_ZWhiqW~GLc zh03^y)#;roM@b3K#UK4Gy?jTzBqIYQbY+G`=BeGWyKuBG_Pb%v65;eVS;^-fRl4$L zQAGbpjrM{62XTrIGEI-&S;^j&O>}w7-Pw%B%0&m54YI!@(u7?Kav(pbxbk*nEa0cDy*X#9&(kK7oC9hBqB_Y3;gE}^Ghm(F~+al;ateo#gS z;$`SSkH3*Bc+Ui~Tn)mq%5p_LwToNBY}JlC17obi$N25byauF*js0aG*Z51tfi9<8 z+-=V)aF`{sQ3olJxYmQ1V_a@F=00Rnm3cP>TlQU5;Zo6i1^1B0LcA}T;s$L2w8 zZ*Zy@=uR=Gy*|LfeZ(UlrMw5y zc~`BV>&$}GVUV|{=oaCAY$k%>*fv4EN@N@?llufs(6Ocs*ZkBIz97n!KNE8AYmlhE z{@Y>fMkDAzVjrQG8xUAg*4A4bjXYI=l9|V zI@*&>AH0tpjh)0bCC5<^vF~ZxWUtl8UEeaD37?5y5^CSu)GB4)>F+&>sqb1>Wb6fl zL79N*8GfcAp;!c~kq-nHC6N zo`KH^_hSgQOJwEhe)KG2RXeK+o1tDkJ~wswVAT0rg4MCyW5Ic4uoEhZ{g1n&Ahu}h zFu>_gH7I}{Ixrkb1`pBeTrPCrtm@DGv~ICB+C!I*(CvuLDmozF zPMD?*xT@0u>tpr%UCswZ@Z~3%ro{vbD7=O)@&+Mx>i4HUgPU4C>X~7GbA?^5^r^Nh3|VBi>w*__~a}F_(20`(2#Idh+ReiX^({y&foZs(RQ2ITmkEgeO+J+*WJ4 zV$L-%YSo`>Wv!|@lN4sqDd!BcBIrSnnl1@^vkEhTlK}EcSrIw((%e3f#zz!&B+`fa; zUw6a@G*xno4k#QYD9{Gx>A->VS%82hD;8|l;gMu1?yY%30V$oV#Z-ijLpcWeyx0h4 zRGBk1>`tZw7Oy-?1~f(4vu1yPHN4$ylD%O@f*mw=ic?}^M z^!@&J+}F^lT#lK&fqHTz1yZ2=&JGj%5%Y375nMDl!B$*7k*1ZXnv!ayetpX6r%2S_ zJD*$4kWoVDdwOf4;tyZL^4?Pjo7*W_h1dvq@0O z9kH53_|G8*q`QS8tj3dX+c#^UUpB1(&;b_E1%4M{`*JDK}#$ zqq#TX6a_M6btnyZU_&s@)_p<>q`4qIu*|6Dy}aH0NjsRq6nM+FEJlTbl5~T+uY&|v zAzFO~mgcnZ-U*fDKj)guVh91R!y=}{%9@@T+8j?-N|1@N&zHKMs9Akl;3G7U0_K!@ zzM#Q7cpzu7J#Y>bjABH7&3%Lnvre&TQC(Fr&;9!N;9GxjU~i%K{m#Y{jG=Fb-bBNw zme6IyzLX?*uJz_G(Sb~-A9R3f2qpQ^fhSR9aXOGFUqA;273n~Vd+d9}UnHCnO-P)e z1LOe!t%N2xV#vzyB+#$N%x{|=ly?b|4c*8tc$G^{7zc_)x!_DYuE|Si*Y|CzS(LTF z&1$LCOS}HG2HbV-x#_b9uR(&jQ{Y0)F|`4BTS>$A3MTXuS7{AbvmP0Z1{5 zC0*V24*`E%Xq=x8+SRGtM8;M4CT_L;X^Wp+L4OylrCr>!r8DEELDEa6Akj1FCMC=# zMuQ7v@1jk0sGzskLqPv_GX|eM!+4nvOk_mUGF0|HflIVZ2flWqAavj*OC24k68Z~S zLdk;dYMtQuwqlt?wOSHKxd$kuYG>G5uegeR$(Jt@xc|(s9cYEKgOh`n$XedWICSG! zI?9VsyK3pI?AjA1BYC%sm17BuD$+X8-`kdbC^U z1sZHH5bu$| ztu+Ku%ixox#jwq%d%+cnPf{mw`p-;IJC02Up9YEIS2M`&1_??F66H!V@`!@bb=6#$oH$;ta@8)AGlDc7IOOJ zum;~kS}3Az(&_Za7bx|Ls~bgLrS+vxH$KYMRaL!E;S_2(mSlxDhd2tFKuo~*G_{u? zR2;hJIqrAqmM0cw-KOyXs%9fd^RUprEhAk za5B8Frq2lbtTP}Z^0UPW!K=Pzx!LjyeWbqhTVR!Suqn;emvy0&El8UUp()Q6v zX~poWvtd@q?{gi>d6#d>D#_#u9E|^TbEKRD=Xr^D!y6FYunYtzO4OamfG5RGHD^IB zKdFW1R1f%tKjW%U^7*}>Vs3l`m7SN@G;!B>tpaCYECI;%QuUglmEsE8)w(QT4fb-xJ4=4JL-%JI0> z&wN7n!gIxwgMdCow~*j1IN|&@Suv($Uq$%2n$jENs*Mndbl6`}tNi4Z z!_lK1I`rFy>0RSZ_XJAoTSlh4cd`dCNk!a4uw+Ro0y15DJsinJuC~M2eBS&nYEv9_ zzcMxU`B2%Dx>!qe59kXnFJQB9gtOTB56CnaN32$)8)fC&8 zt;U+nYyBrSl=DYc6y;3d_Yu-2b}Ol+kwO|)E5 z|Kvhs9*w=JF~68;A^p2Qb3)&>%Z>YZJ8-~*9a$o)uTgmd2A2p$v=B( zyln*Uyij*-=ep+KZ~BHc--@0CKSn(f>NZ4>p|R%?`E3qrRAbp`9}!R~vJ-wxVBM(* zw6^tObur;}u>LeZahuSaO{pKN`h#milI-4T4LU_+)B2YPx41KLzDucK>JWUFA&7zz zK0GL=Mz`mWSQhsg>nFHPHgCwZ<$LFE+g-``y>8DhoYU~_v3JlTDOe?%ld7r^*Ci2& zK2vmMt=RHY;0w7n>j{O3om( z;Rk4W6=axOJF&>G&1o*_FKD%VUbUWRPZ$Y{oXy}7Wqr&&{#<3naEyFBYYjY7G8Z)o zn87iI88SCbaH#i6tbAlq4BT0)de-YsyJ}Yt_uC9DjVtjdWJ2EwGuHXXz6C>v3wEHN zHl5W8tBu5x5D$9j04p`hUAM+#l@;ZJjCr;`Rk1L}Suo`;m~c*4S=RiKD2qwYW9~vw z)9!)OgQ~O9%f&Flg{=U*Wva1sq-DSJ<=Uq|ZkwI|w52BV%Hnm=N!|?o`6RZnDcm)c zKf5%x2cWWL6Q`*H8LN_cF_ly~!k6scC7z58smVZ8gilocI$PlJ90gL@BOsrp@W~!S zzKGY!A)S3@6Br-u%M!r`E`;teMF+xJBA@ib1dQwnlod>$E1#c{9!R`on_Awg=X8)n z<*vHcX=3HEnW%torCZn!sr=8d`YA^a|!B(|T!zb6` z-7jUf3vos^BpZ;0V<^{yESwi6yGSjGDAU(Stop;bl@k8W-Y(tn+T5^glGg=ehv9hBz9TaDHmZ0+ zJt_ngKo|_bWuV~YRPT>QHmgT%Oo*xvr)|7+^Pc~3_+ne-n&+6aoFmIz;E|XU(#}bt zjFHu#TX-U#bn@UO+{X}+(5PEij<`b3=r`6RG|su$Dx@}l(YaYwddyFF^lI*+O|q## zstu$hF8v#rSwRpkVKcx_8X~9y3adV8U9$dKWRGQ`20}xZJej-CN$B$U`={%E&xXCY zcKT8i7jJHO1&6j&g>i&*oc|JMa>`>6MmTRb$3Y4`c;14|gf$_vVg*cVQD+IQ+2xVD zeK;QNpYvI|zjn{I2(?CMRgx<0M6X!pyYJb@`2=oWeD@nOw?<=~rktUD1gU`b!qVnG zG*C3Co20&C__5pQx?oFswW<2KqR~=W`IYBh-pnx;_E&JinQij% zHINB^yLt3ALUw=lQ8K#Uz;5up@}EI8xAvWrfzE3^_VfP2_e;grP4w728*J`WY381; zVJhTE-^1F1LZ`-lL~x;(F>qn{ibrJ8PitaIT96K?k6_4XtK2;g#%?}8ZcI=t3Wd~_ zf-21U2D;=mEmgkt@Uj4u;#GAje=X_pJv_;kn9_%*sF2~S&~6vFz>KS(&}+B405C35 zxI~e?P*wWECS&n*O$i3pCLON2{^Y=h|@_)O3p zFn0^%>C{{j2~!tAM0Pk4FmX4H%xnGauCGrakKS*-(D;ZEy|{ERhV0E2--tdtd?!>H`MUs-w#x9`PR%Ll zi)h=6TUtooN0{t`M%;2`mmwK+#F;k9PAl2$)X2$layt>ehe<4%|SlAv}_#L+!n z2vHgrxp?^~E>)c5LWoJ}LG#T<-dh`#WFXMWx$mLQw~lU-^dcIgtd9$`ZwYi1FbDrG zyL6D{ML9ICd}KJD>j<9IPYnE;Q8Vu!3!8T7-q-pm=2ddRhE%MQ>^rKbqJ8fk?46~Z zoXL$BBM3IK6RGQErZn>ArTnM1^j3Oe4)^D zqcwlxxbr~Os1owFC|>QV;G>(~8f8DCu$l1XA~@j^CJQ0jWlS5{Kc7c2{fUqW$D|2` zxS{L_7EhLKR76lmZyejh;@`BjCiPZU*;_|g9@ok>dCc96^GB0qz6@=}QM^%JM5pwY zQZ*QuJ~8HXp&IH=jp>nEvc5WHg&$oOKjU@dzS*&w5YZ=d?=IaBgWmvOFwc{w$)~W9 z++gyWCsrB7@wrQw%xL$(R?D|btdsVIc*Z)&y_s?$XG(O}E+lHo0IfFN5WelG! zSYHe80uxgS2`HPoNDopaxrgxSiXA^$z1J8*$S+@kbNf#PTM8%Z#8`ZL@oQ@5iM^7q zJlsG#i7k`)dcD})Qwbz6`xCE2^_V~-(O^zhs7u-((e$Ah-j`84QoJO9G9H zi*b$hQfv@hKgBZUhYj8&*CP2;!Bnx@IjL4^{CsHKzO9L*dwuL%8ZVK1EA%n-<}0yk zs{G?JL3wIwL)C{pVk?_t2RsJGbw462y9?|UOpQu**=i62d z5kdjZ{rmk7e!iwv1>R~J(D{Oo|Gn~%s~S+d1(C&ECcrjrmT^f-E!mmI8szX6&~abl zIUcxWWa$xjr_Fjw_AYb!FPFfM*okKhQO`|P?uS0eO$VBYb|ifQa!`E^v4R`O@(Z^l zI`xhOp8s@)*Y#$L(lbke2+6R>gYTE+81J*#LECsKR-hGC>k^@TF4H2qwXgE8+K6LC zBiWZ$>YoTbc$T4mK7;FTL4|;$SwoSv=+!tn;PgAIUH0Jxro|JW++C>3q3U&@GXAh^%tbuTC9s-aE40a`s_J zgR(B)a8Az9+uW}5H_%IXv88_X=GNAB-P9uf!)dm{bTuRB3aNbULEXtIpzN3ze>;LpqcsGOnZ4NM&Xj@_VjfX!c_jbMVI)-3_ zO>{<3`M;pORq7NRCTRk7aW5&VI~1M8rRIYgS^oM7*?YGdWdPkqbqRZOAOr!xmos6k zvA{y)+(9@jwM>Ty%QjM1hzFmwy2NKw>)#r!HS}`Ud2~5S1MjzIVQns3a(TKBOa{xg z^&*nWWXRHWkufOyssIGgT%)aiG&CF9 z$1Y=$i}=v^7`X+{F_t`HKsM+baMNg?)ZXS`d*Zv`Y%;^~@HV2P3qlg1uz)k^v;Pe^ C(3SE4 literal 0 HcmV?d00001 diff --git a/docs/figures/nys_logo.jpg b/docs/figures/nys_logo.jpg new file mode 100644 index 0000000000000000000000000000000000000000..4a033f5ffecaf0440d0b683bc911a86a8588f835 GIT binary patch literal 14902 zcmbWd2UJr})GrzYMT#KOq~ zfQZ!4Lqbt{LJ0vv^5XY>@4kEQTJNs+zB!q-&dHgXGkfpZGkgE`rp!>50ap!l^>qO> zG&F!G)C)kt0EBdc+*|+vBO`z$006j5eRmB&OTD9^UjI=j^MHGR3p6x;fB#izFVg-k zm+0tdFVbJ4r~g|oGcYk+zRY-;o}TdvBO?zV+E(72+nzS@RfD3Fiv}`n#UI36f*Naq&{u1?Hh2{b+-Nj4PDKRop8`NK= zPM?FB7f!>R89bZi%|-H_A1#BTDGUdV?-{&mXd%fff7yEsk9a3TuNd?Ohc zxwxjH_YV$_2*<>e)4z1l0BHY{tp7pT|3()Zm97g^8PL)HrHkf5Ahpu6 z(OtYDcj=n83H?(ab|LxKmpSgHe6H?d5LPh7aX#}MW8@OKjS#2 z3*M4;XWn!fYat z&`kkE#&5v|G(3>>6o4zb4$3=Sa-+Tj<&iuTKQ_&vCMkP%VgjlssA2_{&y%p7vWC5(MuEOhvzcty_(lgKVu>_AGo#}CBtv~I@LuHUz zJ?kGT9H5D%=}%m@Hzo|{M#3D9XJTB&rw&O(;7kvh!G9S&i!`dA*3k2UVkrQDTh~Uy z1M;2Qb7NBfNo@KqcJ6p#^O9$hiuk!VcfdA?BY>TX7XAhg|~owGjVPqO!yIMDiNHKX{KSO1;L zCsj^oB$Dv;9g~7w=OeXL=)oxA4OPrYVgZ#$y?lrma4jU-OT(h_#d8tV+~f%FlO4Bz z-eK<2QUKD$H^8&Pmyp`^iIM_=_gku)Os9|Ew_W?HGW1PSZxxC+Tw(1-#KCcTdx_ba zi0FtL)(f^<+25Kb{5+Lhm3b@6n#|8Un~hp+h5k`ivh}fhl5!lznz>x<@2*>8T9N9v z0{W_4IbSn9ZQ}_=4=)ED$PYaEGoC>&ZsJ*%7WvT4&6%%VHn0i-4L)x@qoV-2K?2+cxcp|2 z1LH@M9o1oe?LwOyR-v}t`_W>24Us;l7IC9^S5jOH{5-^v0{Fx`z$V6PnjWZ6)=htw zJ03oEAp42}SpKY*^clOQ;=dziSULm1 zn*6TfNn=O$q|Ta1LRceOsMxn{i5t10=uo$6QysOy~9jDOfK0zlL%BHJTk^O zj1-Z4wB*lIHMBAIx}I~H2@NC9chQO?jdQ}C#}X6g;~j62?}NnpNOQpf>I~Va7lozf z8N7+2ZrxX!w$nDm(XJ(P_s=KZHF4AOTk>`=W7=!RNtmz){6 zqXoT=;=@gQjO#p=R0{R#Wt8`%F5igVNVYiuaz-rW%ZzE*m$~8Gw1BDVpxMfTn-cNg z^m%l>&mXE=BooDeq=bA)3IG9xoiiHX^BjADxLA^Z$J7JxbMgqPxMe@y^FYZ?!E@AO zrP9H3;Nzi+q2xfg@1s)7A`8{RsuiADdr^esPSZCHg-k<@ehj&)=(;Y8+%(Fkb!#fW z3xl3V4Dgn`t2=wFpU?5iz+X7BRH@L=Xv4uUJyba#A7lQKL z)YT108_B=emWaPx8IwqfEcezrRQqbhDP zqwq4Kh8S}PPxoADv75kt6&%ZQI6A4o+TBhXR{AO7ofvj-^QUXvYB|&J?EYif0F$~j zPh}PT!k-(Nf%Z8NHll&dL*9t$Fg?z;>sA^hew^5rT zGv#}))QE)rs}$-2OEy@go`;aRXU8jTr+vkxu8yvu#TC8-1k-uv#CY2Gz3;VYks&zX zJ0v#@BXXY6#{KD}wMrTx8n^cH=l4s(qt(}B&kuGiC;%rf0ofkeL?+P#KB#RD)4LMZ z{X=6#n0yq_M8}J}TCu57Hc_&zN&jwYseo$mW?yR~w8~2SXd>ezTI*sFb27(ors;%Y z>=9B*pw1y6Tn!;St))tyR~zWri?cdqi7(m+e82JYeOuP0yZb}t*9zPKPjUk{9A;O% zu0rR4-Dj1?MiZ4@iu0k`J_O}}{n^folWc5?*^5n5ok4D4w^Rn|J z+cpZoUq3zSNL_CQ5{B*Q>CW9#!5Tcybd2lOH_cs;5Ggoo=WFwuDiXIjo`SyYT6ut^ zNgrj1F3?x)mo!5!%|70mD)mI)>x8+C&fi?Yq7o>8Z%13wVB_YNg!c4?A6?GQtNr)b z4?I_2{=DKIF$t;nfYbT&X@d0YYmrkW38N}aF8ezLf0`M!r3N&dp0N5j2%lMyq?(94 z_{e#Ov8l?#bAx5bY>T&a6=#%2L=X6uV1l0e2+?Z!Y;Ue$>I8a`r&6P&9ny<)#F#L*LS8G}Vw{ zdm&emn3;*jA$u!pwUWlbZowLwI6+jupnP?dant1W^S494(nPWF=2z%I?~BbUOi^gg zmD6Mr2YugMJqbRmb}5S=l*yK!xqhdk!u<8AIS}_q^Ko)-CAWU^ae&Q>4}#)ZZ!80! zc&mj^nmGJEyFp|b?n2Vm*}i+4-~heKG+)|~xSzGAt?A7TVD$<)6<@bA%Et>lyxzI8 z$QyKDRIRP_XW@8U8q{cYG1X0^YIjr`BcISHndB4OBbka28)mA%-nUqUa;o=K4jdDF ziOV4~0$Td(uO!Fcp7+!O#jwS1>3Ycs1)Yr5+!^(Ls0o^)0G^K~OoXu$U$iXd;6*MeRf~Z}>dy~rY(6>?&hR6nA2rmp-c958 z&!mf;6JT}oL=tr3ucb7vi^ev-!~8nR)6xW)w~Wpfy}e5~X1)~ga;Sl(-S7EM37k>An>y+Nkg*RsKt0fcO z#K8lmIiLN8Yj-D`>VzfT8#p;<)_rV~>4Z1y9nCDF=UCuYi?gzF8&og%t@q5<{4xAi zeki@#JD+`~Ki!Klwti$6?Il*QM1F9Lo`Vt^raKtJ?k4L@_>IVH%GQVu5Bl2Ga!K8~ z@Sc8gYa}Eo2k$bDUY>#{C`JiH*JUzSXTmdJwabu8I=IXv}2m-64Ma}ll%hn!UdIoN3iym#>1#QSJNjv)5?Ww$#DgXLu z;rT>BO_pNjpq6!|b5-k$v9+f}AnOO`8HPtOpv-y^M5yh7mk#+pAvqe>08Y@7AsN?? z9gecNUHBQy^xZ*UdHxQo%r1*O{q_05f2_tc*3dQZE)e()jP(ZGzkRy0Qa4N4N={%% zo9F&mYgyE!zX;smi1)msgPC6L*=D527tS{B$7>4@p4cOyIAP057LHyj3p+ zz_4*V=A>C@1%o!<`!jY|VDkJ9LZXpsV(pNBptuuRNn%#9jo>!VYq%Q&pZCvDmG^G^ zD8HAVDd=lI>4aJhKC1QLl<=J_=QvZ9J<#g>(qVyPC2`dfpv2b!zx43DX#EVxGYSA| zZ8s~Gk6FC1vXBDNC211#FvxfZ!DLHZM|%M=-tax<#o>I@?&ndv7kBSy9BQDnWI_E; zVM}fXKx{lDTd`*aHEVuh;yGLJT&)Fvlt%JuHo2?kg&lu2 z15o^q5?a>fwZ*0;cH;rMQxQ+0`M}zG3Lxt3=lB7x9?Qnb9pM(-2K>X0lkL?fH$nuG zIhI*|cD2O82}xAS;iL!W^;$O_!X(bK4#Uj`lVCTG`%)ryemrgXDD0~=f9JkRM$$3u z8m-1D{dNWgK$nR>eoXx)qnWe0IB~?!(O*?EHVmn&^4x zo=mH}Qyov|+EFC(nx!U8!ga$$&#r$>BgEnMzb#Z`0iu2-*AALSOu^`Emr=b|(ECGw zLb}|x-vOocRD)p4BCD_(y`peA+$cc_inj($)sFvxH2K2&rw zZz}gGH`mUWEYP95Y*8|*+Tq62g8Ux7m~}rpj+@!F0m zucQDDB|zV82%`_rzZ5o2@``?o>h%&G%n1A^!7g?FEsL%~KWKX|k^-pBkHX1d$(}-< zx^DHH|7KJbvA!yN4`7s=L;))!y7F03{^i3Pi2Akc(_k49Chynx)VWkn)SM<=1Uc~> zOTph)^^V(*5lgi4?s-)A5BN9Ka?dI*g7JaB ztv8o|wRvwx<@pr&o)Erk_o);5a6$OSP5}!nMBY=@rGUY~mwnHX46teLqOO-?oC79j z@2a4$-kcen-ISy(ku`rSiaYWxvv&Pen$E_Vqp@9eql_159+S%dg(|h-7`J zDG$Xbu)h9S7v#krUGe#-)VxGIbk4U+9~?4g|Ij8F1po9*L$9-KF3~+~sqe0V4K(;R zp`&395~^WKWltA3N?3lPjkhdYr)W{+xK!5>jfV9@$pkF;K1d?p6vW?xP{HKE0}L92JjV z9lc21c4COUSm4z^9U@6eP}NUL>`nZ7Le+kwXI&pykD-OMm zL=crtTHU1f6e|^ZYM$v&|0~!Nl6I2jpybn~p_hSIbP&P7T+QaoALi*!x7b%A0y#m8 zw|6Th)N%aU8IJProK**Ihv&38bHKxo|LoKn*_JND>mmJ2utYTbN{;^HqKP`9PR2*^ zdkfXi3@>gS$N^Z|SZ$7gbHFZzFtzhIl0w0P%zU|R>q`~#c0x@nYiBhuIwY$bJqw~L z2BW|A5tFTL;yu$h>!6$sjp;Y1UtVzl!<<4;MtCobOcoyA4VyV_wHN*R@dan)>dfZW z`@h0Su*%6ILh>fNU7C~JR1EnN-h3(GI(e4!aAbZ+!pm7;aj^xj;hfdo!Ne4mkO^cJ zy*YQBSJ&R**IXHyYI;HR&;}i>iBE0M%g*_>se;5gOw3$~$D0#$I__ z6#oL z>yNhYU%%c7V73xNkbAY5P;K@~)veYw+1Qu9V>S!#Rvs&~g7#C}4!TwvKtG1VM1R%< zX1dIp7FV0UDAySp%l6G|Y#=3Pw8B8P0znNs)qOe@c98S+*GTF^yK@hY@Uw7ib`=y+M~7I4WSaZ`22VFT|< zFvgAc8?)UjbI;;!3-q~@**m{*ktIG=o-sdI0~LxHWqM46bQ3}}TWYOm<}1sjN`jqC z8n0{(*c>6TS5ZF{!se=;fBA~_FA>=jA38Rz�_Lna|DU!nUR~Waw#`1y25K+@4Ca zthGAWn4LY;f}X!cJ_pz810(%ok%2d)3xDkVI=aPvl0l-LG=>hcvfIMTaN>Pf-9Kq| zwe!mP@4Eunggkcn9xe{iY>aYl|7qor6{F=*JkIBFw$sj7gU^24lWI?^SJkx}>8Wk8 zTszbB7_VtSD)bQ-YIzb)*KPerD<&-KS}Q}24p3F`IviFT^n=k6|5BkC_YQet4wjq5 z0qO=`^kAgrmbzKix?344+=IT@uUji>nfvZEn)$Bm$JG~fDK>@w&PK6M-tO*euVZ;XBr1Y-of0r(r%CW$+EbbU^VUiP$*GqjJFBMu1)-z-H?cbb#)jV&U*||0LL>=(3N`s zVUKVo$0C<=f%NMWM_iLDjkrUl)b9i9anEb{Qv@l1R)42c@g0bcm6m6oOLgC5i50uj z%FT|O4FR+2vUhQ+E;PRqFuD@@Vl|;vdoS0G1z=tL6oAW~;LJN0BBWrWs*KHbd_BA0 zf_6z6aDHEL9~F;Wj)PwZyC7rd5-EV~3B0K>GcmB&PuryeGmXmCSa1r%Z%*c1gBT21{M(To5?w{|Q+nCal4YR>pCGK`?7JZdd8k`3J9Zf|GmkmU z=fmAhp9{~MT;JRcUU%C?ICt9b-(ScDP@_#OubfcDCOTpL!fcl9dNy^rg~y(Ywdexf zJYM$<@vnUznXyzj+d4b?KXC0w!5lRBX{yz7@$r<#OFUn%4X_(b-C~GEju`bcx38Pi zjS^7ky2Oo4&7t`ki-zA9UwyycRkZ|}hxKPSZXXl{jcOCwSI+fp+NRdV_cWBf2i-!S z2(z{HQYNdE!-j^CRB5n|3`v~C2Y*`LEnhJ{;8oG4kyqnw_(cRE?A);AvC zN*ZGMwIL)2aI*RZ!#!l3FFPZQ<6Pfi@bodLo(Nf-{r-$Qp_=QKg3`A9rIYl?q>6-x zj7R^V7F<;LnQv`zzAj-*FBlFSl?k_~R9UpypY0zQUdCIOTAX%B`o38Um9gI6K(uV{ zIWO$P8DL!y4WE@gzO5ymUsTT$%n6KPYdjX;7yv-Br zgq)4Khd+)DlZCO=R^>bw!p$!h2FlqPz?uZCUhF&q zK~8qxrvT>92)Q_5FPbQUh$ewo7LC3TU2%E#^_R!z3=5HyJhW{(SJ@Lzmo{q=@Z-?zD0Uq!;Vys<6YVD2OrIcFVbEoM^$2{H9foHRAkFaMJ{Xpg?P zlgvV%H4A%qo+PCOBC>a7Hzvp`UN$MftrZPP&ke7?D}L8}@g)zl{=kiwOKtqHE(el# zgcJqPO$|RVZ(#R`4?0E&Jp~kihYsO0i^96&aR0)~=_XmC5PXN}bI{8bQz=~rOC8d{LO^$d*vB?2ehqyToBDky+z+y^@cu`3QS z@^3^MB%6fnAZ& zV3wmw7>1?Y6)OuwFS>1EHjY$QT55vwEHxUs`9_wCbT7$+YR~hi4jVES!cCU2eI9X> z$bj7gY$#|;Au7=5KB=oU%w?PwbXgkAR--VS{Rb}@4ILbprrLAQBOVQX`8gxW-6V;4 z+sm^t{#PRPyg{4Ev+-SUzBcJf_x&&{d`T3^%<;BdRUTJjkz&sLcb>-DwBy(IpICZ% zm;0W2-x_kmt~_M)S3OSOtpv$f1mtBM1Z?{MLd0c0)lkpPeL7qdU7v_ns6Prv(w3cn zK|Y5tlZW99{<1tl4ZDW+Vn&Ru&x{W2h6WfopefBWxJ!37^#RwkEYiq~N7yZ6TG^y3 zq^lQD8;9vkJM-G{$-J8OS~=@mSPVEcVB&oDD2>Xja|NmpV~GJb7th~@Spf;j_D%av z^Kc^TM~G`sWtdh3!=|C^%xE-K9HOif+v}s>RSC0ep?FZ!3P7oa9p`L!O|-a9LzVPW(M=W+NsKS?iTp5eCLeRKA<$ zGmBo1oO{;PEc`_Df)aU_69<2lI6zXF$6lfU)X$X3?B6^3kZrI(t<@C3g`eREkidw} zj!VRo5+Ve%RDd-W2og3SzE}b_KCg>668JL7#Z?EXEzK!j6;&2IGp-Efd29Hp6H_+W zFQ4xIP~xZA!y!30Q33vp(^qiBUiTpB*# zt#psexZbS4o!SZ$F)~Pb6I{IAT07yIuWl`YMgCr@;lhB}vbs`Pr1ToKB! zu1+Lhy(}}4<-nZib*A~p^hCL_<^s|Kc!;l#nG=gBf5A7L@T6HR?NsxO%GNIR2R^$kZ5mCozoO-&&EkkmVb=cOyKm#7=| zW&boQv3Lp>E2{& zX?v`Q%+aHEBTv#zVlDn2LEyZDq>2k1h)|l05GIOYIh(^-%_b-Lw)7*s%OD7rXdeB4 zVsx*sS}i$#YmRm|>$d3CnKb#G&fzg_d1uECZ4expTD z>+_tj(sr3ttw%wl8?>sZ+4~p;4E^xPbTmIF0fImi6=vK1_U{shr-|%qRY6#8}ri^DNOrE!q zRf8;7R+M{h`#f3gbGmttBl(8& zLFybq_3>e8Yx+YwLv8V``63&g<%VZh=MX!aXaO)rq~*-)IeHd2gLZ;|_>_Y4Uu+-# z=7aGPBlmicoDo!WP|MG2PT2VTlSYV!_U&6}<3jhWXW0I|@X_=e|Ay^)VY}$P=}SyD zV0ErLYj|}m`b`84kqJW@3o;yl@ZK&DH#VKjkoP0P*KSHhn&>}vT8!+v3h;etw5A&G zp27UDGv}y*QMvEevx$eBJN`zHnr~7)^c9<9K51)TGxmO;eI=d3#aS^!Z{W5 z!8Gbci6r-P=d-rp?6(`IQCtL&->C3O=>3JQy3&NJ!Rw_Y#`8oiagsE#ya>AV&-oV( z=M_)E-tRAN8!jqc|J1(7C-m0&neOzH1(q^UC(_;c6@(A`#Ouut-mn`cKy7S^+padM za&x#L1U3Braf)Y(LFLg88b}*Q>UFjeFQT~djt>?Q3ugqooZEJ3Nub);UGX-5Zhk(` z@L3z`aGm{Cg&7X^6#1}vK~GV|j!V9t*ZP5C(8GjWY)<5{eQsgthE=^hd^0EkpSHJ&f$ze~1VyBsQOmm>AHY9HQH?<>T*B{2VKPV^j6L{I~wFMmjb- zG>M}YL*MH)Gtn7h99IWVhI1;qQL|pOOZW`qDF7Kh>$S&4Cye~0)(fvEID;LSxOL5O zGalyV?q|Q+_>77t+zezh%DsvXYn@iARYI!s+$VvGnxbyDM!ZwtVD%j$@Nw7^>Z#~U zv>Jd^o5SeB)Wct5q%SREQbE0M?0?#e9z0%MunKK;s&(>T0nj*%;R-t4a0m=6Mngeh zcxeE$Bab$+jk%Mk@>VoK)udDGg}0hZhaRyN$J&ps-rI)Zp?x@#2QdXZVqnY+|CVR^ z2i9BlXmiO=#HoBaWAroP{&@^_+llH&D@R| z718a?gmixjyd0+`kIxuQYBN%fmm-;P7OM3uRky`)W&e<8P>UAQ1LA}o)~GU^J#SO= zN(R?@#c6=B^IKoZqC_#h%-=iQKIFwC`5lH+3sfIRKFkkH+9$V~`JECa@d)U3LkHO}2kYp&8#8D~9*aZ<)qH zWrO+&*GXq4)lQq21Y*V#L*FKzfr%4@(({an>qIn}+p5>=GJ2jU!yxN8UUkRb)HnZW zzNzBPM_(nLSrd=&#t+l<@k};KIaDa@qnAIw;DZm(2Eba_!Vs%a+!g_j=iU}O zdmeOv+3VZmgz}r#~mj2fQ^xq7!|{HRbF*GMw(1uNG#d zM)rL-b84;Xrz;&!{hGf1b~oRcE;s6D4=}2mZgrT4c$w|-f>zK((Y-jbFnK(CG=Y3O zXuxiIha`tBFR83FKAm5|5A#n3oFQLYMSmD>XBCu z5i2;*)ZmhM_PlKHc0Ove1)PteA`T3boF}wYlTw`M`iVrv529X?S&8cX0mykl&dJ;A z)>RcQc?Gd6K+p7I^T@KFan=`<9WNmv0jNnaIY4$R_M**kXZ~w&v_( z2+qANesV?vhm6}B84(tft%;rce01KR4WhC9=g5A8px7pfyFRA+ja<`7!}c1<%8ETd z>p6L$AB*$g<}E-ok``_+ip&wDJ9-D#hlptde{tJbo44NB;%sjdK2Nt}2}zsGH}as` z!1^Vy(etcx3IKvf{GduE$~KGxdGI*m1{HyjMi9+nNW5#yh*K%}Rq8akP$W?CV+S3v z5vi^Q3SeUrc_J(tJ0R*D10nKK0K$jIy0&%HsD`d!jJw-edBk}Gn z*8%q*Yu$kT9o(F{m0ao|O2gKx!|qZ5owg8MDS7Za?2jh({& z!zQDa`^(Pe!*p?jX(Vl1!MD+AtG;2?16#ih^dp?whLw^K^d%Yh(fi?5zk66%Ppz*0|QKn0s&*Z{}y<*{)sa%K)vXFx?xYTmAPDviTMyQl<$1(E zNx&oM*O|VTYg7oW{UMmKewpe^J%_RSA-?@l)5`i{{X1}WTiSF<<8reAavoP_6c|PO}Gf`!+*t-OUJRo|n>^I|Ab`2=%9Pzt@4=6u_C} zb8!7Ai6fMdI_^Ib+83hPkyCCY!OQa1BYP!$xK!Vp%ntx8)BIvQh3n!3V=#+UTi<-*(EjFt=@iS> zd~4`^Y(DPjN75&%$J-fOp1l;~jJ3as?J=#bpOkv>en7MShoO{$#AZds<)_;^PZO|l zQ`H>BIp&ycwCLdrhKPWc4%F?QRlg0BT)&rD%I%)v>l6S8o==UjyOOT`#vpcR&!kAo z_^fyY$rTY^GrE&lU{r}D7~IO}pNzgES;GISM^&rdk<9qCVB}0PVirvop?vSlh}dfl z5aXZhteK}n8`V)lU*}Xz)*hVE13nP&DG=Bnn=8rDhwr=`JSq#1|8Q)w&&@JUUXrqcxEjnyj60h zwA#;s2XFO7V{QI*aW(z)_8(7%-Ekm*rbX(J z&5~kOusMlKoPGcO&eKJ0#Dwf+5)DrFm105ZbB8Oqs^qU!l(lfy?UDAaQ9Jps!m2yA zf}&KRt*FQI)F*Q5PZdpw9&9h|kE_m&Khz2uzF^YCpCEYAZ@DS$N~GWCHzhLnhfKr9 zA3l6219D2$2Y*Zw6RnIh%M^lU>+3vL7bz?}4)i3`ufux0-l(yX*vrX`DFrhm-7~#d z4R!2y4dlh3a@!WSqVW>PI^kM@oF2J%)wEt8`4U^R+a1YFN0NPKNiD{-ge>hD(GyRvY0(Y$?ldDVrANjz@G&xD0PZ&Y(1N9o%T+`{t&+xbwXB?O=h zSHrd3)P%+9?DDyd=^VCn-On_Q^YbbEJ`W zA&y7^5U8_=d{2@f>Qgt1q2%t<<9DAY+MZ(CZ&Cmc!dad#zSwmQ{Ls(lGuGBem+N_> zHoZ1a{6BfW>mAdtLz6LE8crB0W+ja?FYoGc^>TiSJkJO(Vj^&GEOQ`wi4=C%~5P0_yaB;fg{4gnc77g4>- zGQeh=t$1y!F01bH+GIF2zx8n~`st{-&AA|+`^_PO`;V_%cEiV#&1{cO25Fg{@gV*S zmxpdidfyRFk~6dUlNq3<5fY{p@NEO%NAPR7pYilQKJhi6)6OTsk#l1>etm66RncEm z74&CCBrR&92L0PH)_dD?aOBIIXK-`uyy@A}z$&6!{|gXz2mJ0qjaX)f=+mZK1EjFo zV+0cB$ZbhwwqMZ2*B4f7$I;86F*#BoX0pj)EjB| zFZWYbz-rPb%Z9u!vm3k*)WVC3Dk~G)o?Wl}9BX?07xP7PS{k2zK%cM6f;O|0=;f{| z_p0J^UW28U7kx^; zBY+dG=O4rP%8k9~3DJny)N#H{?0szJTtEuVp(F1#%|}*?TGwz7Mi1MlI)FT^XPiEA11M!fC~??5Ii|EdmXvD}~=bcn_J=d&%4Mo%!!7Hr5O- zjk&6;iYC;=H!5TxD)Td&*3t*p;E#N**6MdkD&rsw8mdn*tkE3;bZ1}X7^&m>o9R*=_jh&6Ie(r?@>$aDF3__ zu=Nu9l8K5g{yM#-deQiwNLHcG#1R~{2Uf@0qiNeMC_Qmws!qV2{mMuiJi8{pY_n7T z+v?TJh#~l#A%TfVjrP#RqS{pPh8S>s8w5Mbuo3b(&2qv(UOKTud)_;xTK`!}V1fQx z)kIx>Gtet*fGKBLd@ZeXd&|sswdL4#q%!ABW^?E?q#-O{%{rlx$Ldys>V~<=dhN7E zi^HM?+_(#fn6&x{s}3Y_vSJ`Rjc!+}qRL^8L0< zjD71LEW!*Hzk0j+4GS#ES@{FwPksD+Zco`BH<~({ps@)c z@6Gb|*k_k6^W1DeE+dpsR#YF_I1c1eqY+=yy?gcLTICPv8>bhUjlU_{k}q$RZ=51X z>}i;mjRQTgnVl-nT?>{6X7Qy7aZ52`U|r6`MJ|}A?X-#ar{W+jlC#V6dOM)IM;QJg+2$-C_)~Iab9_kQvgG9IxDn|Q(t0>l=I53nP&m&y z9p|^{VlAO&7T4O?1M*7`K($QbU_{B^JD`>1BzRq54+Rh%A%L$>eoJN#Go84-6)$Zt zv#x2X-ps??C<+T+qpb^uiEG++XvLl9N2roVV7LdsC@uQl)6tg|A4l$ zThve7S(}exOHK#my;@C6jS%@87g>%0a(1W~x|W6AMM-IJW2`--N9yMnWeWTiOA~Ew z$I^Pna@qphgx!8}93lMS1jua0=b|j%LZB5>8I&&i^JM3N@8P~9VNF4 z(uc1YOB9&;b10@i*H)JBOD`&GuM6E8^9cKSt=N@c=fTgy8%D!Ak`r#anvT~A9pzqD z&ATC4ByKZ;|F-}O{LNZz;~lAyshPpWK|C$+?&zqN_nxRPE$`N@SH{k_it zq=-?k=IY&_8S8?w)K&c|qECxv%C#DY=v2`#StX^|UE!Tu;)_)CJoqpewP~htSWX5I zOQ}fx+*uv9y#xJt1Pw{m?6r@VQ?~nkaGR?feM<8N-4mAI?XEGHijFto?RHY11&=nx z`(X3m>_$$mW1HgTD$b*&%$;Q>C7Sg~>nElMYWI=Lb+GG5m%L}5pp}@e>Bjc91Uomh zvuyFTlCMAV-R~C^o4huAuM6Fv8u!$s;As?rh^LROn<4Ri4RZ0iGT-Anp@?17mjC|a zbKph$Dy6ij+=TooEQEzB9x51!%iLnBAUP9Dv0l9HrUDb%&Y-gDLuGdE_sPc=pdG|3 zDwq-pqq=t&Sy_pEJ%kXJ{2wAYL&GEfH|07WU(ZTupUL&R&TkddYhA^ATKkqUOEJ(Z zL}M%xWhe(tU?V6pZIu{)Y-7UCAjiMA(I1l~5$i3o{E_+Nt^|9kM` z|NP8}GbVAdk{M?4frL$JzDMMISIg3?4)(Dfk)+=bClMlz)-tmv&2wM7AN1c10M)JR z@ltaG4{LI#8|-7P+ccXqcKrRzs(U^>XGx-{rqrCUnaR@k?h@9eH>Olrz=e>nl}drk6-NJHCz0i cKGaAbH>|PL*5R;pd9B0oi01!L=_#}S7s)=?{r~^~ literal 0 HcmV?d00001 diff --git a/docs/index.rst b/docs/index.rst index e1eb68e..6c5ae65 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -10,6 +10,7 @@ Welcome to abb_robot_client's documentation! :maxdepth: 2 :caption: Contents: + readme abb_robot_client/api_reference Indices and tables From 6225f5341146c64ef95f5d096d26c56c0f64d307 Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 16:36:08 -0500 Subject: [PATCH 4/6] Add readthedocs.yaml --- .readthedocs.yaml | 13 +++++++++++++ docs/requirements.txt | 9 +++++++++ 2 files changed, 22 insertions(+) create mode 100644 .readthedocs.yaml create mode 100644 docs/requirements.txt diff --git a/.readthedocs.yaml b/.readthedocs.yaml new file mode 100644 index 0000000..b16f4eb --- /dev/null +++ b/.readthedocs.yaml @@ -0,0 +1,13 @@ +version: 2 + +sphinx: + configuration: doc/conf.py + +build: + os: ubuntu-22.04 + tools: + python: "3.10" + +python: + install: + - requirements: doc/requirements.txt \ No newline at end of file diff --git a/docs/requirements.txt b/docs/requirements.txt new file mode 100644 index 0000000..d6e3782 --- /dev/null +++ b/docs/requirements.txt @@ -0,0 +1,9 @@ +sphinx_autodoc_typehints +recommonmark +setuptools +requests +numpy +protobuf +websocket-client +httpx +websockets From 725b47ac2d36306d221d46a1d1211f0865d9ca8b Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 16:37:19 -0500 Subject: [PATCH 5/6] Add readthedocs.yaml --- .readthedocs.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index b16f4eb..d59d694 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -10,4 +10,4 @@ build: python: install: - - requirements: doc/requirements.txt \ No newline at end of file + - requirements: docs/requirements.txt \ No newline at end of file From 561451482de22888589a28077bd69837aa4ec19d Mon Sep 17 00:00:00 2001 From: John Wason Date: Tue, 27 Dec 2022 16:38:26 -0500 Subject: [PATCH 6/6] Add readthedocs.yaml --- .readthedocs.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.readthedocs.yaml b/.readthedocs.yaml index d59d694..0fc2426 100644 --- a/.readthedocs.yaml +++ b/.readthedocs.yaml @@ -1,7 +1,7 @@ version: 2 sphinx: - configuration: doc/conf.py + configuration: docs/conf.py build: os: ubuntu-22.04