Skip to content

Commit a05946f

Browse files
committed
Add the tests for composition API.
Signed-off-by: Zhen Ju <[email protected]>
1 parent 3812b43 commit a05946f

File tree

4 files changed

+201
-3
lines changed

4 files changed

+201
-3
lines changed
Lines changed: 198 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,198 @@
1+
# Copyright 2020 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import unittest
16+
from multiprocessing import Process
17+
18+
import rclpy
19+
from rclpy.executors import SingleThreadedExecutor, MultiThreadedExecutor
20+
from rclpy.node import Node
21+
from rclpy.client import Client
22+
from composition_interfaces.srv import ListNodes, LoadNode, UnloadNode
23+
from rclpy_components.component_manager import ComponentManager
24+
25+
RCLPY_COMPOSITION = 'py_composition'
26+
RCLPY_COMPOSITION_TALKER = 'py_composition::Talker'
27+
RCLPY_COMPOSITION_LISTENER = 'py_composition::Listener'
28+
29+
30+
def run_container(container_name, multi_thread):
31+
rclpy.init()
32+
if multi_thread:
33+
executor = MultiThreadedExecutor()
34+
else:
35+
executor = SingleThreadedExecutor()
36+
37+
component_manager = ComponentManager(executor, container_name)
38+
executor.add_node(component_manager)
39+
try:
40+
executor.spin()
41+
except Exception as e:
42+
print(e)
43+
pass
44+
45+
component_manager.destroy_node()
46+
rclpy.shutdown()
47+
48+
49+
class TestComponentManager(unittest.TestCase):
50+
helper_node: Node = None
51+
container_process: Process = None
52+
53+
container_name = 'TestComponentManager'
54+
# service names & clients will be generated with container_name
55+
load_node_svc_name = ""
56+
unload_node_svc_name = ""
57+
list_node_svc_name = ""
58+
load_cli: Client = None
59+
unload_cli: Client = None
60+
list_cli: Client = None
61+
62+
use_multi_threaded_executor = False
63+
64+
@classmethod
65+
def setUpClass(cls):
66+
cls.load_node_svc_name = f'{cls.container_name}/_container/load_node'
67+
cls.unload_node_svc_name = f'{cls.container_name}/_container/unload_node'
68+
cls.list_node_svc_name = f'{cls.container_name}/_container/list_nodes'
69+
70+
# Start the test component manager in the background
71+
cls.container_process = Process(target=run_container,
72+
args=(cls.container_name, cls.use_multi_threaded_executor))
73+
cls.container_process.start()
74+
75+
# Setup the helper_node, which will help create client and test the services
76+
rclpy.init()
77+
cls.helper_node = rclpy.create_node('helper_node')
78+
cls.load_cli = cls.helper_node.create_client(LoadNode, cls.load_node_svc_name)
79+
cls.unload_cli = cls.helper_node.create_client(UnloadNode, cls.unload_node_svc_name)
80+
cls.list_cli = cls.helper_node.create_client(ListNodes, cls.list_node_svc_name)
81+
82+
@classmethod
83+
def tearDownClass(cls):
84+
cls.container_process.terminate()
85+
cls.load_cli.destroy()
86+
cls.unload_cli.destroy()
87+
cls.list_cli.destroy()
88+
cls.helper_node.destroy_node()
89+
rclpy.shutdown()
90+
91+
@classmethod
92+
def load_node(cls, package_name, plugin_name, node_name="", node_namespace=""):
93+
if not cls.load_cli.wait_for_service(timeout_sec=5.0):
94+
raise RuntimeError(f'No load service found in /{cls.container_name}')
95+
96+
load_req = LoadNode.Request()
97+
load_req.package_name = package_name
98+
load_req.plugin_name = plugin_name
99+
100+
if node_name != "":
101+
load_req.node_name = node_name
102+
if node_namespace != "":
103+
load_req.node_namespace = node_namespace
104+
105+
future = cls.load_cli.call_async(load_req)
106+
rclpy.spin_until_future_complete(cls.helper_node, future)
107+
return future.result()
108+
109+
@classmethod
110+
def unload_node(cls, unique_id):
111+
if not cls.unload_cli.wait_for_service(timeout_sec=5.0):
112+
raise RuntimeError(f'No unload service found in /{cls.container_name}')
113+
114+
unload_req = UnloadNode.Request()
115+
unload_req.unique_id = unique_id
116+
117+
future = cls.unload_cli.call_async(unload_req)
118+
rclpy.spin_until_future_complete(cls.helper_node, future)
119+
return future.result()
120+
121+
@classmethod
122+
def list_nodes(cls):
123+
if not cls.list_cli.wait_for_service(timeout_sec=5.0):
124+
raise RuntimeError(f'No list service found in {cls.container_name}')
125+
list_req = ListNodes.Request()
126+
future = cls.list_cli.call_async(list_req)
127+
rclpy.spin_until_future_complete(cls.helper_node, future)
128+
return future.result()
129+
130+
def load_node_test(self):
131+
load_res = self.__class__.load_node(RCLPY_COMPOSITION, RCLPY_COMPOSITION_LISTENER)
132+
assert load_res.success is True
133+
assert load_res.error_message == ""
134+
assert load_res.unique_id == 1
135+
assert load_res.full_node_name == '/listener'
136+
137+
node_name = "renamed_listener"
138+
node_ns = 'testing_ns'
139+
remap_load_res = self.__class__.load_node(
140+
RCLPY_COMPOSITION, RCLPY_COMPOSITION_TALKER, node_name=node_name,
141+
node_namespace=node_ns)
142+
assert remap_load_res.success is True
143+
assert remap_load_res.error_message == ""
144+
assert remap_load_res.unique_id == 2
145+
assert remap_load_res.full_node_name == f'/{node_ns}/{node_name}'
146+
147+
list_res: ListNodes.Response = self.__class__.list_nodes()
148+
assert len(list_res.unique_ids) == len(list_res.full_node_names) == 2
149+
150+
def unload_node_test(self):
151+
if not self.__class__.unload_cli.wait_for_service(timeout_sec=5.0):
152+
raise RuntimeError(f'no unload service found in {self.__class__.container_name}')
153+
154+
unload_res: UnloadNode.Response = self.__class__.unload_node(1)
155+
assert unload_res.success is True
156+
assert unload_res.error_message == ""
157+
158+
# Should be only 1 node left
159+
list_res: ListNodes.Response = self.__class__.list_nodes()
160+
assert len(list_res.full_node_names) == len(list_res.unique_ids) == 1
161+
162+
# The index definitely won't exist
163+
unload_res: UnloadNode.Response = self.__class__.unload_node(1000)
164+
assert unload_res.error_message != ""
165+
assert unload_res.success is False
166+
list_res: ListNodes.Response = self.__class__.list_nodes()
167+
assert len(list_res.full_node_names) == len(list_res.unique_ids) == 1
168+
169+
# Unload the last node
170+
unload_req = UnloadNode.Request()
171+
unload_req.unique_id = 2
172+
future = self.__class__.unload_cli.call_async(unload_req)
173+
rclpy.spin_until_future_complete(self.__class__.helper_node, future)
174+
unload_res: UnloadNode.Response = future.result()
175+
assert unload_res.success is True
176+
assert unload_res.error_message == ""
177+
178+
# Won't be any node in the container
179+
list_res: ListNodes.Response = self.__class__.list_nodes()
180+
assert len(list_res.full_node_names) == len(list_res.unique_ids) == 0
181+
182+
def list_nodes_test(self):
183+
container_name = self.__class__.container_name
184+
print(f'{container_name}: list_nodes tested within test_load_node and test_unload_node')
185+
186+
def test_composition_api(self):
187+
self.load_node_test()
188+
self.unload_node_test()
189+
self.list_nodes_test()
190+
191+
192+
class TestComponentManagerMT(TestComponentManager):
193+
use_multi_threaded_executor = True
194+
container_name = 'TestComponentManagerMT'
195+
196+
197+
if __name__ == '__main__':
198+
unittest.main()

rclpy_components/test/test_copyright.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# Copyright 2015 Open Source Robotics Foundation, Inc.
1+
# Copyright 2020 Open Source Robotics Foundation, Inc.
22
#
33
# Licensed under the Apache License, Version 2.0 (the "License");
44
# you may not use this file except in compliance with the License.

rclpy_components/test/test_flake8.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# Copyright 2017 Open Source Robotics Foundation, Inc.
1+
# Copyright 2020 Open Source Robotics Foundation, Inc.
22
#
33
# Licensed under the Apache License, Version 2.0 (the "License");
44
# you may not use this file except in compliance with the License.

rclpy_components/test/test_pep257.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
# Copyright 2015 Open Source Robotics Foundation, Inc.
1+
# Copyright 2020 Open Source Robotics Foundation, Inc.
22
#
33
# Licensed under the Apache License, Version 2.0 (the "License");
44
# you may not use this file except in compliance with the License.

0 commit comments

Comments
 (0)