1
+ import unittest
2
+
3
+ import launch
4
+ import launch_ros
5
+ import launch_testing
6
+ from pprint import pprint
7
+ from launch .substitutions import LaunchConfiguration , PathJoinSubstitution
8
+ from ament_index_python .packages import get_package_share_directory
9
+
10
+ import pytest
11
+
12
+ @pytest .mark .rostest
13
+ def generate_test_description ():
14
+ test_node = launch_ros .actions .Node (
15
+ executable = PathJoinSubstitution ([LaunchConfiguration ('test_binary_dir' ), 'map_test.py' ]),
16
+ output = 'screen' ,
17
+ parameters = [
18
+ {"min_lines" :3 },
19
+ {"expected_pose" :"0.73 0.11 1.0 0.98 -0.01 -0.18 0.07" },
20
+ {"expect" : "100 -0.27 0.82 -1.77 -38.17 -0.15 -149.53,\
21
+ 103 -1.86 -0.59 -1.04 1.70 -23.72 -165.87,\
22
+ 106 0.22 -0.0 -0.0 -0.9 0.24 0.15,\
23
+ 107 0.2 -0.28 -0.0 -0.94 1.49 -0.92,\
24
+ 110 0.7 0.05 0.0 3.38 -4.9 -90,\
25
+ 111 0.0 0.0 0.0 0.0 0.0 0.0,\
26
+ 112 0.0 -0.3 0.0 -1.0 0.48 -0.05" }
27
+ ],
28
+ )
29
+
30
+ rosbag_player = launch .actions .ExecuteProcess (
31
+ cmd = ['ros2' , 'bag' , 'play' , '-l' , PathJoinSubstitution ([LaunchConfiguration ('test_binary_dir' ), 'aruco_transforms.db3' ])],
32
+ output = 'screen'
33
+ )
34
+
35
+ static_tranform_publisher = launch_ros .actions .Node (
36
+ package = 'tf2_ros' ,
37
+ executable = 'static_transform_publisher' ,
38
+ name = 'camera_base' ,
39
+ arguments = "0.0 0.0 0.0 0.0 0.0 0.0 1.0 base_link raspicam" .split ()
40
+ )
41
+
42
+
43
+ # aruco_detect = launch_ros.actions.Node(
44
+ # package='aruco_detect',
45
+ # namespace='aruco_detect',
46
+ # executable='aruco_detect',
47
+ # name='aruco_detect',
48
+ # parameters=[
49
+ # {"image_transport":'raw'},
50
+ # {"publish_images":True},
51
+ # {"fiducial_len":0.145},
52
+ # ],
53
+ # #Not sure if the remapping is working properly TODO
54
+ # remappings=[
55
+ # ('camera/compressed', 'camera/image/compressed'),
56
+ # ('fiducial_vertices', '/fiducial_vertices'),
57
+ # ('fiducial_transforms', '/fiducial_transforms')
58
+ # ]
59
+ # )
60
+
61
+ fiducial_slam = launch_ros .actions .Node (
62
+ package = 'fiducial_slam' ,
63
+ executable = 'fiducial_slam_node' ,
64
+ name = 'fiducial_slam_node' ,
65
+ parameters = [
66
+ {"map_frame" :'map' },
67
+ {"odom_frame" :"" },
68
+ {"base_frame" :"base_link" },
69
+ {"future_date_transforms" , "0.0" },
70
+ {"publish_6dof_pose" ,"true" },
71
+ {"map_file" :"/dev/null" },
72
+ {"initial_map_file" : PathJoinSubstitution ([LaunchConfiguration ('test_binary_dir' ), '111_initial_map.txt' ])},
73
+ {"do_rotation" :"true" }
74
+ ],
75
+ )
76
+
77
+
78
+ return launch .LaunchDescription ([
79
+ launch .actions .DeclareLaunchArgument (name = 'test_binary_dir' , # From https://github.com/ros-planning/moveit2/blob/1e1337b46daed0aaa1252b87367c1824f46c9b1a/moveit_ros/moveit_servo/test/launch/servo_launch_test_common.py#L92
80
+ description = 'Binary directory of package containing test executables' ),
81
+ # other fixture actions
82
+ fiducial_slam ,
83
+ test_node ,
84
+ rosbag_player ,
85
+ static_tranform_publisher ,
86
+ #launch_testing.util.KeepAliveProc(), # From https://github.com/ros2/geometry2/blob/a1be44fdbd8c032351ffd3ddff8467d000f4c6d7/test_tf2/test/buffer_client_tester.launch.py#L39
87
+ launch_testing .actions .ReadyToTest (),
88
+ ]), locals ()
89
+
90
+
91
+ class TestTestTermination (unittest .TestCase ):
92
+ def test_termination (self , test_node , proc_output , proc_info ):
93
+ proc_info .assertWaitForShutdown (process = test_node , timeout = (30 ))
94
+
95
+ @launch_testing .post_shutdown_test ()
96
+ class TestProcessOutput (unittest .TestCase ):
97
+ def test_no_failed_tests (self , proc_output , proc_info , test_node ):
98
+ # Check that process exits with code -15 code: termination request, sent to the program
99
+ pprint (proc_info [test_node ].returncode )
100
+ number_of_failed_tests = 0
101
+ launch_testing .asserts .assertExitCodes (proc_info , [number_of_failed_tests ], process = test_node )
0 commit comments