Skip to content

Commit

Permalink
Make nodes context-manager aware. (#1293)
Browse files Browse the repository at this point in the history
* Make nodes context-manager aware.

This way it is much easier to create examples that properly
clean up after themselves.

* Add in testing for context managers.

Signed-off-by: Chris Lalancette <clalancette@gmail.com>
  • Loading branch information
clalancette authored Jun 4, 2024
1 parent ffcdae9 commit 793e3a2
Show file tree
Hide file tree
Showing 4 changed files with 53 additions and 0 deletions.
12 changes: 12 additions & 0 deletions rclpy/rclpy/node.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import math
import time

from types import TracebackType
from typing import Any
from typing import Callable
from typing import Dict
Expand Down Expand Up @@ -2295,3 +2296,14 @@ def wait_for_node(
flag = fully_qualified_node_name in fully_qualified_node_names
time.sleep(0.1)
return flag

def __enter__(self) -> 'Node':
return self

def __exit__(
self,
exc_type: Optional[Type[BaseException]],
exc_val: Optional[BaseException],
exc_tb: Optional[TracebackType],
) -> None:
self.destroy_node()
11 changes: 11 additions & 0 deletions rclpy/test/test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -2528,6 +2528,17 @@ def test_use_sim_time(self):
finally:
rclpy.shutdown(context=context)

def test_node_context_manager(self):
context = rclpy.context.Context()
rclpy.init(context=context)

try:
with rclpy.create_node('test_node_no_sim', context=context) as node:
self.assertTrue(node.has_parameter(USE_SIM_TIME_NAME))
self.assertFalse(node.get_parameter(USE_SIM_TIME_NAME).value)
finally:
rclpy.shutdown(context=context)


def test_node_resolve_name():
context = rclpy.Context()
Expand Down
11 changes: 11 additions & 0 deletions rclpy/test/test_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,5 +126,16 @@ def test_wait_for_all_acked(self):
sub.destroy()


def test_publisher_context_manager():
rclpy.init()
try:
with rclpy.create_node('pub_node', namespace='/pub_node_ns') as node:
with node.create_publisher(BasicTypes, 'chatter', 1) as pub:
assert pub.get_subscription_count() == 0

finally:
rclpy.shutdown()


if __name__ == '__main__':
unittest.main()
19 changes: 19 additions & 0 deletions rclpy/test/test_subscription.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,25 @@ def test_subscription_callback_type():
node.destroy_node()


def test_subscription_context_manager():
node = Node('test_node', namespace='test_subscription/test_subscription_callback_type')
with node.create_subscription(
msg_type=Empty,
topic='test_subscription/test_subscription_callback_type/topic',
qos_profile=10,
callback=lambda _: None) as sub:
assert sub._callback_type == Subscription.CallbackType.MessageOnly

with node.create_subscription(
msg_type=Empty,
topic='test_subscription/test_subscription_callback_type/topic',
qos_profile=10,
callback=lambda _, _2: None) as sub:
assert sub._callback_type == Subscription.CallbackType.WithMessageInfo

node.destroy_node()


def test_subscription_publisher_count():
topic_name = 'test_subscription/test_subscription_publisher_count/topic'
node = Node('test_node', namespace='test_subscription/test_subscription_publisher_count')
Expand Down

0 comments on commit 793e3a2

Please sign in to comment.