Skip to content

Commit

Permalink
Revamp the test_load_composable_nodes test. (#403)
Browse files Browse the repository at this point in the history
* Revamp the test_load_composable_nodes test.

In particular, it made little sense to do an rclpy.init
in a class that inherited from rclpy.node.Node.  Instead,
flip this around and make the mock_component_container
responsible for creating the context, doing rclpy.init,
creating the node, spinning the executor, and tearing it
all down.  Note that this uses the new rclpy.init
context manager as well, which reduces the amount of code
we need here.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Jul 9, 2024
1 parent 5856482 commit dbc2bbc
Showing 1 changed file with 16 additions and 24 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,31 +44,18 @@

class MockComponentContainer(rclpy.node.Node):

def __init__(self):
def __init__(self, context):
# List of LoadNode requests received
self.requests = []

self._context = rclpy.context.Context()
rclpy.init(context=self._context)

super().__init__(TEST_CONTAINER_NAME, context=self._context)
super().__init__(TEST_CONTAINER_NAME, context=context)

self.load_node_service = self.create_service(
LoadNode,
'~/_container/load_node',
self.load_node_callback
)

self._executor = rclpy.executors.SingleThreadedExecutor(context=self._context)

# Start spinning in a thread
self._thread = threading.Thread(
target=rclpy.spin,
args=(self, self._executor),
daemon=True
)
self._thread.start()

def load_node_callback(self, request, response):
self.requests.append(request)
response.success = True
Expand All @@ -79,12 +66,6 @@ def load_node_callback(self, request, response):
response.unique_id = len(self.requests)
return response

def shutdown(self):
self._executor.shutdown()
rclpy.shutdown(context=self._context)
self.destroy_node()
self._thread.join()


def _assert_launch_no_errors(actions):
ld = LaunchDescription(actions)
Expand Down Expand Up @@ -122,9 +103,20 @@ def _load_composable_node(

@pytest.fixture
def mock_component_container():
container = MockComponentContainer()
yield container
container.shutdown()
context = rclpy.context.Context()
with rclpy.init(context=context):
executor = rclpy.executors.SingleThreadedExecutor(context=context)

container = MockComponentContainer(context)
executor.add_node(container)

# Start spinning in a thread
thread = threading.Thread(target=lambda executor: executor.spin(), args=(executor,))
thread.start()
yield container
executor.remove_node(container)
executor.shutdown()
thread.join()


def test_load_node(mock_component_container):
Expand Down

0 comments on commit dbc2bbc

Please sign in to comment.