Skip to content

Commit 1df1f95

Browse files
authored
Fix action cancellation by passing status from JSON (#953)
1 parent c308374 commit 1df1f95

File tree

16 files changed

+100
-35
lines changed

16 files changed

+100
-35
lines changed

ROSBRIDGE_PROTOCOL.md

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -560,15 +560,17 @@ A result for a ROS action.
560560
"id": <string>,
561561
"action": <string>,
562562
"values": <json>,
563+
"status": <int>,
563564
"result": <boolean>
564565
}
565566
```
566567

567568
* **action** – the name of the action that was executed
569+
* **id** – if an ID was provided to the action goal, then the action result will contain the ID
568570
* **values** – the result values. If the service had no return values, then
569571
this field can be omitted (and will be by the rosbridge server)
570-
* **id** – if an ID was provided to the action goal, then the action result will contain the ID
571-
* **result** - return value of the action. true means success, false failure.
572+
* **status** - return status of the action. This matches the enumeration in the [`action_msgs/msg/GoalStatus`](https://docs.ros2.org/latest/api/action_msgs/msg/GoalStatus.html) ROS message.
573+
* **result** - return value of action. True means success, false failure.
572574

573575
---
574576

rosbridge_library/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
<exec_depend>python3-bson</exec_depend>
3131

3232
<test_depend>rosbridge_test_msgs</test_depend>
33-
<test_depend>actionlib_msgs</test_depend>
33+
<test_depend>action_msgs</test_depend>
3434
<test_depend>ament_cmake_pytest</test_depend>
3535
<test_depend>builtin_interfaces</test_depend>
3636
<test_depend>diagnostic_msgs</test_depend>

rosbridge_library/src/rosbridge_library/capabilities/action_result.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@ class ActionResult(Capability):
4141
(True, "action", str),
4242
(False, "id", str),
4343
(False, "values", dict),
44+
(True, "status", int),
4445
(True, "result", bool),
4546
]
4647

@@ -63,11 +64,12 @@ def action_result(self, message: dict) -> None:
6364
if message["result"]:
6465
# parse the message
6566
values = message["values"]
67+
status = message["status"]
6668
# create a message instance
6769
result = ros_loader.get_action_result_instance(action_handler.action_type)
6870
message_conversion.populate_instance(values, result)
69-
# pass along the result
70-
action_handler.handle_result(goal_id, result)
71+
# pass along the result and status
72+
action_handler.handle_result(goal_id, result, status)
7173
else:
7274
# Abort the goal
7375
action_handler.handle_abort(goal_id)

rosbridge_library/src/rosbridge_library/capabilities/advertise_action.py

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
from typing import Any
3535

3636
import rclpy
37+
from action_msgs.msg import GoalStatus
3738
from rclpy.action import ActionServer
3839
from rclpy.action.server import CancelResponse, ServerGoalHandle
3940
from rclpy.callback_groups import ReentrantCallbackGroup
@@ -52,6 +53,7 @@ def __init__(
5253
) -> None:
5354
self.goal_futures = {}
5455
self.goal_handles = {}
56+
self.goal_statuses = {}
5557

5658
self.action_name = action_name
5759
self.action_type = action_type
@@ -84,7 +86,13 @@ def done_callback(fut: rclpy.task.Future) -> None:
8486
# Send an empty result to avoid stack traces
8587
fut.set_result(get_action_class(self.action_type).Result())
8688
else:
87-
goal.succeed()
89+
status = self.goal_statuses[goal_id]
90+
if status == GoalStatus.STATUS_SUCCEEDED:
91+
goal.succeed()
92+
elif status == GoalStatus.STATUS_CANCELED:
93+
goal.canceled()
94+
else:
95+
goal.abort()
8896

8997
future = rclpy.task.Future()
9098
future.add_done_callback(done_callback)
@@ -113,7 +121,6 @@ def cancel_callback(self, cancel_request: ServerGoalHandle) -> CancelResponse:
113121
for goal_id, goal_handle in self.goal_handles.items():
114122
if cancel_request.goal_id == goal_handle.goal_id:
115123
self.protocol.log("warning", f"Canceling action {goal_id}")
116-
self.goal_futures[goal_id].cancel()
117124
cancel_message = {
118125
"op": "cancel_action_goal",
119126
"id": goal_id,
@@ -131,11 +138,12 @@ def handle_feedback(self, goal_id: str, feedback: Any) -> None:
131138
else:
132139
self.protocol.log("warning", f"Received action feedback for unrecognized id: {goal_id}")
133140

134-
def handle_result(self, goal_id: str, result: Any) -> None:
141+
def handle_result(self, goal_id: str, result: dict, status: int) -> None:
135142
"""
136143
Called by the ActionResult capability to handle a successful action result from the external client.
137144
"""
138145
if goal_id in self.goal_futures:
146+
self.goal_statuses[goal_id] = status
139147
self.goal_futures[goal_id].set_result(result)
140148
else:
141149
self.protocol.log("warning", f"Received action result for unrecognized id: {goal_id}")

rosbridge_library/src/rosbridge_library/capabilities/send_action_goal.py

Lines changed: 9 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
from functools import partial
3535
from threading import Thread
3636

37+
from action_msgs.msg import GoalStatus
3738
from rosbridge_library.capability import Capability
3839
from rosbridge_library.internal.actions import ActionClientHandler
3940
from rosbridge_library.internal.message_conversion import extract_values
@@ -75,7 +76,11 @@ def __init__(self, protocol: Protocol) -> None:
7576
protocol.node_handle.get_logger().info("Sending action goals in existing thread")
7677
protocol.register_operation("send_action_goal", self.send_action_goal)
7778

78-
protocol.register_operation("cancel_action_goal", self.cancel_action_goal)
79+
# Always register goal canceling in a new thread.
80+
protocol.register_operation(
81+
"cancel_action_goal",
82+
lambda msg: Thread(target=self.cancel_action_goal, args=(msg,)).start(),
83+
)
7984

8085
def send_action_goal(self, message: dict) -> None:
8186
# Pull out the ID
@@ -154,7 +159,8 @@ def _success(
154159
outgoing_message = {
155160
"op": "action_result",
156161
"action": action,
157-
"values": message,
162+
"values": message["result"],
163+
"status": message["status"],
158164
"result": True,
159165
}
160166
if cid is not None:
@@ -169,6 +175,7 @@ def _failure(self, cid: str, action: str, exc: Exception) -> None:
169175
"op": "action_result",
170176
"action": action,
171177
"values": str(exc),
178+
"status": GoalStatus.STATUS_UNKNOWN,
172179
"result": False,
173180
}
174181
if cid is not None:

rosbridge_library/src/rosbridge_library/internal/actions.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,9 @@ def goal_response_cb(self, future: Future) -> None:
147147
result_future = self.goal_handle.get_result_async()
148148
result_future.add_done_callback(self.get_result_cb)
149149

150+
def goal_cancel_cb(self, _: Future) -> None:
151+
self.goal_canceled = True
152+
150153
def send_goal(
151154
self,
152155
node_handle: Node,
@@ -169,7 +172,7 @@ def send_goal(
169172
send_goal_future = client.send_goal_async(inst, feedback_callback=feedback_cb)
170173
send_goal_future.add_done_callback(self.goal_response_cb)
171174

172-
while self.result is None and not self.goal_canceled:
175+
while self.result is None:
173176
time.sleep(self.sleep_time)
174177

175178
client.destroy()
@@ -186,6 +189,6 @@ def cancel_goal(self) -> None:
186189
return
187190

188191
cancel_goal_future = self.goal_handle.cancel_goal_async()
192+
cancel_goal_future.add_done_callback(self.goal_cancel_cb)
189193
while not cancel_goal_future.done():
190194
time.sleep(self.sleep_time)
191-
self.goal_canceled = True

rosbridge_library/test/capabilities/test_action_capabilities.py

Lines changed: 41 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
from threading import Thread
66

77
import rclpy
8+
from action_msgs.msg import GoalStatus
89
from example_interfaces.action._fibonacci import Fibonacci_FeedbackMessage
910
from rclpy.executors import SingleThreadedExecutor
1011
from rclpy.node import Node
@@ -97,7 +98,7 @@ def test_advertise_action(self):
9798
self.advertise.advertise_action(advertise_msg)
9899

99100
@unittest.skip(
100-
reason="Currently fails in Iron/Rolling due to https://github.com/ros2/rclpy/issues/1195, need to fix this"
101+
reason="Currently fails in Iron due to https://github.com/ros2/rclpy/issues/1195. Unskip when Iron is EOL in Nov 2024."
101102
)
102103
def test_execute_advertised_action(self):
103104
# Advertise the action
@@ -133,7 +134,7 @@ def test_execute_advertised_action(self):
133134
while self.received_message is None:
134135
time.sleep(0.5)
135136
loop_iterations += 1
136-
if loop_iterations > 3:
137+
if loop_iterations > 5:
137138
self.fail("Timed out waiting for action goal message.")
138139

139140
self.assertIsNotNone(self.received_message)
@@ -170,7 +171,7 @@ def test_execute_advertised_action(self):
170171
while self.latest_feedback is None:
171172
time.sleep(0.5)
172173
loop_iterations += 1
173-
if loop_iterations > 3:
174+
if loop_iterations > 5:
174175
self.fail("Timed out waiting for action feedback message.")
175176

176177
self.assertIsNotNone(self.latest_feedback)
@@ -184,6 +185,7 @@ def test_execute_advertised_action(self):
184185
"action": action_path,
185186
"id": self.received_message["id"],
186187
"values": {"sequence": [0, 1, 1, 2, 3, 5]},
188+
"status": GoalStatus.STATUS_SUCCEEDED,
187189
"result": True,
188190
}
189191
)
@@ -195,15 +197,16 @@ def test_execute_advertised_action(self):
195197
while self.received_message is None:
196198
time.sleep(0.5)
197199
loop_iterations += 1
198-
if loop_iterations > 3:
200+
if loop_iterations > 5:
199201
self.fail("Timed out waiting for action result message.")
200202

201203
self.assertIsNotNone(self.received_message)
202204
self.assertEqual(self.received_message["op"], "action_result")
203-
self.assertEqual(self.received_message["values"]["result"]["sequence"], [0, 1, 1, 2, 3, 5])
205+
self.assertEqual(self.received_message["values"]["sequence"], [0, 1, 1, 2, 3, 5])
206+
self.assertEqual(self.received_message["status"], GoalStatus.STATUS_SUCCEEDED)
204207

205208
@unittest.skip(
206-
reason="Currently fails in Iron/Rolling due to https://github.com/ros2/rclpy/issues/1195, need to fix this"
209+
reason="Currently fails in due to https://github.com/ros2/rclpy/issues/1195, need to fix this"
207210
)
208211
def test_cancel_advertised_action(self):
209212
# Advertise the action
@@ -239,7 +242,7 @@ def test_cancel_advertised_action(self):
239242
while self.received_message is None:
240243
time.sleep(0.5)
241244
loop_iterations += 1
242-
if loop_iterations > 3:
245+
if loop_iterations > 5:
243246
self.fail("Timed out waiting for action goal message.")
244247

245248
self.assertIsNotNone(self.received_message)
@@ -264,12 +267,39 @@ def test_cancel_advertised_action(self):
264267
while self.received_message is None:
265268
time.sleep(0.5)
266269
loop_iterations += 1
267-
if loop_iterations > 3:
270+
if loop_iterations > 5:
271+
self.fail("Timed out waiting for action result message.")
272+
273+
self.assertIsNotNone(self.received_message)
274+
self.assertEqual(self.received_message["op"], "cancel_action_goal")
275+
276+
# Now send the cancel result
277+
result_msg = loads(
278+
dumps(
279+
{
280+
"op": "action_result",
281+
"action": action_path,
282+
"id": self.received_message["id"],
283+
"values": {"sequence": []},
284+
"status": GoalStatus.STATUS_CANCELED,
285+
"result": True,
286+
}
287+
)
288+
)
289+
self.received_message = None
290+
self.result.action_result(result_msg)
291+
292+
loop_iterations = 0
293+
while self.received_message is None:
294+
time.sleep(0.5)
295+
loop_iterations += 1
296+
if loop_iterations > 5:
268297
self.fail("Timed out waiting for action result message.")
269298

270299
self.assertIsNotNone(self.received_message)
271300
self.assertEqual(self.received_message["op"], "action_result")
272-
self.assertFalse(self.received_message["result"])
301+
self.assertEqual(self.received_message["values"]["sequence"], [])
302+
self.assertEqual(self.received_message["status"], GoalStatus.STATUS_CANCELED)
273303

274304
@unittest.skip("Currently raises an exception not catchable by unittest, need to fix this")
275305
def test_unadvertise_action(self):
@@ -307,7 +337,7 @@ def test_unadvertise_action(self):
307337
while self.received_message is None:
308338
time.sleep(0.5)
309339
loop_iterations += 1
310-
if loop_iterations > 3:
340+
if loop_iterations > 5:
311341
self.fail("Timed out waiting for action goal message.")
312342

313343
self.assertIsNotNone(self.received_message)
@@ -327,7 +357,7 @@ def test_unadvertise_action(self):
327357
rclpy.spin_once(self.node, timeout_sec=0.1)
328358
time.sleep(0.5)
329359
loop_iterations += 1
330-
if loop_iterations > 3:
360+
if loop_iterations > 5:
331361
self.fail("Timed out waiting for unadvertise action message.")
332362

333363

rosbridge_library/test/capabilities/test_advertise.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -137,7 +137,7 @@ def test_invalid_msg_classes(self):
137137
def test_valid_msg_classes(self):
138138
assortedmsgs = [
139139
"geometry_msgs/Pose",
140-
"actionlib_msgs/GoalStatus",
140+
"action_msgs/GoalStatus",
141141
"geometry_msgs/WrenchStamped",
142142
"stereo_msgs/DisparityImage",
143143
"nav_msgs/OccupancyGrid",

rosbridge_library/test/internal/publishers/test_multi_publisher.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,7 @@ def test_verify_type(self):
8888
msg_type = "std_msgs/String"
8989
othertypes = [
9090
"geometry_msgs/Pose",
91-
"actionlib_msgs/GoalStatus",
91+
"action_msgs/GoalStatus",
9292
"geometry_msgs/WrenchStamped",
9393
"stereo_msgs/DisparityImage",
9494
"nav_msgs/OccupancyGrid",

rosbridge_library/test/internal/subscribers/test_multi_subscriber.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ def test_verify_type(self):
5858
msg_type = "std_msgs/String"
5959
othertypes = [
6060
"geometry_msgs/Pose",
61-
"actionlib_msgs/GoalStatus",
61+
"action_msgs/GoalStatus",
6262
"geometry_msgs/WrenchStamped",
6363
"stereo_msgs/DisparityImage",
6464
"nav_msgs/OccupancyGrid",

rosbridge_library/test/internal/test_message_conversion.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -228,7 +228,7 @@ def test_header_msg(self):
228228
def test_assorted_msgs(self):
229229
assortedmsgs = [
230230
"geometry_msgs/Pose",
231-
"actionlib_msgs/GoalStatus",
231+
"action_msgs/GoalStatus",
232232
"geometry_msgs/WrenchStamped",
233233
"stereo_msgs/DisparityImage",
234234
"nav_msgs/OccupancyGrid",

rosbridge_library/test/internal/test_ros_loader.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ def test_msg_cache(self):
130130
def test_assorted_msg_names(self):
131131
assortedmsgs = [
132132
"geometry_msgs/Pose",
133-
"actionlib_msgs/GoalStatus",
133+
"action_msgs/GoalStatus",
134134
"geometry_msgs/WrenchStamped",
135135
"stereo_msgs/DisparityImage",
136136
"nav_msgs/OccupancyGrid",

rosbridge_server/test/websocket/advertise_action.test.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import sys
44
import unittest
55

6+
from action_msgs.msg import GoalStatus
67
from example_interfaces.action import Fibonacci
78
from rclpy.action import ActionClient
89
from rclpy.node import Node
@@ -68,6 +69,7 @@ async def test_two_concurrent_calls(self, node: Node, make_client):
6869
"op": "action_result",
6970
"action": "/test_fibonacci_action",
7071
"values": {"sequence": [0, 1, 1, 2]},
72+
"status": GoalStatus.STATUS_SUCCEEDED,
7173
"id": requests[0]["id"],
7274
"result": True,
7375
}
@@ -82,6 +84,7 @@ async def test_two_concurrent_calls(self, node: Node, make_client):
8284
"op": "action_result",
8385
"action": "/test_fibonacci_action",
8486
"values": {"sequence": [0, 1, 1, 2, 3, 5]},
87+
"status": GoalStatus.STATUS_SUCCEEDED,
8588
"id": requests[1]["id"],
8689
"result": True,
8790
}

rosbridge_server/test/websocket/advertise_action_feedback.test.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import sys
44
import unittest
55

6+
from action_msgs.msg import GoalStatus
67
from example_interfaces.action import Fibonacci
78
from rclpy.action import ActionClient
89
from rclpy.node import Node
@@ -74,6 +75,7 @@ async def test_feedback(self, node: Node, make_client):
7475
"op": "action_result",
7576
"action": "/test_fibonacci_action",
7677
"values": {"sequence": [0, 1, 1, 2, 3, 5]},
78+
"status": GoalStatus.STATUS_SUCCEEDED,
7779
"id": requests[0]["id"],
7880
"result": True,
7981
}

0 commit comments

Comments
 (0)