|
| 1 | +#!/usr/bin/env python |
| 2 | + |
| 3 | +# Copyright 2023 Carologistics |
| 4 | +# |
| 5 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 6 | +# you may not use this file except in compliance with the License. |
| 7 | +# You may obtain a copy of the License at |
| 8 | +# |
| 9 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 10 | +# |
| 11 | +# Unless required by applicable law or agreed to in writing, software |
| 12 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 13 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 14 | +# See the License for the specific language governing permissions and |
| 15 | +# limitations under the License. |
| 16 | + |
| 17 | +"""Use to move gripper to target pose.""" |
| 18 | + |
| 19 | +from rclpy.duration import Duration |
| 20 | +from gigatino_msgs.action import Gripper |
| 21 | +from flexbe_core import EventState, Logger |
| 22 | +from flexbe_core.proxy import ProxyActionClient |
| 23 | + |
| 24 | +class GripperCloseState(EventState): |
| 25 | + """ |
| 26 | + Use to grip the workpiece |
| 27 | + |
| 28 | + Parameters |
| 29 | + -- timeout Maximum time allowed (seconds) |
| 30 | + -- action_topic Name of action to invoke example ='robotinobase2/gigatino/gripper' |
| 31 | +
|
| 32 | + Outputs |
| 33 | + <= success congrats we got the workpiece. |
| 34 | + <= failed Failed for some reason. |
| 35 | + <= canceled User canceled before completion. |
| 36 | + <= timeout The action has timed out. |
| 37 | +
|
| 38 | + User data |
| 39 | + ># close bool false to close the gripper |
| 40 | +
|
| 41 | + """ |
| 42 | + |
| 43 | + def __init__(self, timeout, action_topic): |
| 44 | + # See example_state.py for basic explanations. |
| 45 | + super().__init__(outcomes=['success', 'failed', 'canceled', 'timeout'], |
| 46 | + input_keys=['close'], output_keys=[]) |
| 47 | + |
| 48 | + self._timeout = Duration(seconds=timeout) |
| 49 | + self._timeout_sec = timeout |
| 50 | + self._topic = action_topic |
| 51 | + |
| 52 | + # Create the action client when building the behavior. |
| 53 | + # Using the proxy client provides asynchronous access to the result and status |
| 54 | + # and makes sure only one client is used, no matter how often this state is used in a behavior |
| 55 | + ProxyActionClient.initialize(GripperCloseState._node) |
| 56 | + |
| 57 | + self._client = ProxyActionClient({self._topic: Gripper}, |
| 58 | + wait_duration=0.0) # pass required clients as dict (topic: type) |
| 59 | + |
| 60 | + # It may happen that the action client fails to send the action goal. |
| 61 | + self._error = False |
| 62 | + self._return = None # Retain return value in case the outcome is blocked by operator |
| 63 | + self._start_time = None |
| 64 | + |
| 65 | + def execute(self, userdata): |
| 66 | + # While this state is active, check if the action has been finished and evaluate the result. |
| 67 | + |
| 68 | + # Check if the client failed to send the goal. |
| 69 | + if self._error: |
| 70 | + return 'failed' |
| 71 | + |
| 72 | + if self._return is not None: |
| 73 | + # Return prior outcome in case transition is blocked by autonomy level |
| 74 | + return self._return |
| 75 | + |
| 76 | + if self._client.has_result(self._topic): |
| 77 | + _ = self._client.get_result(self._topic) # The delta result value is not useful here |
| 78 | + Logger.loginfo('gripped work piece') |
| 79 | + self._return = 'success' |
| 80 | + return self._return |
| 81 | + |
| 82 | + if self._node.get_clock().now().nanoseconds - self._start_time.nanoseconds > self._timeout.nanoseconds: |
| 83 | + # Checking for timeout after we check for goal response |
| 84 | + self._return = 'timeout' |
| 85 | + return 'timeout' |
| 86 | + |
| 87 | + # If the action has not yet finished, no outcome will be returned and the state stays active. |
| 88 | + return None |
| 89 | + |
| 90 | + def on_enter(self, userdata): |
| 91 | + |
| 92 | + # make sure to reset the error state since a previous state execution might have failed |
| 93 | + self._error = False |
| 94 | + self._return = None |
| 95 | + # Initialize start time |
| 96 | + self._start_time = self._node.get_clock().now() |
| 97 | + |
| 98 | + # Define timeout duration (if not already initialized) |
| 99 | + self._target_time = Duration(seconds=self._timeout_sec) |
| 100 | + |
| 101 | + |
| 102 | + if 'close' not in userdata: |
| 103 | + self._error = True |
| 104 | + Logger.logwarn("GripperCloseState requires data") |
| 105 | + return |
| 106 | + goal = Gripper.Goal() |
| 107 | + |
| 108 | + if isinstance(userdata.close, bool): |
| 109 | + goal.open = userdata.close |
| 110 | + else: |
| 111 | + self._error = True |
| 112 | + Logger.logwarn("Input is %s. Expects an bool", type(userdata.close).__name__) |
| 113 | + |
| 114 | + # Send the goal. |
| 115 | + try: |
| 116 | + self._client.send_goal(self._topic, goal, wait_duration=self._timeout_sec) |
| 117 | + except Exception as exc: # pylint: disable=W0703 |
| 118 | + # Since a state failure not necessarily causes a behavior failure, |
| 119 | + # it is recommended to only print warnings, not errors. |
| 120 | + # Using a linebreak before appending the error log enables the operator to collapse details in the GUI. |
| 121 | + Logger.logwarn(f"Failed to send the RotateAbsolute command:\n {type(exc)} - {exc}") |
| 122 | + self._error = True |
| 123 | + |
| 124 | + def on_exit(self, userdata): |
| 125 | + # Make sure that the action is not running when leaving this state. |
| 126 | + # A situation where the action would still be active is for example when the operator manually triggers an outcome. |
| 127 | + |
| 128 | + if not self._client.has_result(self._topic): |
| 129 | + self._client.cancel(self._topic) |
| 130 | + Logger.loginfo('Cancelled active action goal.') |
0 commit comments