26
26
from rclpy .node import Node
27
27
28
28
# ROS messages
29
- from action_msgs .msg import GoalInfo , GoalStatus
29
+ from action_msgs .msg import GoalStatus
30
+ from action_msgs .srv import CancelGoal
30
31
31
32
# Task Manager messages
32
33
from task_manager_msgs .msg import TaskStatus
@@ -65,6 +66,8 @@ def cancel_task(self) -> None:
65
66
class ActionTaskClient (TaskClient ):
66
67
"""Task client that keeps track of a single Action task."""
67
68
69
+ DONE_STATES = [GoalStatus .STATUS_SUCCEEDED , GoalStatus .STATUS_ABORTED , GoalStatus .STATUS_CANCELED ]
70
+
68
71
def __init__ (
69
72
self ,
70
73
node : Node ,
@@ -94,6 +97,7 @@ def __init__(
94
97
self ._client : ActionClient = action_clients [task_specs .task_name ]
95
98
96
99
self ._goal_handle : Optional [ClientGoalHandle ] = None
100
+ self ._result_future : Optional [Future ] = None
97
101
self .server_wait_timeout = 10.0
98
102
self .cancel_task_timeout = 5.0 # Timeout to wait for task to cancel
99
103
@@ -147,27 +151,21 @@ def start_task_async(self, goal_message: Any) -> None:
147
151
raise TaskStartError (f"Goal was not accepted by the action server for the task { self .task_specs .task_name } " )
148
152
149
153
self .task_details .status = TaskStatus .IN_PROGRESS
150
- future : Future = self ._goal_handle .get_result_async ()
151
- future .add_done_callback (self ._goal_done_cb )
154
+ self . _result_future = self ._goal_handle .get_result_async ()
155
+ self . _result_future .add_done_callback (self ._goal_done_cb )
152
156
153
157
def cancel_task (self ) -> None :
154
- """
158
+ """Cancel the task.
159
+
155
160
:raises CancelTaskFailedError: If cancel request fails, due to timeout or other
156
161
"""
162
+ if not self ._goal_handle :
163
+ raise CancelTaskFailedError ("Couldn't cancel the task, goal handle does not exist!" )
164
+
157
165
# In some rare cases the goal might already be done at this point. If not, cancel it.
158
- done_states = [GoalStatus .STATUS_SUCCEEDED , GoalStatus .STATUS_ABORTED , GoalStatus .STATUS_CANCELED ]
159
- if self ._goal_handle .status not in done_states :
160
- # There seems to be a bug in rclpy, making the return code to be 0 (ERROR_NONE),
161
- # no matter if the cancel was rejected or accepted. So checking instead if the
162
- # goal is within the cancelling goals.
163
- goals_canceling = self ._request_canceling (self .cancel_task_timeout )
164
- goal_ids_cancelling = [goal_info .goal_id for goal_info in goals_canceling ]
165
- if self ._goal_handle .goal_id not in goal_ids_cancelling :
166
- self ._node .get_logger ().error (
167
- f"Couldn't cancel the task. Action server { self .task_specs .topic } did not "
168
- f"accept to cancel the goal."
169
- )
170
- raise CancelTaskFailedError ("Couldn't cancel the task!" )
166
+ if self ._goal_handle .status not in self .DONE_STATES :
167
+ response = self ._request_canceling (self .cancel_task_timeout )
168
+ self ._handle_cancel_response (response )
171
169
172
170
# Wait until _goal_done_cb is called and callbacks have been notified
173
171
if not self .goal_done .wait (timeout = self .cancel_task_timeout ):
@@ -176,7 +174,15 @@ def cancel_task(self) -> None:
176
174
f"Is the task cancel implemented correctly?"
177
175
)
178
176
179
- def _request_canceling (self , timeout : float ) -> List [GoalInfo ]:
177
+ def _request_canceling (self , timeout : float ) -> CancelGoal .Response :
178
+ """Requests canceling for the goal and returns the cancel response.
179
+
180
+ :raises CancelTaskFailedError: If the cancel request timed out
181
+ :param timeout: Time to wait for cancel request to pass
182
+ :return: CancelGoal.Response
183
+ """
184
+ if not self ._goal_handle :
185
+ raise CancelTaskFailedError ("Couldn't cancel the task, goal handle does not exist!" )
180
186
future = self ._goal_handle .cancel_goal_async ()
181
187
try :
182
188
self ._wait_for_future_to_complete (future , timeout = timeout )
@@ -185,17 +191,65 @@ def _request_canceling(self, timeout: float) -> List[GoalInfo]:
185
191
f"Timeout while waiting response to cancel request from server { self .task_specs .task_name } : { str (e )} ."
186
192
)
187
193
raise CancelTaskFailedError ("Cancel request timed out." ) from e
188
- return future .result ().goals_canceling
194
+ return future .result ()
195
+
196
+ def _handle_cancel_response (self , response : CancelGoal .Response ) -> None :
197
+ """Handles the response from the cancel request.
198
+
199
+ :raises CancelTaskFailedError: If the cancel request fails
200
+ """
201
+ # There seems to be a bug in rclpy, making the return code to be 0 (ERROR_NONE),
202
+ # no matter if the cancel was rejected or accepted. So checking instead if the
203
+ # goal is within the cancelling goals.
204
+ if response .return_code == CancelGoal .Response .ERROR_UNKNOWN_GOAL_ID :
205
+ self ._node .get_logger ().info (
206
+ f"Action server { self .task_specs .topic } did not recognize the goal id. "
207
+ f"Maybe server has restarted during the task execution and the goal no longer exists. "
208
+ f"Considering the task canceled."
209
+ )
210
+ if not self ._result_future :
211
+ raise CancelTaskFailedError ("Couldn't cancel the task result future since it does not exist!" )
212
+ self ._result_future .cancel ()
213
+
214
+ elif response .return_code == CancelGoal .Response .ERROR_GOAL_TERMINATED :
215
+ self ._node .get_logger ().info (
216
+ f"Action server { self .task_specs .topic } did not accept to cancel the goal. "
217
+ f"Goal seems to have already finished. Considering the task canceled."
218
+ )
219
+ if not self ._result_future :
220
+ raise CancelTaskFailedError ("Couldn't cancel the task result future since it does not exist!" )
221
+ self ._result_future .cancel ()
222
+
223
+ else :
224
+ if not self ._goal_handle :
225
+ raise CancelTaskFailedError ("Couldn't cancel the task, goal handle does not exist!" )
226
+ goal_ids_cancelling = [goal_info .goal_id for goal_info in response .goals_canceling ]
227
+ if self ._goal_handle .goal_id not in goal_ids_cancelling :
228
+ self ._node .get_logger ().error (
229
+ f"Couldn't cancel the task. Action server { self .task_specs .topic } did not "
230
+ f"accept to cancel the goal."
231
+ )
232
+ raise CancelTaskFailedError ("Couldn't cancel the task!" )
189
233
190
234
def _goal_done_cb (self , future : Future ) -> None :
191
- """Called when the Action Client's goal finishes. Updates the task status and notifies callbacks further the
192
- other callbacks.
235
+ """Called when the Action Client's goal finishes. Updates the task status and invokes task done callbacks.
193
236
194
237
:param future: Future object giving the result of the action call.
195
238
"""
239
+ if future .cancelled ():
240
+ self .task_details .status = TaskStatus .CANCELED
241
+ self .task_details .result = self .task_specs .msg_interface .Result ()
242
+ else :
243
+ self ._fill_in_task_details (future )
244
+
245
+ for callback in self ._task_done_callbacks :
246
+ callback (self .task_specs , self .task_details )
247
+ self .goal_done .set ()
248
+
249
+ def _fill_in_task_details (self , future : Future ) -> None :
250
+ """Fills in the task details based on the future result."""
196
251
result = future .result ()
197
252
goal_status = result .status
198
-
199
253
try :
200
254
end_goal_status = ros_goal_status_to_task_status (goal_status )
201
255
except RuntimeError as e :
@@ -208,13 +262,8 @@ def _goal_done_cb(self, future: Future) -> None:
208
262
self .task_details .status = TaskStatus .DONE
209
263
else :
210
264
self .task_details .status = end_goal_status
211
-
212
265
self .task_details .result = result .result
213
266
214
- for callback in self ._task_done_callbacks :
215
- callback (self .task_specs , self .task_details )
216
- self .goal_done .set ()
217
-
218
267
@staticmethod
219
268
def _wait_for_future_to_complete (future : Future , timeout : Optional [float ]) -> None :
220
269
event = Event ()
0 commit comments