17
17
from ament_index_python .packages import get_package_share_directory
18
18
from launch import LaunchDescription
19
19
from launch .actions import DeclareLaunchArgument
20
+ from launch .actions import OpaqueFunction
20
21
from launch .actions import SetLaunchConfiguration
21
22
from launch .conditions import IfCondition
22
23
from launch .conditions import UnlessCondition
23
24
from launch .substitutions import LaunchConfiguration
24
25
from launch_ros .actions import ComposableNodeContainer
25
26
from launch_ros .actions import LoadComposableNodes
26
27
from launch_ros .descriptions import ComposableNode
28
+ from launch_ros .parameter_descriptions import ParameterFile
27
29
28
30
29
- def generate_launch_description ():
30
- launch_arguments = []
31
-
32
- def add_launch_arg (name : str , default_value = None , description = None ):
33
- # a default_value of None is equivalent to not passing that kwarg at all
34
- launch_arguments .append (
35
- DeclareLaunchArgument (name , default_value = default_value , description = description )
36
- )
37
-
38
- fine_detector_share_dir = get_package_share_directory ("traffic_light_fine_detector" )
39
- classifier_share_dir = get_package_share_directory ("traffic_light_classifier" )
40
- add_launch_arg ("enable_image_decompressor" , "True" )
41
- add_launch_arg ("enable_fine_detection" , "True" )
42
- add_launch_arg ("input/image" , "/sensing/camera/traffic_light/image_raw" )
43
- add_launch_arg ("output/rois" , "/perception/traffic_light_recognition/rois" )
44
- add_launch_arg (
45
- "output/traffic_signals" ,
46
- "/perception/traffic_light_recognition/traffic_signals" ,
47
- )
48
- add_launch_arg (
49
- "output/car/traffic_signals" , "/perception/traffic_light_recognition/car/traffic_signals"
50
- )
51
- add_launch_arg (
52
- "output/pedestrian/traffic_signals" ,
53
- "/perception/traffic_light_recognition/pedestrian/traffic_signals" ,
54
- )
55
-
56
- # traffic_light_fine_detector
57
- add_launch_arg (
58
- "fine_detector_model_path" ,
59
- os .path .join (fine_detector_share_dir , "data" , "tlr_yolox_s.onnx" ),
60
- )
61
- add_launch_arg (
62
- "fine_detector_label_path" ,
63
- os .path .join (fine_detector_share_dir , "data" , "tlr_labels.txt" ),
64
- )
65
- add_launch_arg ("fine_detector_precision" , "fp16" )
66
- add_launch_arg ("fine_detector_score_thresh" , "0.3" )
67
- add_launch_arg ("fine_detector_nms_thresh" , "0.65" )
68
-
69
- add_launch_arg ("approximate_sync" , "False" )
70
-
71
- # traffic_light_classifier
72
- add_launch_arg ("classifier_type" , "1" )
73
- add_launch_arg (
74
- "car_classifier_model_path" ,
75
- os .path .join (classifier_share_dir , "data" , "traffic_light_classifier_efficientNet_b1.onnx" ),
76
- )
77
- add_launch_arg (
78
- "pedestrian_classifier_model_path" ,
79
- os .path .join (
80
- classifier_share_dir , "data" , "pedestrian_traffic_light_classifier_efficientNet_b1.onnx"
81
- ),
82
- )
83
- add_launch_arg (
84
- "car_classifier_label_path" , os .path .join (classifier_share_dir , "data" , "lamp_labels.txt" )
85
- )
86
- add_launch_arg (
87
- "pedestrian_classifier_label_path" ,
88
- os .path .join (classifier_share_dir , "data" , "lamp_labels_ped.txt" ),
89
- )
90
- add_launch_arg ("classifier_precision" , "fp16" )
91
- add_launch_arg ("classifier_mean" , "[123.675, 116.28, 103.53]" )
92
- add_launch_arg ("classifier_std" , "[58.395, 57.12, 57.375]" )
93
- add_launch_arg ("backlight_threshold" , "0.85" )
94
-
95
- add_launch_arg ("use_intra_process" , "False" )
96
- add_launch_arg ("use_multithread" , "False" )
97
-
31
+ def launch_setup (context , * args , ** kwargs ):
98
32
def create_parameter_dict (* args ):
99
33
result = {}
100
34
for x in args :
101
35
result [x ] = LaunchConfiguration (x )
102
36
return result
103
37
38
+ fine_detector_model_param = ParameterFile (
39
+ param_file = LaunchConfiguration ("fine_detector_param_path" ).perform (context ),
40
+ allow_substs = True ,
41
+ )
42
+ car_traffic_light_classifier_model_param = ParameterFile (
43
+ param_file = LaunchConfiguration ("car_classifier_param_path" ).perform (context ),
44
+ allow_substs = True ,
45
+ )
46
+ pedestrian_traffic_light_classifier_model_param = ParameterFile (
47
+ param_file = LaunchConfiguration ("pedestrian_classifier_param_path" ).perform (context ),
48
+ allow_substs = True ,
49
+ )
50
+
104
51
container = ComposableNodeContainer (
105
52
name = "traffic_light_node_container" ,
106
53
namespace = "" ,
@@ -112,19 +59,7 @@ def create_parameter_dict(*args):
112
59
plugin = "traffic_light::TrafficLightClassifierNodelet" ,
113
60
name = "car_traffic_light_classifier" ,
114
61
namespace = "classification" ,
115
- parameters = [
116
- {
117
- "approximate_sync" : LaunchConfiguration ("approximate_sync" ),
118
- "classifier_type" : LaunchConfiguration ("classifier_type" ),
119
- "classify_traffic_light_type" : 0 ,
120
- "classifier_model_path" : LaunchConfiguration ("car_classifier_model_path" ),
121
- "classifier_label_path" : LaunchConfiguration ("car_classifier_label_path" ),
122
- "classifier_precision" : LaunchConfiguration ("classifier_precision" ),
123
- "classifier_mean" : LaunchConfiguration ("classifier_mean" ),
124
- "classifier_std" : LaunchConfiguration ("classifier_std" ),
125
- "backlight_threshold" : LaunchConfiguration ("backlight_threshold" ),
126
- }
127
- ],
62
+ parameters = [car_traffic_light_classifier_model_param ],
128
63
remappings = [
129
64
("~/input/image" , LaunchConfiguration ("input/image" )),
130
65
("~/input/rois" , LaunchConfiguration ("output/rois" )),
@@ -139,23 +74,7 @@ def create_parameter_dict(*args):
139
74
plugin = "traffic_light::TrafficLightClassifierNodelet" ,
140
75
name = "pedestrian_traffic_light_classifier" ,
141
76
namespace = "classification" ,
142
- parameters = [
143
- {
144
- "approximate_sync" : LaunchConfiguration ("approximate_sync" ),
145
- "classifier_type" : LaunchConfiguration ("classifier_type" ),
146
- "classify_traffic_light_type" : 1 ,
147
- "classifier_model_path" : LaunchConfiguration (
148
- "pedestrian_classifier_model_path"
149
- ),
150
- "classifier_label_path" : LaunchConfiguration (
151
- "pedestrian_classifier_label_path"
152
- ),
153
- "classifier_precision" : LaunchConfiguration ("classifier_precision" ),
154
- "classifier_mean" : LaunchConfiguration ("classifier_mean" ),
155
- "classifier_std" : LaunchConfiguration ("classifier_std" ),
156
- "backlight_threshold" : LaunchConfiguration ("backlight_threshold" ),
157
- }
158
- ],
77
+ parameters = [pedestrian_traffic_light_classifier_model_param ],
159
78
remappings = [
160
79
("~/input/image" , LaunchConfiguration ("input/image" )),
161
80
("~/input/rois" , LaunchConfiguration ("output/rois" )),
@@ -214,22 +133,14 @@ def create_parameter_dict(*args):
214
133
condition = IfCondition (LaunchConfiguration ("enable_image_decompressor" )),
215
134
)
216
135
217
- fine_detector_param = create_parameter_dict (
218
- "fine_detector_model_path" ,
219
- "fine_detector_label_path" ,
220
- "fine_detector_precision" ,
221
- "fine_detector_score_thresh" ,
222
- "fine_detector_nms_thresh" ,
223
- )
224
-
225
136
fine_detector_loader = LoadComposableNodes (
226
137
composable_node_descriptions = [
227
138
ComposableNode (
228
139
package = "traffic_light_fine_detector" ,
229
140
plugin = "traffic_light::TrafficLightFineDetectorNodelet" ,
230
141
name = "traffic_light_fine_detector" ,
231
142
namespace = "detection" ,
232
- parameters = [fine_detector_param ],
143
+ parameters = [fine_detector_model_param ],
233
144
remappings = [
234
145
("~/input/image" , LaunchConfiguration ("input/image" )),
235
146
("~/input/rois" , "rough/rois" ),
@@ -245,6 +156,61 @@ def create_parameter_dict(*args):
245
156
condition = IfCondition (LaunchConfiguration ("enable_fine_detection" )),
246
157
)
247
158
159
+ return [container , decompressor_loader , fine_detector_loader ]
160
+
161
+
162
+ def generate_launch_description ():
163
+ launch_arguments = []
164
+
165
+ def add_launch_arg (name : str , default_value = None , description = None ):
166
+ # a default_value of None is equivalent to not passing that kwarg at all
167
+ launch_arguments .append (
168
+ DeclareLaunchArgument (name , default_value = default_value , description = description )
169
+ )
170
+
171
+ fine_detector_share_dir = get_package_share_directory ("traffic_light_fine_detector" )
172
+ classifier_share_dir = get_package_share_directory ("traffic_light_classifier" )
173
+ add_launch_arg ("enable_image_decompressor" , "True" )
174
+ add_launch_arg ("enable_fine_detection" , "True" )
175
+ add_launch_arg ("input/image" , "/sensing/camera/traffic_light/image_raw" )
176
+ add_launch_arg ("output/rois" , "/perception/traffic_light_recognition/rois" )
177
+ add_launch_arg (
178
+ "output/traffic_signals" ,
179
+ "/perception/traffic_light_recognition/traffic_signals" ,
180
+ )
181
+ add_launch_arg (
182
+ "output/car/traffic_signals" , "/perception/traffic_light_recognition/car/traffic_signals"
183
+ )
184
+ add_launch_arg (
185
+ "output/pedestrian/traffic_signals" ,
186
+ "/perception/traffic_light_recognition/pedestrian/traffic_signals" ,
187
+ )
188
+
189
+ # traffic_light_fine_detector
190
+ add_launch_arg (
191
+ "fine_detector_param_path" ,
192
+ os .path .join (fine_detector_share_dir , "config" , "traffic_light_fine_detector.param.yaml" ),
193
+ )
194
+
195
+ # traffic_light_classifier
196
+ add_launch_arg (
197
+ "car_classifier_param_path" ,
198
+ os .path .join (
199
+ classifier_share_dir , "config" , "car_traffic_light_classifier_efficientNet.param.yaml"
200
+ ),
201
+ )
202
+ add_launch_arg (
203
+ "pedestrian_classifier_param_path" ,
204
+ os .path .join (
205
+ classifier_share_dir ,
206
+ "config" ,
207
+ "pedestrian_traffic_light_classifier_efficientNet.param.yaml" ,
208
+ ),
209
+ )
210
+
211
+ add_launch_arg ("use_intra_process" , "False" )
212
+ add_launch_arg ("use_multithread" , "False" )
213
+
248
214
set_container_executable = SetLaunchConfiguration (
249
215
"container_executable" ,
250
216
"component_container" ,
@@ -262,8 +228,6 @@ def create_parameter_dict(*args):
262
228
* launch_arguments ,
263
229
set_container_executable ,
264
230
set_container_mt_executable ,
265
- container ,
266
- decompressor_loader ,
267
- fine_detector_loader ,
231
+ OpaqueFunction (function = launch_setup ),
268
232
]
269
233
)
0 commit comments