class Box(GenericWithPose): _ABSTRACT = False def test(self, *, an: Optional[str] = None) -> None: """Run test. :return: """ pass def action_with_unknown_parameter_type(self, param: ActionMetadata, *, an: Optional[str] = None) -> bool: """Pointless action. :param param: :return: """ return True test.__action__ = ActionMetadata() # type: ignore action_with_unknown_parameter_type.__action__ = ActionMetadata( ) # type: ignore
class TestObject(GenericWithPose): """TestObject description.""" _ABSTRACT = False def action_1(self, param1: str, param2: int, param3: bool = False, *, an: Optional[str] = None) -> None: """Short description. :param param1: str param :param param2: int param :param param3: bool param :return: """ assert 0 <= param2 <= 100 def action_1_cancel(self, *, an: Optional[str] = None) -> None: pass def action_2(self, *, an: Optional[str] = None) -> bool: """ Short description :return: """ def action_3(self, *, an: Optional[str] = None) -> None: pass action_1.__action__ = ActionMetadata(blocking=True) # type: ignore action_2.__action__ = ActionMetadata() # type: ignore
class BarcodeService(Service): """ REST interface to the barcode service. """ def __init__(self, configuration_id: str): super(BarcodeService, self).__init__(configuration_id) systems.create(URL, self) @staticmethod def get_configuration_ids() -> FrozenSet[str]: return systems.systems(URL) @action def active_scanners(self) -> List[str]: """ Gets scanners ids. :return: """ return rest.get_list_primitive(f"{URL}/scanners", str) @action def scan(self, scanner_id: str) -> str: """ Gets scan. :param scanner_id: :return: """ return rest.get_primitive(f"{URL}/scanners/{scanner_id}/scan", str) active_scanners.__action__ = ActionMetadata(free=True, blocking=True) scan.__action__ = ActionMetadata(free=True, blocking=True)
class LogicService(Service): """ Logic-related actions. """ def __init__( self, configuration_id: str): # TODO avoid need for configuration_id? super(LogicService, self).__init__(configuration_id) @staticmethod def get_configuration_ids() -> FrozenSet[str]: return frozenset({"default"}) @action def equals(self, val1: int, val2: int) -> bool: return val1 == val2 @action def less_than(self, val1: int, val2: int) -> bool: return val1 < val2 @action def greater_than(self, val1: int, val2: int) -> bool: return val1 > val2 equals.__action__ = ActionMetadata(blocking=True) # type: ignore less_than.__action__ = ActionMetadata(blocking=True) # type: ignore greater_than.__action__ = ActionMetadata(blocking=True) # type: ignore
class ObjectWithActions(Generic): """Object with actions that even return something.""" _ABSTRACT = False def __init__(self, obj_id: str, name: str, settings: Optional[Settings] = None) -> None: super(ObjectWithActions, self).__init__(obj_id, name, settings) def _random_bool(self) -> bool: return random.choice([False, True]) def str_action(self, *, an: Optional[str] = None) -> str: return "Hello world." def bool_action(self, *, an: Optional[str] = None) -> bool: return self._random_bool() def tuple_action(self, *, an: Optional[str] = None) -> Tuple[bool, bool]: return self._random_bool(), self._random_bool() def enum_action(self, *, an: Optional[str] = None) -> MyEnum: return random.choice(list(MyEnum)) bool_action.__action__ = ActionMetadata() # type: ignore str_action.__action__ = ActionMetadata() # type: ignore tuple_action.__action__ = ActionMetadata() # type: ignore enum_action.__action__ = ActionMetadata() # type: ignore
class Generic(metaclass=abc.ABCMeta): """ Generic object """ DYNAMIC_PARAMS: DynamicParamDict = {} CANCEL_MAPPING: CancelDict = {} def __init__(self, obj_id: str, name: str, pose: Pose, collision_model: Optional[Models] = None) -> None: self.id = obj_id self.name = name self.pose = pose self.collision_model = copy.deepcopy(collision_model) if self.collision_model: # originally, each model has id == object type (e.g. BigBox) but here we need to set it so something unique self.collision_model.id = self.id self._int_dict: Dict[str, int] = {} @classmethod def description( cls) -> str: # TODO mixin with common stuff for objects/services? return parse_docstring(cls.__doc__)["short_description"] def scene_object(self) -> SceneObject: return SceneObject(self.id, self.name, self.__class__.__name__, self.pose) def __repr__(self) -> str: return str(self.__dict__) def cleanup(self) -> None: """ This method is called when a scene is closed or when script ends. :return: """ pass # TODO allow to store any value? @action def set_int(self, key: str, value: int) -> None: self._int_dict[key] = value @action def get_int(self, key: str) -> int: try: return self._int_dict[key] except KeyError: raise GenericException(f"Unknown key: {key}.") set_int.__action__ = ActionMetadata() # type: ignore get_int.__action__ = ActionMetadata() # type: ignore
class TimeService(Service): """ Time-related actions. """ def __init__( self, configuration_id: str): # TODO avoid need for configuration_id? super(TimeService, self).__init__(configuration_id) self._rate_start_time: Optional[float] = None @staticmethod def get_configuration_ids() -> FrozenSet[str]: return frozenset({"default"}) @action def sleep(self, seconds: float = 1.0) -> None: assert 0.0 <= seconds <= 10.0e6 time.sleep(seconds) @action def rate(self, period: float = 1.0) -> None: """ Can be used to maintain desired rate of the loop. Should be the first action. :param period: Desired period in seconds. :return: """ assert 0.0 <= period <= 10.0e6 now = time.monotonic() if self._rate_start_time is None: self._rate_start_time = now return dif = self._rate_start_time + period - now if dif > 0: time.sleep(dif) @action def time_ns(self) -> int: """ Returns nanoseconds since Unix Epoch. :return: """ return time.time_ns() sleep.__action__ = ActionMetadata(blocking=True) # type: ignore rate.__action__ = ActionMetadata(blocking=True) # type: ignore time_ns.__action__ = ActionMetadata(blocking=True) # type: ignore
class Box(Generic): @action def test(self) -> None: pass @action def action_with_unknown_parameter_type(self, param: ActionMetadata) -> bool: return True test.__action__ = ActionMetadata() # type: ignore action_with_unknown_parameter_type.__action__ = ActionMetadata( ) # type: ignore
class RandomActions(Generic): """Collection of actions to generate random values.""" _ABSTRACT = False def random_integer(self, range_min: int, range_max: int, *, an: Optional[str] = None) -> int: """Generates random integer in given range (including min/max values). :param range_min: Minimal value. :param range_max: Maximal value. :return: """ try: return random.randint(range_min, range_max) except ValueError as e: raise Arcor2Exception(str(e)) from e def random_double(self, range_min: float, range_max: float, *, an: Optional[str] = None) -> float: """Generates random double in given range. :param range_min: Minimal value. :param range_max: Maximal value. :return: """ try: return random.uniform(range_min, range_max) except ValueError as e: raise Arcor2Exception(str(e)) from e def random_bool(self, *, an: Optional[str] = None) -> bool: """Returns random boolean value. :return: """ return random.choice((False, True)) random_integer.__action__ = ActionMetadata(blocking=True) # type: ignore random_double.__action__ = ActionMetadata(blocking=True) # type: ignore random_bool.__action__ = ActionMetadata(blocking=True) # type: ignore
class TimeActions(Generic): """Time-related actions.""" _ABSTRACT = False def __init__(self, obj_id: str, name: str, settings: Optional[Settings] = None) -> None: super(TimeActions, self).__init__(obj_id, name, settings) self._last_time: Optional[float] = None def sleep(self, seconds: float = 1.0, *, an: Optional[str] = None) -> None: assert 0.0 <= seconds <= 10.0e6 time.sleep(seconds) def rate(self, period: float = 1.0, *, an: Optional[str] = None) -> None: """Can be used to maintain desired rate of the loop. Should be the first action. :param period: Desired period in seconds. :return: """ assert 0.0 <= period <= 10.0e6 now = time.monotonic() if self._last_time is not None: dif = self._last_time + period - now if dif > 0: time.sleep(dif) self._last_time = now def time_ns(self, *, an: Optional[str] = None) -> int: """Returns nanoseconds since Unix Epoch. :return: """ return time.time_ns() sleep.__action__ = ActionMetadata() # type: ignore rate.__action__ = ActionMetadata() # type: ignore time_ns.__action__ = ActionMetadata() # type: ignore
class ParamToReturn(Generic): _ABSTRACT = False def bool_param(self, param: bool, *, an: Optional[str] = None) -> bool: return param def int_param(self, param: int, *, an: Optional[str] = None) -> int: return param def double_param(self, param: float, *, an: Optional[str] = None) -> float: return param bool_param.__action__ = ActionMetadata(blocking=True) # type: ignore int_param.__action__ = ActionMetadata(blocking=True) # type: ignore double_param.__action__ = ActionMetadata(blocking=True) # type: ignore
class LogicActions(Generic): """Logic-related actions.""" _ABSTRACT = False def equals(self, val1: int, val2: int, *, an: Optional[str] = None) -> bool: """Tests if two integer values are equal. :param val1: :param val2: :return: """ return val1 == val2 def less_than(self, val1: int, val2: int, *, an: Optional[str] = None) -> bool: """Compares two integer values. :param val1: :param val2: :return: """ return val1 < val2 def greater_than(self, val1: int, val2: int, *, an: Optional[str] = None) -> bool: """Compares two integer values. :param val1: :param val2: :return: """ return val1 > val2 equals.__action__ = ActionMetadata(blocking=True) # type: ignore less_than.__action__ = ActionMetadata(blocking=True) # type: ignore greater_than.__action__ = ActionMetadata(blocking=True) # type: ignore
class Ict(AbstractWithPose): """REST interface to the ict service (0.4.0).""" _ABSTRACT = False # Init function because of parameter name "configurationId" # Should be removed after unifying of the patrameter name in all APIs def __init__( self, obj_id: str, name: str, pose: Pose, collision_model: Optional[Models] = None, settings: Optional[Settings] = None, ) -> None: super(AbstractWithPose, self).__init__(obj_id, name, pose, collision_model, settings) rest.call( rest.Method.PUT, f"{self.settings.url}/system/set", body=pose, params={"configurationId": self.settings.configuration_id, "id": self.id}, ) def test(self, serial_number: str, *, an: Optional[str] = None) -> bool: """Tests a PCB in an ICT tester. :return: """ return rest.call( rest.Method.GET, f"{self.settings.url}/tester/test", params={"serialNumber": serial_number}, return_type=bool, ) def ready(self, *, an: Optional[str] = None) -> bool: """Determines whether the ICT Tester is open and ready to start testing. :return: True if ICT tester is ready; otherwise, false. """ return rest.call(rest.Method.GET, f"{self.settings.url}/tester/ready", return_type=bool) test.__action__ = ActionMetadata(blocking=True) # type: ignore ready.__action__ = ActionMetadata(blocking=True) # type: ignore
class MyObject(Generic): def action(self, param: UnknownParameterType, *, an: Optional[str] = None) -> None: pass action.__action__ = ActionMetadata() # type: ignore
class KinectAzure(Camera): _ABSTRACT = False def __init__( self, obj_id: str, name: str, pose: Pose, collision_model: Optional[Models] = None, settings: Optional[Settings] = None, ) -> None: super(KinectAzure, self).__init__(obj_id, name, pose, collision_model, settings) if self._started(): self._stop() self._start() # TODO start with user-set parameters self.color_camera_params = rest.call( rest.Method.GET, f"{self.settings.url}/color/parameters", return_type=CameraParameters ) @property def settings(self) -> Settings: return cast(Settings, super(KinectAzure, self).settings) def _start(self) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/state/start") def _started(self) -> bool: return rest.call(rest.Method.GET, f"{self.settings.url}/state/started", return_type=bool) def _stop(self) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/state/stop") def color_image(self, *, an: Optional[str] = None) -> Image.Image: return rest.get_image(f"{self.settings.url}/color/image") def depth_image(self, averaged_frames: int = 1, *, an: Optional[str] = None) -> Image.Image: return Image.open( rest.call( rest.Method.GET, f"{self.settings.url}/depth/image", return_type=BytesIO, params={"averagedFrames": averaged_frames}, ) ) def sync_images(self) -> None: pass def cleanup(self) -> None: super(KinectAzure, self).cleanup() self._stop() color_image.__action__ = ActionMetadata(blocking=True) # type: ignore
class QL700(Generic): def __init__(self, obj_id: str, pose: Pose, collision_model: Optional[Models] = None) -> None: super(QL700, self).__init__(obj_id, pose, collision_model) self.qlr = BrotherQLRaster("QL-700") self.qlr.exception_on_warning = True @action def print(self, qr_text: str) -> None: qr = qrcode.make(qr_text) img = qr.get_image() img = img.resize((PX_WIDTH, PX_WIDTH)) status = send(instructions=convert(self.qlr, [img], "62", cut=False), printer_identifier="usb://0x04f9:0x2042", backend_identifier="pyusb", blocking=True) if False in (status["did_print"], status["ready_for_next_job"]): raise QL700Exception() @action def cut(self) -> None: # kind of hack (it is so far not possible to only perform cut) img = Image.new('RGB', (PX_WIDTH, 1), (255, 255, 255)) status = send(instructions=convert(self.qlr, [img], "62"), printer_identifier="usb://0x04f9:0x2042", backend_identifier="pyusb", blocking=True) if False in (status["did_print"], status["ready_for_next_job"]): raise QL700Exception() print.__action__ = ActionMetadata(free=True, blocking=True) cut.__action__ = ActionMetadata(free=True, blocking=True)
def test_object_actions() -> None: actions = object_actions(TestObject, parse_def(TestObject)) assert len(actions) == 2 for act in actions.values(): if act.name == TestObject.action_1.__name__: expected_meta = ActionMetadata(blocking=True) expected_meta.cancellable = True assert act.meta == expected_meta assert not act.returns assert act.description == "Short description." assert not act.disabled assert act.origins is None assert len(act.parameters) == 3 for param in act.parameters: if param.name == "param1": assert param.description == "str param" elif param.name == "param2": assert param.description == "int param" elif param.name == "param3": assert param.description == "bool param" else: pytest.fail( f"Unknown parameter: {param.name} of action {act.name}." ) elif act.name == TestObject.action_2.__name__: assert act.meta == ActionMetadata() assert len(act.returns) == 1 assert act.description == "Short description" assert not act.disabled assert act.origins is None assert not act.parameters else: pytest.fail(f"Unknown action: {act.name}.")
class MyObject(Generic): def inner_inner_action(self, *, an: Optional[str] = None) -> None: pass def inner_action(self, *, an: Optional[str] = None) -> None: self.inner_inner_action() def inner_action_2(self, *, an: Optional[str] = None) -> None: pass def action(self, *, an: Optional[str] = None) -> None: self.inner_action() self.inner_action_2() def action_wo_flag(self, *, an: Optional[str] = None) -> None: self.inner_action() self.inner_action_2() def action_with_inner_name_spec(self, *, an: Optional[str] = None) -> None: self.inner_action(an="whatever") inner_inner_action.__action__ = ActionMetadata() # type: ignore inner_action.__action__ = ActionMetadata( composite=True) # type: ignore inner_action_2.__action__ = ActionMetadata() # type: ignore action.__action__ = ActionMetadata(composite=True) # type: ignore action_wo_flag.__action__ = ActionMetadata() # type: ignore action_with_inner_name_spec.__action__ = ActionMetadata( ) # type: ignore
class Barcode(AbstractWithPose): """REST interface to the barcode service (0.3.0).""" _ABSTRACT = False def scan(self, *, an: Optional[str] = None) -> str: """Gets scan from active scanner. :return: """ return rest.call(rest.Method.GET, f"{self.settings.url}/scanner/scan", return_type=str) scan.__action__ = ActionMetadata(blocking=True) # type: ignore
class Interaction(AbstractSimple): """REST interface to the Interaction service (0.4.0).""" _ABSTRACT = False # --- Dialog Controller -------------------------------------------------------------------------------------------- def add_dialog(self, title: str, content: str, options: List[str], *, an: Optional[str] = None) -> str: """Creates dialog, block until operator selects one of the options. :param title: Dialog title :param content: Dialog content :param options: Dialog options. :return: """ return rest.call( rest.Method.PUT, f"{self.settings.url}/dialogs", return_type=str, params={ "title": title, "content": content }, body=options, timeout=rest.Timeout(read=8 * 60 * 60), ) def get_dialog(self, *, an: Optional[str] = None) -> DialogValue: """Returns active dialog (title and options) or error if no dialog is active. :return: """ return rest.call(rest.Method.GET, f"{self.settings.url}/dialogs", return_type=DialogValue) def resolve_dialog(self, id: str, option: str, *, an: Optional[str] = None) -> None: """Resolves current dialog using one of the options. :param id: :param option: :return: """ rest.call(rest.Method.PUT, f"{self.settings.url}/dialogs/resolve", params={ "id": id, "option": option }) # --- Notification Controller -------------------------------------------------------------------------------------- def add_notification(self, message: str, level: NotificationLevelEnum, *, an: Optional[str] = None) -> None: """Creates notification. :param message: :param level: :return: """ rest.call(rest.Method.PUT, f"{self.settings.url}/notification", params={ "message": message, "level": level }) def delete_notifications(self, *, an: Optional[str] = None) -> None: """Clears all notifications. :return: """ rest.call(rest.Method.DELETE, f"{self.settings.url}/notifications") def get_notifications(self, since_timestamp: int, *, an: Optional[str] = None) -> List[NotificationValue]: """Gets all notifications stored after given timestamp. :param since_timestamp: UNIX timestamp in nanoseconds, after which created notifications are returned. :return: """ return rest.call( rest.Method.GET, f"{self.settings.url}/notifications", list_return_type=NotificationValue, params={"sinceTimestamp": since_timestamp}, ) add_dialog.__action__ = ActionMetadata(blocking=True) # type: ignore get_dialog.__action__ = ActionMetadata(blocking=True) # type: ignore resolve_dialog.__action__ = ActionMetadata(blocking=True) # type: ignore add_notification.__action__ = ActionMetadata(blocking=True) # type: ignore delete_notifications.__action__ = ActionMetadata( blocking=True) # type: ignore get_notifications.__action__ = ActionMetadata( blocking=True) # type: ignore
class SearchService(Service): """ REST interface to the search service. """ def __init__(self, configuration_id: str): super(SearchService, self).__init__(configuration_id) systems.create(URL, self) @staticmethod def get_configuration_ids() -> FrozenSet[str]: return systems.systems(URL) @action def grab_image(self) -> None: """ Grabs image and stores to internal cache. :return: """ rest.put(f"{URL}/capture/grab") @action def get_image(self) -> Image: """ Gets RGB image from internal cache, if there is any. :return: """ return rest.get_image(f"{URL}/capture/image") @action def get_pose(self) -> Pose: """ Gets capture device pose in actual initialized spatial system space. :return: """ return rest.get(f"{URL}/capture/pose", Pose) def put_suction_configuration(self, item_id: str, tool_id: str, poses: List[Pose]) -> None: """ Adds or updates suction pick configuration. :param item_id: :param tool_id: :param poses: :return: """ rest.put(f"{URL}/pick/suctions", poses, {"item_id": item_id, "tool_id": tool_id}) @action def get_pick_poses_for_suction(self, item_id: str, tool_id: str, pose: Pose) -> List[Pose]: """ Gets pick poses for specific suction and item. :param item_id: :param tool_id: :param pose: :return: """ return rest.get_list(f"{URL}/pick/suctions/poses", Pose, pose, params={"item_id": item_id, "tool_id": tool_id}) def put_gripper_configuration(self, item_id: str, tool_id: str, gripper_setup: List[GripperSetup]) -> None: """ Adds or updates gripper definitions for tool and item. :param item_id: :param tool_id: :param gripper_setup: :return: """ rest.put(f"{URL}/pick/grippers", gripper_setup, {"item_id": item_id, "tool_id": tool_id}) def get_pick_poses_for_gripper(self, item_id: str, tool_id: str, pose: Pose) -> List[GripperSetup]: """ Gets pick poses for specific tool and item. :param item_id: :param tool_id: :param pose: :return: """ return rest.get_list(f"{URL}/pick/grippers/setup", GripperSetup, pose, {"item_id": item_id, "tool_id": tool_id}) @action def search(self) -> SearchOutput: """ Searches items based on search engine configuration and images stored in internal cache. :return: """ return rest.get(f"{URL}/search", SearchOutput) def set_search_parameters(self, parameters: SearchEngineParameters) -> None: """ Sets the search parameters. :param parameters: :return: """ rest.put(f"{URL}/search", parameters) @action def visualization(self) -> Image: """ Gets RGB visualization from last search run, if there is any. :return: """ return rest.get_image(f"{URL}/search/visualization") grab_image.__action__ = ActionMetadata(free=True, blocking=True) get_image.__action__ = ActionMetadata(free=True, blocking=True) get_pose.__action__ = ActionMetadata(free=True, blocking=True) get_pick_poses_for_suction.__action__ = ActionMetadata(free=True, blocking=True) search.__action__ = ActionMetadata(free=True, blocking=True) visualization.__action__ = ActionMetadata(free=True, blocking=True)
class Tester(CollisionObject): """A generic tester.""" _ABSTRACT = False def __init__(self, *args, **kwargs) -> None: super(Tester, self).__init__(*args, **kwargs) self._cancel: bool = False self._param1: str = "" def run_test(self, seq: list[float], seq_id: list[str], eqp_res: list[bool], *, an: Optional[str] = None) -> list[bool]: """Run test with many parameters. :param seq: :param seq_id: :param eqp_res: :return: """ return [bool(seq), bool(seq_id), bool(eqp_res)] def long_running_action(self, *, an: Optional[str] = None) -> None: """This runs for long time. :return: """ for _ in range(60): time.sleep(1) if self._cancel: self._cancel = False break def long_running_action_with_params(self, param1: str, *, an: Optional[str] = None) -> None: """Runs for long time. :param param1: :return: """ self._param1 = param1 for _ in range(60): time.sleep(1) if self._cancel: self._cancel = False break def simple_cancel(self, *, an: Optional[str] = None) -> None: self._cancel = True def cancel_with_param(self, param1: str, *, an: Optional[str] = None) -> None: assert param1 == self._param1 self._cancel = True run_test.__action__ = ActionMetadata() # type: ignore long_running_action.__action__ = ActionMetadata() # type: ignore long_running_action_with_params.__action__ = ActionMetadata( ) # type: ignore
class MyObject(Generic): def action(self, pose: Pose, *, an: Optional[str] = None) -> None: pass action.__action__ = ActionMetadata() # type: ignore
class InteractionService(Service): """ REST interface to the barcode service. """ def __init__(self, configuration_id: str): super(InteractionService, self).__init__(configuration_id) @staticmethod def get_configuration_ids() -> FrozenSet[str]: return frozenset({"default"}) @action def add_dialog(self, title: str, content: str, options: List[str]) -> None: """ Logs value with the specified group and name. :param title: :param content: :param options: :return: """ rest.put(f"{URL}/dialog", params={"title": title, "content": content}, data=options) @action def get_dialog(self) -> DialogValue: """ Gets names of all tracked values stored in given group. :return: """ try: return rest.get(f"{URL}/dialog", DialogValue) except rest.RestException: return None @action def add_dialog_resolve(self, option: str) -> None: """ Logs value with the specified group and name. :param option: :return: """ rest.put(f"{URL}/dialog/resolve", params={"option": option}) @action def add_notification(self, message: str, level: NotificationLevelEnum) -> None: """ Logs value with the specified group and name. :param message: :param level: :return: """ rest.put(f"{URL}/notification", params={"message": message, "level": level}) @action def delete_notifications(self) -> None: """ Deletes all tracked values stored in given group. :return: """ rest.delete(f"{URL}/notifications") @action def get_notifications(self, since_imestamp: int) -> List[NotificationValue]: """ Gets names of all tracked values stored in given group. :param since_imestamp: :return: """ return rest.get_list(f"{URL}/notifications", NotificationValue, params={"since_imestamp": since_imestamp}) add_dialog.__action__ = ActionMetadata(free=True, blocking=True) get_dialog.__action__ = ActionMetadata(free=True, blocking=True) add_dialog_resolve.__action__ = ActionMetadata(free=True, blocking=True) add_notification.__action__ = ActionMetadata(free=True, blocking=True) delete_notifications.__action__ = ActionMetadata(free=True, blocking=True) get_notifications.__action__ = ActionMetadata(free=True, blocking=True)
class AbstractDobot(FitCommonMixin, Robot): robot_type = RobotType.SCARA def __init__(self, obj_id: str, name: str, pose: Pose, settings: DobotSettings) -> None: super(AbstractDobot, self).__init__(obj_id, name, pose, settings) def _start(self, model: str) -> None: if self._started(): self._stop() rest.call( rest.Method.PUT, f"{self.settings.url}/state/start", params={ "model": model, "port": self.settings.port }, body=self.pose, ) @property def settings(self) -> DobotSettings: # type: ignore return cast(DobotSettings, super(AbstractDobot, self).settings) def cleanup(self): self._stop() def get_end_effectors_ids(self) -> Set[str]: return {"default"} def grippers(self) -> Set[str]: return set() def suctions(self) -> Set[str]: return {"default"} def get_end_effector_pose(self, end_effector_id: str) -> Pose: return rest.call(rest.Method.GET, f"{self.settings.url}/eef/pose", return_type=Pose) def move_to_pose(self, end_effector_id: str, target_pose: Pose, speed: float, safe: bool = True) -> None: if safe: raise DobotException("Dobot does not support safe moves.") self.move(target_pose, MoveType.LINEAR, speed * 100) def move_to_joints(self, target_joints: List[Joint], speed: float, safe: bool = True) -> None: if safe: raise DobotException("Dobot does not support safe moves.") self.move(self.forward_kinematics("", target_joints), MoveType.LINEAR, speed * 100) def home(self, *, an: Optional[str] = None) -> None: """Run the homing procedure.""" with self._move_lock: rest.call(rest.Method.PUT, f"{self.settings.url}/home") def move( self, pose: Pose, move_type: MoveType, velocity: float = 50.0, acceleration: float = 50.0, *, an: Optional[str] = None, ) -> None: """Moves the robot's end-effector to a specific pose. :param pose: Target pose. :move_type: Move type. :param velocity: Speed of move (percent). :param acceleration: Acceleration of move (percent). :return: """ assert 0.0 <= velocity <= 100.0 assert 0.0 <= acceleration <= 100.0 with self._move_lock: rest.call( rest.Method.PUT, f"{self.settings.url}/eef/pose", body=pose, params={ "move_type": move_type, "velocity": velocity, "acceleration": acceleration }, ) def suck(self, *, an: Optional[str] = None) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/suck") def release(self, *, an: Optional[str] = None) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/release") def pick(self, pick_pose: Pose, vertical_offset: float = 0.05, *, an: Optional[str] = None) -> None: """Picks an item from given pose. :param pick_pose: :param vertical_offset: :return: """ pick_pose.position.z += vertical_offset self.move(pick_pose, MoveType.JOINTS) # pre-pick pose pick_pose.position.z -= vertical_offset self.move(pick_pose, MoveType.JOINTS) # pick pose self.suck() pick_pose.position.z += vertical_offset self.move(pick_pose, MoveType.JOINTS) # pre-pick pose def place(self, place_pose: Pose, vertical_offset: float = 0.05, *, an: Optional[str] = None) -> None: """Places an item to a given pose. :param place_pose: :param vertical_offset: :return: """ place_pose.position.z += vertical_offset self.move(place_pose, MoveType.JOINTS) # pre-place pose place_pose.position.z -= vertical_offset self.move(place_pose, MoveType.JOINTS) # place pose self.release() place_pose.position.z += vertical_offset self.move(place_pose, MoveType.JOINTS) # pre-place pose def robot_joints(self) -> List[Joint]: return rest.call(rest.Method.GET, f"{self.settings.url}/joints", list_return_type=Joint) home.__action__ = ActionMetadata(blocking=True) # type: ignore move.__action__ = ActionMetadata(blocking=True) # type: ignore suck.__action__ = ActionMetadata(blocking=True) # type: ignore release.__action__ = ActionMetadata(blocking=True) # type: ignore pick.__action__ = ActionMetadata(blocking=True, composite=True) # type: ignore place.__action__ = ActionMetadata(blocking=True, composite=True) # type: ignore
class RestRobot(Robot): """ REST interface to the robot. """ def __init__(self, robot_api: RestRobotService, obj_id: str, obj_name: str, pose: Pose, collision_model: Optional[Models] = None) -> None: super(RestRobot, self).__init__(obj_id, obj_name, pose, collision_model) self.robot_api = robot_api def get_end_effectors_ids(self) -> FrozenSet[str]: return self.robot_api.get_end_effectors_ids(self.id) def get_end_effector_pose(self, end_effector_id: str) -> Pose: # global pose return self.robot_api.get_end_effector_pose(self.id, end_effector_id) @staticmethod def from_services(robot_api: RestRobotService) -> Iterator["RestRobot"]: # TODO what if robot does not support get_robot_pose? for robot_id in robot_api.get_robot_ids(): try: yield RestRobot(robot_api, robot_id, robot_id, robot_api.get_robot_pose(robot_id)) except Arcor2Exception as e: print(e) def stop(self) -> None: self.robot_api.stop(self.id) def robot_joints(self) -> List[Joint]: return self.robot_api.robot_joints(self.id) @action def move(self, end_effector_id: str, pose: Pose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector to a specific pose. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 self.robot_api.move(self.id, end_effector_id, pose, move_type, speed) @action def move_relative(self, end_effector_id: str, pose: Pose, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector to a specific pose. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 self.robot_api.move_relative(self.id, end_effector_id, pose, rel_pose, move_type, speed) @action def move_relative_joints(self, end_effector_id: str, joints: ProjectRobotJoints, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector relatively to specific joint values. :param end_effector_id: Unique end-effector id. :param joints: Target joints. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 self.robot_api.move_relative_joints(self.id, end_effector_id, joints, rel_pose, move_type, speed) @action def set_joints(self, joints: ProjectRobotJoints, move_type: MoveTypeEnum, speed: float = 0.5) -> None: assert 0.0 <= speed <= 1.0 assert self.id == joints.robot_id self.robot_api.set_joints(self.id, joints, move_type, speed) def inputs(self) -> FrozenSet[str]: return self.robot_api.inputs(self.id) def outputs(self) -> FrozenSet[str]: return self.robot_api.outputs(self.id) @action def get_input(self, input_id: str) -> float: return self.robot_api.get_input(self.id, input_id) @action def set_output(self, output_id: str, value: float) -> None: self.robot_api.set_output(self.id, output_id, value) @action def get_output(self, output_id: str) -> float: return self.robot_api.get_output(self.id, output_id) def focus(self, mfa: MeshFocusAction) -> Pose: return self.robot_api.focus(mfa) def grippers(self) -> FrozenSet[str]: return self.robot_api.grippers(self.id) @action def grip(self, gripper_id: str, position: float = 0.0, speed: float = 0.5, force: float = 0.5) -> None: assert 0.0 <= position <= 1.0 assert 0.0 <= speed <= 1.0 assert 0.0 <= force <= 1.0 return self.robot_api.grip(self.id, gripper_id, position, speed, force) @action def set_opening(self, gripper_id: str, position: float = 1.0, speed: float = 0.5) -> None: assert 0.0 <= position <= 1.0 assert 0.0 <= speed <= 1.0 self.robot_api.set_opening(self.id, gripper_id, position, speed) @action def get_gripper_opening(self, gripper_id: str) -> float: return self.robot_api.get_gripper_opening(self.id, gripper_id) @action def is_item_gripped(self, gripper_id: str) -> bool: return self.robot_api.is_item_gripped(self.id, gripper_id) def suctions(self) -> FrozenSet[str]: return self.robot_api.suctions(self.id) @action def suck(self, suction_id: str) -> None: self.robot_api.suck(self.id, suction_id) @action def release(self, suction_id: str) -> None: self.robot_api.release(self.id, suction_id) @action def is_item_attached(self, suction_id: str) -> bool: return self.robot_api.is_item_attached(self.id, suction_id) move.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) move_relative.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) move_relative_joints.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) set_joints.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) get_input.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) set_output.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) get_output.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) grip.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) set_opening.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) get_gripper_opening.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) is_item_gripped.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) suck.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) release.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True) is_item_attached.__action__ = ActionMetadata(free=True, blocking=True, composite=True, blackbox=True)
class Aubo(AbstractRobot): """REST interface to the robot service (0.12.0).""" _ABSTRACT = False urdf_package_name = "aubo.zip" def move_to_pose(self, end_effector_id: str, target_pose: Pose, speed: float, safe: bool = True) -> None: self.move(end_effector_id, target_pose, MoveTypeEnum.SIMPLE, speed, safe=safe) # --- EndEffectors Controller -------------------------------------------------------------------------------------- @lru_cache() def get_end_effectors_ids(self) -> Set[str]: return set( rest.call(rest.Method.GET, f"{self.settings.url}/endEffectors", list_return_type=str)) def get_end_effector_pose(self, end_effector_id: str) -> Pose: return rest.call( rest.Method.GET, f"{self.settings.url}/endEffectors/{end_effector_id}/pose", return_type=Pose) def move( self, end_effector_id: str, pose: Pose, move_type: MoveTypeEnum, speed: float = 0.5, acceleration: float = 0.5, safe: bool = True, *, an: Optional[str] = None, ) -> None: """Moves the robot's end-effector to a specific pose. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param move_type: Type of move. :param speed: Speed of move. :param acceleration: Acceleration of move. :param safe: When true, robot will consider its environment and avoid collisions. :return: """ assert 0.0 <= speed <= 1.0 assert 0.0 <= acceleration <= 1.0 url = f"{self.settings.url}/endEffectors/{end_effector_id}/move" params = { "moveType": move_type.value, "speed": speed, "acceleration": acceleration, "safe": safe } with self._move_lock: rest.call(rest.Method.PUT, url, body=pose, params=params, timeout=self.move_timeout) def move_relative( self, end_effector_id: str, pose: Pose, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5, acceleration: float = 0.5, safe: bool = True, *, an: Optional[str] = None, ) -> None: """Moves the robot's end-effector to a specific pose. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :param acceleration: Acceleration of move. :param safe: When true, robot will consider its environment and avoid collisions. :return: """ assert 0.0 <= speed <= 1.0 assert 0.0 <= acceleration <= 1.0 url = f"{self.settings.url}/endEffectors/{end_effector_id}/moveRelative" params = { "moveType": move_type.value, "speed": speed, "acceleration": acceleration, "safe": safe } body = MoveRelativeParameters(pose, rel_pose.position, rel_pose.orientation) with self._move_lock: rest.call(rest.Method.PUT, url, body=body, params=params, timeout=self.move_timeout) def move_relative_joints( self, end_effector_id: str, joints: ProjectRobotJoints, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5, acceleration: float = 0.5, safe: bool = True, *, an: Optional[str] = None, ) -> None: """Moves the robot's end-effector relatively to specific joint values. :param robot_id: Unique robot id. :param end_effector_id: Unique end-effector id. :param joints: Target joints. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :param acceleration: Acceleration of move. :param safe: When true, robot will consider its environment and avoid collisions. :return: """ assert 0.0 <= speed <= 1.0 assert 0.0 <= acceleration <= 1.0 url = f"{self.settings.url}/endEffectors/{end_effector_id}/moveJointsRelative" body = MoveRelativeJointsParameters(joints.joints, rel_pose.position, rel_pose.orientation) params = { "moveType": move_type.value, "speed": speed, "acceleration": acceleration, "safe": safe } with self._move_lock: rest.call(rest.Method.PUT, url, body=body, params=params, timeout=self.move_timeout) def link(self, end_effector_id: str, collision_id: str) -> None: """Links collision object to end effector. :param end_effector_id: Unique end-effector id. :param collision_id: Unique id of collision :return: """ rest.call( rest.Method.PUT, f"{self.settings.url}/endEffectors/{end_effector_id}/link", params={"collisionId": collision_id}, ) def unlink(self, end_effector_id: str) -> None: """Unlinks collision object from end effector. :param end_effector_id: Unique end-effector id. :return: """ rest.call( rest.Method.PUT, f"{self.settings.url}/endEffectors/{end_effector_id}/unlink") def inverse_kinematics( self, end_effector_id: str, pose: Pose, start_joints: Optional[List[Joint]] = None, avoid_collisions: bool = True, ) -> List[Joint]: """Computes inverse kinematics. :param end_effector_id: IK target pose end-effector :param pose: IK target pose :param start_joints: IK start joints (if not provided, current joint values will be used) :param avoid_collisions: Return non-collision IK result if true :return: Inverse kinematics """ if start_joints is None: start_joints = self.robot_joints() body = IKPoseJointsParameters(pose, start_joints) return rest.call( rest.Method.PUT, f"{self.settings.url}/endEffectors/{end_effector_id}/inverseKinematics", params={"avoidCollisions": avoid_collisions}, body=body, list_return_type=Joint, ) def forward_kinematics(self, end_effector_id: str, joints: List[Joint]) -> Pose: """Computes forward kinematics. :param end_effector_id: Target end effector name :param joints: Input joint values :return: Pose of the given end effector """ return rest.call( rest.Method.PUT, f"{self.settings.url}/endEffectors/{end_effector_id}/forwardKinematics", body=joints, return_type=Pose, ) # --- Suctions Controller ------------------------------------------------------------------------------------------ @lru_cache() def suctions(self) -> Set[str]: return set( rest.call(rest.Method.GET, f"{self.settings.url}/suctions", list_return_type=str)) def suck(self, suction_id: str, *, an: Optional[str] = None) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/suctions/{suction_id}/suck") def release(self, suction_id: str, *, an: Optional[str] = None) -> None: rest.call(rest.Method.PUT, f"{self.settings.url}/suctions/{suction_id}/release") def is_item_attached(self, suction_id: str, *, an: Optional[str] = None) -> bool: return rest.call(rest.Method.GET, f"{self.settings.url}/suctions/{suction_id}/attached", return_type=bool) move.__action__ = ActionMetadata(blocking=True) # type: ignore move_relative.__action__ = ActionMetadata(blocking=True) # type: ignore move_relative_joints.__action__ = ActionMetadata( blocking=True) # type: ignore suck.__action__ = ActionMetadata(blocking=True) # type: ignore release.__action__ = ActionMetadata(blocking=True) # type: ignore is_item_attached.__action__ = ActionMetadata(blocking=True) # type: ignore
class Search(AbstractWithPose): """REST interface to the search service (0.11.0).""" _ABSTRACT = False # --- Capture Controller ------------------------------------------------------------------------------------------- def grab_image(self, *, an: Optional[str] = None) -> None: """Grabs image and stores to internal cache. :return: """ rest.call(rest.Method.PUT, f"{self.settings.url}/capture/grab") def get_image(self, *, an: Optional[str] = None) -> Image: """Gets RGB image from internal cache, if there is any. :return: """ return rest.get_image(f"{self.settings.url}/capture/image") def get_pose(self, *, an: Optional[str] = None) -> Pose: """Gets capture device pose in actual initialized spatial system space. :return: """ return rest.call(rest.Method.GET, f"{self.settings.url}/capture/pose", return_type=Pose) def capture_export(self, path_to_save_zip: str, *, an: Optional[str] = None) -> None: """Gets the zipped captured data. :param path_to_save_zip: Where to save the zip file. :return: """ rest.download(f"{self.settings.url}/capture/export", path_to_save_zip) # --- Pick Controller ---------------------------------------------------------------------------------------------- def upsert_pick_args(self, item_id: str, suction_id: str, poses: List[PickArgs], *, an: Optional[str] = None) -> None: """Adds or updates arguments required for pick given item with given suction. :param item_id: :param suction_id: :param poses: :return: """ rest.call( rest.Method.PUT, f"{self.settings.url}/pick/suctions", body=poses, params={ "itemId": item_id, "suctionId": suction_id }, ) def get_pick_args(self, item_id: str, suction_id: str, *, an: Optional[str] = None) -> List[PickArgs]: """Gets pick arguments for given suction and item. :param item_id: :param suction_id: :return: """ rest.call( rest.Method.GET, f"{self.settings.url}/pick/suctions", params={ "itemId": item_id, "suctionId": suction_id }, list_return_type=PickArgs, ) def compute_pick_args(self, item_id: str, suction_id: str, pose: Pose, *, an: Optional[str] = None) -> List[Pose]: """Computes pick arguments for given suction, item and item pose. :param item_id: :param suction_id: :param pose: :return: """ return rest.call( rest.Method.PUT, f"{self.settings.url}/pick/suctions/compute", body=pose, params={ "itemId": item_id, "suctionId": suction_id }, list_return_type=Pose, ) def upsert_gripper_args(self, item_id: str, gripper_id: str, gripper_setup: List[GripperSetup], *, an: Optional[str] = None) -> None: """Adds or updates arguments required for pick given item with given gripper. :param item_id: :param gripper_id: :param gripper_setup: :return: """ rest.call( rest.Method.PUT, f"{self.settings.url}/pick/grippers", body=gripper_setup, params={ "itemId": item_id, "gripperId": gripper_id }, ) def get_gripper_args(self, item_id: str, gripper_id: str, *, an: Optional[str] = None) -> List[GripperSetup]: """Gets pick arguments for given gripper and item. :param item_id: :param gripper_id: :return: """ rest.call( rest.Method.GET, f"{self.settings.url}/pick/grippers", params={ "itemId": item_id, "gripperId": gripper_id }, list_return_type=GripperSetup, ) def compute_gripper_args(self, item_id: str, gripper_id: str, pose: Pose, *, an: Optional[str] = None) -> List[Pose]: """Gets pick poses for specific tool and item. :param item_id: :param gripper_id: :param pose: :return: """ return rest.call( rest.Method.GET, f"{self.settings.url}/pick/grippers/compute", list_return_type=Pose, body=pose, params={ "itemId": item_id, "gripperId": gripper_id }, ) # --- Search Controller -------------------------------------------------------------------------------------------- def search(self, *, an: Optional[str] = None) -> SearchOutput: """Searches items based on search engine configuration and images stored in internal cache. :return: """ return rest.call(rest.Method.GET, f"{self.settings.url}/search", return_type=SearchOutput) def set_search_parameters(self, parameters: SearchEngineParameters, *, an: Optional[str] = None) -> None: """Sets the search parameters. :param parameters: :return: """ rest.call(rest.Method.PUT, f"{self.settings.url}/search", body=parameters) def visualization(self, *, an: Optional[str] = None) -> Image: """Gets RGB visualization from last search run, if there is any. :return: """ return rest.get_image(f"{self.settings.url}/search/visualization") grab_image.__action__ = ActionMetadata(blocking=True) # type: ignore get_image.__action__ = ActionMetadata(blocking=True) # type: ignore get_pose.__action__ = ActionMetadata(blocking=True) # type: ignore upsert_pick_args.__action__ = ActionMetadata(blocking=True) # type: ignore get_pick_args.__action__ = ActionMetadata(blocking=True) # type: ignore compute_pick_args.__action__ = ActionMetadata( blocking=True) # type: ignore upsert_gripper_args.__action__ = ActionMetadata( blocking=True) # type: ignore get_gripper_args.__action__ = ActionMetadata(blocking=True) # type: ignore compute_gripper_args.__action__ = ActionMetadata( blocking=True) # type: ignore search.__action__ = ActionMetadata(blocking=True) # type: ignore set_search_parameters.__action__ = ActionMetadata( blocking=True) # type: ignore visualization.__action__ = ActionMetadata(blocking=True) # type: ignore
class RestRobotService(RobotService): """ REST interface to the robot service. """ def __init__(self, configuration_id: str): super(RestRobotService, self).__init__(configuration_id) systems.create(URL, self) def destroy(self): systems.destroy(URL) @staticmethod def get_configuration_ids() -> FrozenSet[str]: return systems.systems(URL) def add_collision(self, obj: Generic) -> None: if not obj.collision_model or obj.collision_model.type( ) == Model3dType.NONE: return params = obj.collision_model.to_dict() del params["id"] params[obj.collision_model.__class__.__name__.lower() + "Id"] = collision_id(obj) # TODO temporary hack if obj.collision_model.type() == Model3dType.MESH: params["mesh_scale_x"] = 1.0 params["mesh_scale_y"] = 1.0 params["mesh_scale_z"] = 1.0 params["transform_id"] = "world" rest.put(f"{URL}/collisions/{obj.collision_model.type().value}", obj.pose, params) def remove_collision(self, obj: Generic) -> None: if not obj.collision_model or obj.collision_model.type( ) == Model3dType.NONE: return rest.delete(f"{URL}/collisions/{collision_id(obj)}") def clear_collisions(self) -> None: for coll_id in rest.get_list_primitive(f"{URL}/collisions", str): rest.delete(f"{URL}/collisions/{coll_id}") @lru_cache() def get_robot_ids(self) -> FrozenSet[str]: return frozenset(rest.get_data(f"{URL}/robots")) def get_robot_pose(self, robot_id: str) -> Pose: return rest.get(f"{URL}/robots/{robot_id}/pose", Pose) def stop(self, robot_id: str) -> None: rest.put(f"{URL}/robots/{robot_id}/stop") def robot_joints(self, robot_id: str) -> List[Joint]: return rest.get_list(f"{URL}/robots/{robot_id}/joints", Joint) @lru_cache() def get_end_effectors_ids(self, robot_id: str) -> FrozenSet[str]: return frozenset( rest.get_data(f"{URL}/robots/{robot_id}/endeffectors")) def get_end_effector_pose(self, robot_id: str, end_effector_id: str) -> Pose: return rest.get( f"{URL}/robots/{robot_id}/endeffectors/{end_effector_id}/pose", Pose) @action def move(self, robot_id: str, end_effector_id: str, pose: Pose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector to a specific pose. :param robot_id: Unique robot id. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 rest.put( f"{URL}/robots/{robot_id}/endeffectors/{end_effector_id}/move", pose, { "moveType": move_type.value, "speed": speed }) @action def move_relative(self, robot_id: str, end_effector_id: str, pose: Pose, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector to a specific pose. :param robot_id: Unique robot id. :param end_effector_id: Unique end-effector id. :param pose: Target pose. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 body = MoveRelativeParameters(pose, rel_pose.position, rel_pose.orientation) rest.put( f"{URL}/robots/{robot_id}/endeffectors/{end_effector_id}/moveRelative", body, { "moveType": move_type.value, "speed": speed }) @action def move_relative_joints(self, robot_id: str, end_effector_id: str, joints: ProjectRobotJoints, rel_pose: RelativePose, move_type: MoveTypeEnum, speed: float = 0.5) -> None: """ Moves the robot's end-effector relatively to specific joint values. :param robot_id: Unique robot id. :param end_effector_id: Unique end-effector id. :param joints: Target joints. :param rel_pose: Relative pose. :param move_type: Type of move. :param speed: Speed of move. :return: """ assert 0.0 <= speed <= 1.0 body = MoveRelativeJointsParameters(joints.joints, rel_pose.position, rel_pose.orientation) rest.put( f"{URL}/robots/{robot_id}/endeffectors/{end_effector_id}/moveRelativeJoints", body, { "moveType": move_type.value, "speed": speed }) @action def set_joints(self, robot_id: str, joints: ProjectRobotJoints, move_type: MoveTypeEnum, speed: float = 0.5) -> None: assert 0.0 <= speed <= 1.0 assert robot_id == joints.robot_id rest.put(f"{URL}/robots/{robot_id}/joints", joints.joints, { "moveType": move_type.value, "speed": speed }) @lru_cache() def inputs(self, robot_id: str) -> FrozenSet[str]: return frozenset(rest.get_data(f"{URL}/robots/{robot_id}/inputs")) @lru_cache() def outputs(self, robot_id: str) -> FrozenSet[str]: return frozenset(rest.get_data(f"{URL}/robots/{robot_id}/outputs")) @action def get_input(self, robot_id: str, input_id: str) -> float: super(RestRobotService, self).get_input(robot_id, input_id) return rest.get_primitive(f"{URL}/robots/{robot_id}/inputs/{input_id}", float) @action def set_output(self, robot_id: str, output_id: str, value: float) -> None: assert 0.0 <= value <= 1.0 super(RestRobotService, self).set_output(robot_id, output_id, value) rest.put(f"{URL}/robots/{robot_id}/outputs/{output_id}", params={"value": value}) @action def get_output(self, robot_id: str, output_id: str) -> float: return rest.get_primitive( f"{URL}/robots/{robot_id}/outputs/{output_id}", float) def focus(self, mfa: MeshFocusAction) -> Pose: return rest.put(f"{URL}/utils/focus", mfa, data_cls=Pose) @lru_cache() def grippers(self, robot_id: str) -> FrozenSet[str]: return frozenset(rest.get_data(f"{URL}/robots/{robot_id}/grippers")) @action def grip(self, robot_id: str, gripper_id: str, position: float = 0.0, speed: float = 0.5, force: float = 0.5) -> \ None: assert 0.0 <= position <= 1.0 assert 0.0 <= speed <= 1.0 assert 0.0 <= force <= 1.0 rest.put(f"{URL}/robots/{robot_id}/grippers/{gripper_id}/grip", params={ "position": position, "speed": speed, "force": force }) @action def set_opening(self, robot_id: str, gripper_id: str, position: float = 1.0, speed: float = 0.5) -> None: assert 0.0 <= position <= 1.0 assert 0.0 <= speed <= 1.0 rest.put(f"{URL}/robots/{robot_id}/grippers/{gripper_id}/opening", params={ "position": position, "speed": speed }) @action def get_gripper_opening(self, robot_id: str, gripper_id: str) -> float: return rest.get_primitive( f"{URL}/robots/{robot_id}/grippers/{gripper_id}/opening", float) @action def is_item_gripped(self, robot_id: str, gripper_id: str) -> bool: return rest.get_primitive( f"{URL}/robots/{robot_id}/grippers/{gripper_id}/gripped", bool) @lru_cache() def suctions(self, robot_id: str) -> FrozenSet[str]: return frozenset(rest.get_data(f"{URL}/robots/{robot_id}/suctions")) @action def suck(self, robot_id: str, suction_id: str) -> None: rest.put(f"{URL}/robots/{robot_id}/suctions/{suction_id}/suck") @action def release(self, robot_id: str, suction_id: str) -> None: rest.put(f"{URL}/robots/{robot_id}/suctions/{suction_id}/release") @action def is_item_attached(self, robot_id: str, suction_id: str) -> bool: return rest.get_primitive( f"{URL}/robots/{robot_id}/suctions/{suction_id}/attached", bool) move.__action__ = ActionMetadata(free=True, blocking=True) move_relative.__action__ = ActionMetadata(free=True, blocking=True) move_relative_joints.__action__ = ActionMetadata(free=True, blocking=True) set_joints.__action__ = ActionMetadata(free=True, blocking=True) get_input.__action__ = ActionMetadata(free=True, blocking=True) set_output.__action__ = ActionMetadata(free=True, blocking=True) get_output.__action__ = ActionMetadata(free=True, blocking=True) grip.__action__ = ActionMetadata(free=True, blocking=True) set_opening.__action__ = ActionMetadata(free=True, blocking=True) get_gripper_opening.__action__ = ActionMetadata(free=True, blocking=True) is_item_gripped.__action__ = ActionMetadata(free=True, blocking=True) suck.__action__ = ActionMetadata(free=True, blocking=True) release.__action__ = ActionMetadata(free=True, blocking=True) is_item_attached.__action__ = ActionMetadata(free=True, blocking=True)
class AbstractDobot(Robot): robot_type = RobotType.SCARA def __init__(self, obj_id: str, name: str, pose: Pose, settings: DobotSettings) -> None: super(AbstractDobot, self).__init__(obj_id, name, pose, settings) if not self.settings.simulator: try: self._dobot = dobot.Dobot(self.settings.port) except dobot.DobotException as e: raise DobotException("Could not connect to the robot.") from e if self.settings.calibrate_on_init: self.home() else: self._ee_pose = Pose() self._ee_pose.orientation.set_from_quaternion( quaternion.from_euler_angles(0, math.pi, 0)) def alarms_to_exception(self) -> None: alarms = self._dobot.get_alarms() if alarms: raise DobotException( f"Alarm(s): {','.join([alarm.name for alarm in alarms])}.") @property def settings(self) -> DobotSettings: return cast(DobotSettings, super(AbstractDobot, self).settings) def cleanup(self): if not self.settings.simulator: self._dobot.close() def get_end_effectors_ids(self) -> Set[str]: return {"default"} def grippers(self) -> Set[str]: return set() def suctions(self) -> Set[str]: return {"default"} def get_end_effector_pose(self, end_effector_id: str) -> Pose: # global pose if self.settings.simulator: return tr.make_pose_abs(self.pose, self._ee_pose) pos = self._dobot.get_pose().position # in mm p = Pose() p.position.x = pos.x / 1000.0 p.position.y = pos.y / 1000.0 p.position.z = pos.z / 1000.0 p.orientation.set_from_quaternion( quaternion.from_euler_angles(0, math.pi, pos.r)) return tr.make_pose_abs(self.pose, p) def move_to_pose(self, end_effector_id: str, target_pose: Pose, speed: float) -> None: self.move(target_pose, MoveType.LINEAR, speed * 100, 50.0) def move_to_joints(self, target_joints: List[Joint], speed: float) -> None: raise NotImplementedError( "Dobot does not support setting joints so far.") def home(self): """ Run the homing procedure. """ self._dobot.clear_alarms() with self._move_lock: if self.settings.simulator: time.sleep(2.0) return self._dobot.wait_for_cmd(self._dobot.home()) self.alarms_to_exception() def move(self, pose: Pose, move_type: MoveType, velocity: float = 50., acceleration: float = 50.) -> None: """ Moves the robot's end-effector to a specific pose. :param pose: Target pose. :move_type: Move type. :param velocity: Speed of move (percent). :param acceleration: Acceleration of move (percent). :return: """ assert .0 <= velocity <= 100. assert .0 <= acceleration <= 100. self._dobot.clear_alarms() with self._move_lock: rp = tr.make_pose_rel(self.pose, pose) if self.settings.simulator: time.sleep((100.0 - velocity) * 0.05) self._ee_pose = rp return rotation = quaternion.as_euler_angles( rp.orientation.as_quaternion())[2] self._dobot.speed(velocity, acceleration) self._dobot.wait_for_cmd( self._dobot.move_to(rp.position.x * 1000.0, rp.position.y * 1000.0, rp.position.z * 1000.0, rotation, MOVE_TYPE_MAPPING[move_type])) self.alarms_to_exception() def suck(self) -> None: if not self.settings.simulator: self._dobot.wait_for_cmd(self._dobot.suck(True)) def release(self) -> None: if not self.settings.simulator: self._dobot.wait_for_cmd(self._dobot.suck(False)) home.__action__ = ActionMetadata(blocking=True) # type: ignore move.__action__ = ActionMetadata(blocking=True) # type: ignore suck.__action__ = ActionMetadata(blocking=True) # type: ignore release.__action__ = ActionMetadata(blocking=True) # type: ignore