Skip to content

Commit 1eeb61a

Browse files
committed
directly test launch_a_launch_file
Signed-off-by: Markus Kramer <[email protected]>
1 parent d948c72 commit 1eeb61a

File tree

1 file changed

+159
-73
lines changed

1 file changed

+159
-73
lines changed

launch_ros/test/test_cli_remap.py

Lines changed: 159 additions & 73 deletions
Original file line numberDiff line numberDiff line change
@@ -12,118 +12,204 @@
1212
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1313
# See the License for the specific language governing permissions and
1414
# limitations under the License.
15-
import subprocess
15+
16+
import logging
17+
import os
18+
import signal
19+
import sys
20+
import threading
1621
import time
1722
import unittest
1823

24+
from ament_index_python.packages import PackageNotFoundError
1925
import rclpy
2026
from rclpy.node import Node
2127

28+
from ros2launch.api.api import (
29+
get_share_file_path_from_package,
30+
launch_a_launch_file,
31+
MultipleLaunchFilesError
32+
)
33+
34+
# Configure basic logging
35+
logging.basicConfig(level=logging.INFO, stream=sys.stderr,
36+
format='%(asctime)s - %(levelname)s - [%(threadName)s] %(message)s')
37+
2238

2339
class TestRemapArgument(unittest.TestCase):
2440
"""Test the --remap command line argument for ros2 launch."""
2541

2642
def test_remap_argument(self):
27-
"""Test that the --remap argument correctly remaps topics."""
28-
launch_proc_remapped = None
29-
try:
30-
# Start the talker_listener launch file with remapping
31-
# Note: Using shell=True to allow sourcing the setup file.
32-
# Ensure ROS_DISTRO is set in the environment where this test runs.
33-
command_str = (
34-
'source /opt/ros/$ROS_DISTRO/setup.bash && '
35-
'ros2 launch demo_nodes_cpp talker_listener_launch.py '
36-
'--remap /chatter:=/chatter_remapped'
37-
)
38-
launch_proc_remapped = subprocess.Popen(
39-
command_str,
40-
stdout=subprocess.PIPE,
41-
stderr=subprocess.PIPE,
42-
shell=True, # Execute through the shell
43-
executable='/bin/bash' # Be explicit about the shell
44-
)
43+
"""Test that the --remap argument correctly remaps topics using direct API call."""
44+
logging.info('Starting test_remap_argument...')
45+
46+
checker_thread = None
47+
# Flag to indicate test success from the checker thread
48+
test_successful = threading.Event()
49+
test_failed_assertion = None
50+
51+
def check_topics_target():
52+
nonlocal test_failed_assertion
53+
logging.info('Checker thread started.')
4554

4655
# Initialize rclpy and create node for checking topics
47-
stdout_log = ''
48-
stderr_log = ''
49-
rclpy.init()
56+
logging.info('Checker thread: Initializing rclpy...')
57+
# Ensure rclpy initializes in this thread context if necessary
58+
# It might inherit context or need specific args depending on ROS setup
59+
try:
60+
rclpy.init()
61+
except Exception as e:
62+
logging.error(f'Checker thread: rclpy.init() failed: {e}', exc_info=True)
63+
# Can't proceed without rclpy
64+
os.kill(os.getpid(), signal.SIGINT) # Signal main thread to stop
65+
return
66+
5067
node = None
5168
try:
69+
logging.info('Checker thread: Creating node __test_remap_checker...')
5270
node = Node('__test_remap_checker', use_global_arguments=False)
71+
logging.info('Checker thread: Node created.')
5372

5473
# Wait for the remapped topic to appear, poll for it
5574
start_time = time.time()
56-
timeout = 15.0 # seconds
75+
timeout = 25.0
5776
remapped_topic_found = False
77+
iteration = 0
5878

79+
logging.info('Checker thread: Starting topic polling loop...')
5980
while time.time() - start_time < timeout:
81+
iteration += 1
82+
# Check if main thread is still alive (optional, sanity check)
83+
6084
topic_names_and_types = node.get_topic_names_and_types()
61-
current_topics = [name for name,
62-
types in topic_names_and_types]
85+
current_topics = [name for name, types in topic_names_and_types]
86+
logging.info(f'Poll {iteration}. Topic count: {len(current_topics)}')
6387

6488
if '/chatter_remapped' in current_topics:
89+
logging.info("Checker thread: Found target topic '/chatter_remapped'!")
6590
remapped_topic_found = True
66-
break # Found the target topic
91+
break
6792

68-
# Avoid busy-waiting
6993
time.sleep(0.5)
7094

71-
# Get the final list of topics after the loop/timeout
72-
final_topic_names_and_types = node.get_topic_names_and_types()
73-
final_topics = [name for name,
74-
types in final_topic_names_and_types]
75-
76-
# Capture stdout and stderr before asserting
77-
if launch_proc_remapped and not remapped_topic_found:
78-
# Ensure the process is terminated before reading streams
79-
if launch_proc_remapped.poll() is None:
80-
launch_proc_remapped.terminate()
81-
try:
82-
launch_proc_remapped.wait(timeout=1)
83-
except subprocess.TimeoutExpired:
84-
if launch_proc_remapped.poll() is None:
85-
launch_proc_remapped.kill()
86-
launch_proc_remapped.wait(timeout=1)
87-
# Now read the streams
88-
stdout_bytes, stderr_bytes = launch_proc_remapped.communicate()
89-
stdout_log = stdout_bytes.decode('utf-8', errors='replace')
90-
stderr_log = stderr_bytes.decode('utf-8', errors='replace')
91-
92-
# Verify /chatter_remapped IS in the list
93-
self.assertTrue(
94-
remapped_topic_found,
95-
f'Expected topic "/chatter_remapped" not found within {timeout}s.\n'
96-
f'Final topics found: {final_topics}\n'
97-
f'--- Launch STDOUT ---\n{stdout_log}\n'
98-
f'--- Launch STDERR ---\n{stderr_log}'
99-
)
95+
log_msg = f'Polling finished. Found remapped topic: {remapped_topic_found}'
96+
logging.info(f'Checker thread: {log_msg}')
10097

101-
# Verify /chatter is NOT in the list
102-
self.assertNotIn(
103-
'/chatter',
104-
final_topics,
105-
f'Unexpectedly found original topic "/chatter". Final topics: {
106-
final_topics}'
107-
)
98+
final_topic_names_and_types = node.get_topic_names_and_types()
99+
final_topics = [name for name, types in final_topic_names_and_types]
100+
logging.info(f'Checker thread: Final topics: {final_topics}')
108101

102+
# Perform assertions within this thread using self.assertX methods
103+
try:
104+
logging.info('Checker thread: Asserting /chatter_remapped is present...')
105+
msg = (
106+
f'Expected topic "/chatter_remapped" not found within {timeout}s. '
107+
f'Final topics: {final_topics}'
108+
)
109+
self.assertTrue(remapped_topic_found, msg)
110+
logging.info('Checker thread: Assertion passed.')
111+
112+
logging.info('Checker thread: Asserting /chatter is NOT present...')
113+
msg = (
114+
f'Unexpectedly found original topic "/chatter". '
115+
f'Final topics: {final_topics}'
116+
)
117+
self.assertNotIn('/chatter', final_topics, msg)
118+
logging.info('Checker thread: Assertion passed.')
119+
120+
# If assertions pass, set the success flag
121+
test_successful.set()
122+
except AssertionError as e:
123+
logging.error(f'Checker thread: Assertion failed: {e}')
124+
test_failed_assertion = e # Store assertion for main thread reporting
125+
except Exception as e:
126+
# Catch and print any other exceptions from the launch thread
127+
logging.error(f'Checker thread: Error during checks: {e}', exc_info=True)
109128
finally:
110129
# Clean up node and rclpy
111130
if node is not None:
131+
logging.info('Checker thread: Destroying node...')
112132
node.destroy_node()
113133
if rclpy.ok():
134+
logging.info('Checker thread: Shutting down rclpy...')
114135
rclpy.shutdown()
136+
logging.info('Checker thread: rclpy cleanup finished.')
137+
138+
# Signal the main thread (running launch) to stop
139+
log_msg = 'Signaling main thread (SIGINT) to stop launch service...'
140+
logging.info(f'Checker thread: {log_msg}')
141+
os.kill(os.getpid(), signal.SIGINT)
142+
logging.info('Checker thread: Exiting.')
143+
144+
# Main thread execution starts here
145+
try:
146+
logging.info('Main thread: Creating checker thread...')
147+
# Make checker non-daemon so main thread waits for it via join()
148+
checker_thread = threading.Thread(target=check_topics_target, daemon=False)
149+
logging.info('Main thread: Starting checker thread...')
150+
checker_thread.start()
115151

152+
launch_return_code = None
153+
try:
154+
# Find launch file (moved here from background thread)
155+
logging.info('Main thread: Finding launch file...')
156+
package = 'demo_nodes_cpp'
157+
file = 'talker_listener_launch.py'
158+
launch_file_path = get_share_file_path_from_package(
159+
package_name=package, file_name=file
160+
)
161+
logging.info(f'Main thread: Found launch file: {launch_file_path}')
162+
163+
remap_rules = ['/chatter:=/chatter_remapped']
164+
165+
# Call launch_a_launch_file in the main thread
166+
logging.info('Main thread: Calling launch_a_launch_file (blocking)...')
167+
launch_return_code = launch_a_launch_file(
168+
launch_file_path=launch_file_path,
169+
launch_file_arguments=[],
170+
noninteractive=True,
171+
debug=False,
172+
remap_rules=remap_rules
173+
)
174+
log_msg = f'launch_a_launch_file returned with code: {launch_return_code}'
175+
logging.info(f'Main thread: {log_msg}')
176+
177+
except (PackageNotFoundError, FileNotFoundError, MultipleLaunchFilesError) as e:
178+
logging.error(f'Main thread: Error finding launch file: {e}')
179+
# Ensure checker thread is stopped if launch setup failed
180+
if checker_thread and checker_thread.is_alive():
181+
log_msg = 'Signaling checker thread to stop due to launch error...'
182+
logging.info(f'Main thread: {log_msg}')
183+
# Ideally have a cleaner way, but SIGINT might work if thread handles it
184+
# Or rely on join timeout below
185+
except Exception as e:
186+
logging.error(f'Main thread: Error during launch: {e}', exc_info=True)
187+
finally:
188+
# Wait for the checker thread to finish its checks and signal
189+
logging.info('Main thread: Joining checker thread...')
190+
if checker_thread is not None:
191+
checker_thread.join(timeout=30.0) # Increased timeout to allow checks
192+
if checker_thread.is_alive():
193+
logging.warning('Checker thread is still alive after timeout.')
194+
else:
195+
logging.info('Checker thread joined successfully.')
196+
197+
# Outer try block needs a finally or except
198+
# Re-adding the final check logic here which belongs to the outer try
116199
finally:
117-
# Clean up the launch process
118-
if launch_proc_remapped is not None and launch_proc_remapped.poll() is None:
119-
# Ensure process is terminated if not already done for logging
120-
launch_proc_remapped.terminate()
121-
try:
122-
launch_proc_remapped.wait(timeout=5)
123-
except subprocess.TimeoutExpired:
124-
if launch_proc_remapped.poll() is None: # Check again if terminate failed
125-
launch_proc_remapped.kill()
126-
launch_proc_remapped.wait()
200+
# After launch and checker thread have finished, check assertion results
201+
logging.info('Main thread: Checking test results...')
202+
if test_failed_assertion:
203+
# Re-raise the assertion failure captured from the checker thread
204+
raise test_failed_assertion
205+
elif not test_successful.is_set():
206+
# Fail if the checker thread didn't explicitly signal success
207+
msg = 'Test failed: Checker thread did not signal success'
208+
self.fail(msg)
209+
else:
210+
logging.info('Main thread: Test success confirmed by checker thread.')
211+
212+
logging.info('Main thread: Test finished.')
127213

128214

129215
if __name__ == '__main__':

0 commit comments

Comments
 (0)