Skip to content

Commit d948c72

Browse files
committed
added further debugging
Signed-off-by: Markus Kramer <[email protected]>
1 parent db4dcc7 commit d948c72

File tree

1 file changed

+37
-13
lines changed

1 file changed

+37
-13
lines changed

launch_ros/test/test_cli_remap.py

Lines changed: 37 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -28,20 +28,24 @@ def test_remap_argument(self):
2828
launch_proc_remapped = None
2929
try:
3030
# 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+
)
3138
launch_proc_remapped = subprocess.Popen(
32-
[
33-
'ros2',
34-
'launch',
35-
'demo_nodes_cpp',
36-
'talker_listener_launch.py',
37-
'--remap',
38-
'/chatter:=/chatter_remapped',
39-
],
39+
command_str,
4040
stdout=subprocess.PIPE,
4141
stderr=subprocess.PIPE,
42+
shell=True, # Execute through the shell
43+
executable='/bin/bash' # Be explicit about the shell
4244
)
4345

4446
# Initialize rclpy and create node for checking topics
47+
stdout_log = ''
48+
stderr_log = ''
4549
rclpy.init()
4650
node = None
4751
try:
@@ -69,11 +73,29 @@ def test_remap_argument(self):
6973
final_topics = [name for name,
7074
types in final_topic_names_and_types]
7175

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+
7292
# Verify /chatter_remapped IS in the list
7393
self.assertTrue(
7494
remapped_topic_found,
75-
f'Expected topic "/chatter_remapped" not found within {timeout}s. '
76-
f'Final topics found: {final_topics}'
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}'
7799
)
78100

79101
# Verify /chatter is NOT in the list
@@ -93,13 +115,15 @@ def test_remap_argument(self):
93115

94116
finally:
95117
# Clean up the launch process
96-
if launch_proc_remapped is not None:
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
97120
launch_proc_remapped.terminate()
98121
try:
99122
launch_proc_remapped.wait(timeout=5)
100123
except subprocess.TimeoutExpired:
101-
launch_proc_remapped.kill()
102-
launch_proc_remapped.wait()
124+
if launch_proc_remapped.poll() is None: # Check again if terminate failed
125+
launch_proc_remapped.kill()
126+
launch_proc_remapped.wait()
103127

104128

105129
if __name__ == '__main__':

0 commit comments

Comments
 (0)