Skip to content

Commit 728ed0d

Browse files
Spir0ubjsowa
andauthored
fix: Handle action rejection and server timeout (#1139)
* add server timeout exception * forward rejected goal handles The goal_response_cb should not throw an exception, so the exception is passed in the result and then raised in send_goal * return an empty result when result was None due to cancellation/abortion * fix lint error --------- Co-authored-by: Błażej Sowa <bsowa123@gmail.com>
1 parent 1efe67a commit 728ed0d

File tree

2 files changed

+13
-8
lines changed

2 files changed

+13
-8
lines changed

rosbridge_library/src/rosbridge_library/capabilities/advertise_action.py

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -103,10 +103,6 @@ def done_callback(fut: Future[ROSActionResultT]) -> None:
103103
if fut.cancelled():
104104
goal.abort()
105105
self.protocol.log("info", f"Aborted goal {goal_id}")
106-
# Send an empty result to avoid stack traces
107-
fut.set_result(
108-
cast("ROSActionResultT", get_action_class(self.action_type).Result())
109-
)
110106
else:
111107
if goal_id not in self.goal_statuses:
112108
goal.abort()
@@ -138,7 +134,9 @@ def done_callback(fut: Future[ROSActionResultT]) -> None:
138134

139135
try:
140136
result = await future
141-
assert result is not None, "Action result cannot be None"
137+
if result is None:
138+
# Return empty result when cancelled/aborted
139+
return cast("ROSActionResultT", get_action_class(self.action_type).Result())
142140
return result
143141
finally:
144142
del self.goal_futures[goal_id]

rosbridge_library/src/rosbridge_library/internal/actions.py

Lines changed: 10 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -146,7 +146,7 @@ def args_to_action_goal_instance(inst: ROSMessage, args: list | dict[str, Any] |
146146
class SendGoal(Generic[ROSActionGoalT, ROSActionResultT, ROSActionFeedbackT]):
147147
"""Helper class to send action goals."""
148148

149-
result: GetResultServiceResponse[ROSActionResultT] | None = None
149+
result: GetResultServiceResponse[ROSActionResultT] | Exception | None = None
150150

151151
def __init__(self, server_timeout_time: float = 1.0, sleep_time: float = 0.001) -> None:
152152
self.server_timeout_time = server_timeout_time
@@ -166,7 +166,8 @@ def goal_response_cb(
166166
assert self.goal_handle is not None
167167
if not self.goal_handle.accepted:
168168
msg = "Action goal was rejected"
169-
raise Exception(msg)
169+
self.result = Exception(msg)
170+
return
170171
result_future: Future[GetResultServiceResponse[ROSActionResultT]] = (
171172
self.goal_handle.get_result_async()
172173
)
@@ -195,14 +196,20 @@ def send_goal(
195196
client: ActionClient[ROSActionGoalT, ROSActionResultT, ROSActionFeedbackT] = ActionClient(
196197
node_handle, action_class, action_name
197198
)
198-
client.wait_for_server(timeout_sec=self.server_timeout_time)
199+
if not client.wait_for_server(timeout_sec=self.server_timeout_time):
200+
msg = "No action server available"
201+
raise Exception(msg)
199202
send_goal_future = client.send_goal_async(inst, feedback_callback=feedback_cb) # type: ignore[arg-type]
200203
send_goal_future.add_done_callback(self.goal_response_cb)
201204

202205
while self.result is None:
203206
time.sleep(self.sleep_time)
204207

205208
client.destroy()
209+
210+
if isinstance(self.result, Exception):
211+
raise self.result
212+
206213
if self.result is not None:
207214
# Turn the response into JSON and pass to the callback
208215
json_response = extract_values(self.result)

0 commit comments

Comments
 (0)