|
| 1 | +from skiros2_common.core.abstract_skill import State |
| 2 | +from skiros2_common.core.primitive import PrimitiveBase |
| 3 | +from skiros2_common.core.params import ParamTypes |
| 4 | +import skiros2_common.tools.logger as log |
| 5 | +import rclpy |
| 6 | +from rclpy import action, task, client, Future |
| 7 | +from rclpy.time import Duration |
| 8 | +from actionlib_msgs.msg import GoalStatus |
| 9 | +import queue |
| 10 | +from threading import Lock |
| 11 | +from typing import Optional |
| 12 | +from action_msgs.msg import GoalStatus |
| 13 | +from skiros2_std_skills.utils import AtomicVar |
| 14 | + |
| 15 | +class PrimitiveServiceClient(PrimitiveBase): |
| 16 | + """ |
| 17 | + @brief Base class for skills based on a service client. |
| 18 | +
|
| 19 | + See test_service_skill for a practical example |
| 20 | + """ |
| 21 | + |
| 22 | + build_client_onstart = False |
| 23 | + call_timeout_sec = None |
| 24 | + |
| 25 | + def onPreempt(self): |
| 26 | + """ |
| 27 | + @brief Cancel service call |
| 28 | + """ |
| 29 | + log.debug("Cancel requested") |
| 30 | + if self._future is not None: |
| 31 | + self._future.cancel() |
| 32 | + self._future = None |
| 33 | + self.client.destroy() |
| 34 | + self.client = None |
| 35 | + log.debug("Service call canceled") |
| 36 | + return self.success("Service call canceled.") |
| 37 | + else: |
| 38 | + return self.fail("Goal has not been accepted or rejected, cannot cancel.") |
| 39 | + |
| 40 | + def onStart(self): |
| 41 | + self._response = AtomicVar() |
| 42 | + |
| 43 | + # 1. Build client |
| 44 | + if self.build_client_onstart or self.client is None: |
| 45 | + self.client = self.buildClient() |
| 46 | + |
| 47 | + if self.client is None: |
| 48 | + return self.startError("Action client returned by buildClient() is None.", -101) |
| 49 | + |
| 50 | + # 2. Wait for server |
| 51 | + if not self.client.wait_for_service(0.5): |
| 52 | + return self.startError("Service server is not available: {}".format(self.client), -101) |
| 53 | + |
| 54 | + # 3. Build message and call service |
| 55 | + service_request = self.buildRequest() |
| 56 | + if service_request is None: |
| 57 | + return self.startError("Service request is None", -106) |
| 58 | + |
| 59 | + self._future = self.client.call_async(service_request) |
| 60 | + self._future.add_done_callback(self._response_callback) |
| 61 | + self._last_call_timestamp = self.node.get_clock().now() |
| 62 | + |
| 63 | + return True |
| 64 | + |
| 65 | + def _response_callback(self, future: Future): |
| 66 | + self._response.set(future.result()) |
| 67 | + |
| 68 | + def execute(self): |
| 69 | + res = self._response.get_and_reset() |
| 70 | + if res is not None: |
| 71 | + return self.onDone(res) |
| 72 | + |
| 73 | + time_since_start_sec = (self.node.get_clock().now()-self._last_call_timestamp).nanoseconds/1.0e9 |
| 74 | + if self.call_timeout_sec is not None: |
| 75 | + if time_since_start_sec > self.call_timeout_sec: |
| 76 | + self.client.destroy() |
| 77 | + self.client = None |
| 78 | + return self.fail("Service call did not finish within timeout of %d sec" % self.call_timeout_sec, -104) |
| 79 | + |
| 80 | + return self.step("Service called, been waiting for %.1f sec" % time_since_start_sec) |
| 81 | + |
| 82 | + def onInit(self): |
| 83 | + """ |
| 84 | + @brief Optional to override. Called once when loading the primitive. If return False, the primitive is not loaded |
| 85 | + @return True if loaded correctly. False on error |
| 86 | + """ |
| 87 | + self.client = None |
| 88 | + if not self.build_client_onstart: |
| 89 | + self.client = self.buildClient() |
| 90 | + |
| 91 | + return True |
| 92 | + |
| 93 | + def onEnd(self): |
| 94 | + """ |
| 95 | + @brief Optional to override. Routine called just after skill execution end |
| 96 | + """ |
| 97 | + return True |
| 98 | + |
| 99 | + def buildClient(self)->client.Client: |
| 100 | + """ |
| 101 | + @brief To override. Called when starting the skill |
| 102 | + @return an service client created by self.node.create_client(...) |
| 103 | + """ |
| 104 | + pass |
| 105 | + |
| 106 | + def buildRequest(self): |
| 107 | + """ |
| 108 | + @brief To override. Called when starting the skill |
| 109 | + @return an action msg initialized |
| 110 | + """ |
| 111 | + pass |
| 112 | + |
| 113 | + def onDone(self, response): |
| 114 | + """ |
| 115 | + @brief To override. Called when response has arrived. |
| 116 | + @return self.success or self.fail |
| 117 | + """ |
| 118 | + #Do something with result msg |
| 119 | + return self.success("Finished. Result: {}".format(response)) |
0 commit comments