Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -103,10 +103,6 @@ def done_callback(fut: Future[ROSActionResultT]) -> None:
if fut.cancelled():
goal.abort()
self.protocol.log("info", f"Aborted goal {goal_id}")
# Send an empty result to avoid stack traces
fut.set_result(
cast("ROSActionResultT", get_action_class(self.action_type).Result())
)
else:
if goal_id not in self.goal_statuses:
goal.abort()
Expand Down Expand Up @@ -138,7 +134,9 @@ def done_callback(fut: Future[ROSActionResultT]) -> None:

try:
result = await future
assert result is not None, "Action result cannot be None"
if result is None:
# Return empty result when cancelled/aborted
return cast("ROSActionResultT", get_action_class(self.action_type).Result())
return result
finally:
del self.goal_futures[goal_id]
Expand Down
13 changes: 10 additions & 3 deletions rosbridge_library/src/rosbridge_library/internal/actions.py
Original file line number Diff line number Diff line change
Expand Up @@ -146,7 +146,7 @@ def args_to_action_goal_instance(inst: ROSMessage, args: list | dict[str, Any] |
class SendGoal(Generic[ROSActionGoalT, ROSActionResultT, ROSActionFeedbackT]):
"""Helper class to send action goals."""

result: GetResultServiceResponse[ROSActionResultT] | None = None
result: GetResultServiceResponse[ROSActionResultT] | Exception | None = None

def __init__(self, server_timeout_time: float = 1.0, sleep_time: float = 0.001) -> None:
self.server_timeout_time = server_timeout_time
Expand All @@ -166,7 +166,8 @@ def goal_response_cb(
assert self.goal_handle is not None
if not self.goal_handle.accepted:
msg = "Action goal was rejected"
raise Exception(msg)
self.result = Exception(msg)
return
result_future: Future[GetResultServiceResponse[ROSActionResultT]] = (
self.goal_handle.get_result_async()
)
Expand Down Expand Up @@ -195,14 +196,20 @@ def send_goal(
client: ActionClient[ROSActionGoalT, ROSActionResultT, ROSActionFeedbackT] = ActionClient(
node_handle, action_class, action_name
)
client.wait_for_server(timeout_sec=self.server_timeout_time)
if not client.wait_for_server(timeout_sec=self.server_timeout_time):
msg = "No action server available"
raise Exception(msg)
send_goal_future = client.send_goal_async(inst, feedback_callback=feedback_cb) # type: ignore[arg-type]
send_goal_future.add_done_callback(self.goal_response_cb)

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

client.destroy()

if isinstance(self.result, Exception):
raise self.result

if self.result is not None:
# Turn the response into JSON and pass to the callback
json_response = extract_values(self.result)
Expand Down