|
7 | 7 | import rclpy
|
8 | 8 | from action_msgs.msg import GoalStatus
|
9 | 9 | from example_interfaces.action._fibonacci import Fibonacci_FeedbackMessage
|
10 |
| -from rclpy.executors import SingleThreadedExecutor |
| 10 | +from rclpy.executors import MultiThreadedExecutor |
11 | 11 | from rclpy.node import Node
|
12 | 12 | from rclpy.qos import DurabilityPolicy, QoSProfile, ReliabilityPolicy
|
13 | 13 | from rosbridge_library.capabilities.action_feedback import ActionFeedback
|
|
25 | 25 | class TestActionCapabilities(unittest.TestCase):
|
26 | 26 | def setUp(self):
|
27 | 27 | rclpy.init()
|
28 |
| - self.executor = SingleThreadedExecutor() |
| 28 | + self.executor = MultiThreadedExecutor() |
29 | 29 | self.node = Node("test_action_capabilities")
|
30 | 30 | self.executor.add_node(self.node)
|
31 | 31 |
|
@@ -295,7 +295,6 @@ def test_cancel_advertised_action(self):
|
295 | 295 | self.assertEqual(self.received_message["values"]["sequence"], [])
|
296 | 296 | self.assertEqual(self.received_message["status"], GoalStatus.STATUS_CANCELED)
|
297 | 297 |
|
298 |
| - @unittest.skip("Currently raises an exception not catchable by unittest, need to fix this") |
299 | 298 | def test_unadvertise_action(self):
|
300 | 299 | # Advertise the action
|
301 | 300 | action_path = "/fibonacci_action_4"
|
@@ -340,8 +339,6 @@ def test_unadvertise_action(self):
|
340 | 339 | self.assertTrue("id" in self.received_message)
|
341 | 340 |
|
342 | 341 | # Now unadvertise the action
|
343 |
| - # TODO: This raises an exception, likely because of the following rclpy issue: |
344 |
| - # https://github.com/ros2/rclpy/issues/1098 |
345 | 342 | unadvertise_msg = loads(dumps({"op": "unadvertise_action", "action": action_path}))
|
346 | 343 | self.received_message = None
|
347 | 344 | self.unadvertise.unadvertise_action(unadvertise_msg)
|
|
0 commit comments