@@ -34,6 +34,8 @@ def get_lidar_make(sensor_name):
34
34
return "Hesai" , ".csv"
35
35
elif sensor_name [:3 ].lower () in ["hdl" , "vlp" , "vls" ]:
36
36
return "Velodyne" , ".yaml"
37
+ elif sensor_name .lower () in ["helios" , "bpearl" ]:
38
+ return "Robosense" , None
37
39
return "unrecognized_sensor_model"
38
40
39
41
@@ -75,21 +77,28 @@ def create_parameter_dict(*args):
75
77
nebula_decoders_share_dir = get_package_share_directory ("nebula_decoders" )
76
78
77
79
# Calibration file
78
- sensor_calib_fp = os .path .join (
79
- nebula_decoders_share_dir ,
80
- "calibration" ,
81
- sensor_make .lower (),
82
- sensor_model + sensor_extension ,
83
- )
84
- assert os .path .exists (
85
- sensor_calib_fp
86
- ), "Sensor calib file under calibration/ was not found: {}" .format (sensor_calib_fp )
80
+ if sensor_extension is not None : # Velodyne and Hesai
81
+ sensor_calib_fp = os .path .join (
82
+ nebula_decoders_share_dir ,
83
+ "calibration" ,
84
+ sensor_make .lower (),
85
+ sensor_model + sensor_extension ,
86
+ )
87
+ assert os .path .exists (
88
+ sensor_calib_fp
89
+ ), "Sensor calib file under calibration/ was not found: {}" .format (sensor_calib_fp )
90
+ else : # Robosense
91
+ sensor_calib_fp = ""
87
92
88
93
# Pointcloud preprocessor parameters
89
94
distortion_corrector_node_param = ParameterFile (
90
95
param_file = LaunchConfiguration ("distortion_correction_node_param_path" ).perform (context ),
91
96
allow_substs = True ,
92
97
)
98
+ ring_outlier_filter_node_param = ParameterFile (
99
+ param_file = LaunchConfiguration ("ring_outlier_filter_node_param_path" ).perform (context ),
100
+ allow_substs = True ,
101
+ )
93
102
94
103
nodes = []
95
104
@@ -129,6 +138,8 @@ def create_parameter_dict(*args):
129
138
# cSpell:ignore knzo25
130
139
# TODO(knzo25): fix the remapping once nebula gets updated
131
140
("velodyne_points" , "pointcloud_raw_ex" ),
141
+ # ("robosense_points", "pointcloud_raw_ex"), #for robosense
142
+ # ("pandar_points", "pointcloud_raw_ex"), # for hesai
132
143
],
133
144
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
134
145
)
@@ -199,11 +210,9 @@ def create_parameter_dict(*args):
199
210
200
211
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
201
212
if LaunchConfiguration ("output_as_sensor_frame" ).perform (context ).lower () == "true" :
202
- ring_outlier_filter_parameters = {"output_frame" : LaunchConfiguration ("frame_id" )}
213
+ ring_outlier_output_frame = {"output_frame" : LaunchConfiguration ("frame_id" )}
203
214
else :
204
- ring_outlier_filter_parameters = {
205
- "output_frame" : ""
206
- } # keep the output frame as the input frame
215
+ ring_outlier_output_frame = {"output_frame" : "" } # keep the output frame as the input frame
207
216
nodes .append (
208
217
ComposableNode (
209
218
package = "autoware_pointcloud_preprocessor" ,
@@ -213,7 +222,7 @@ def create_parameter_dict(*args):
213
222
("input" , "rectified/pointcloud_ex" ),
214
223
("output" , "pointcloud_before_sync" ),
215
224
],
216
- parameters = [ring_outlier_filter_parameters ],
225
+ parameters = [ring_outlier_filter_node_param , ring_outlier_output_frame ],
217
226
extra_arguments = [{"use_intra_process_comms" : LaunchConfiguration ("use_intra_process" )}],
218
227
)
219
228
)
@@ -312,6 +321,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
312
321
),
313
322
description = "path to parameter file of distortion correction node" ,
314
323
)
324
+ add_launch_arg (
325
+ "ring_outlier_filter_node_param_path" ,
326
+ os .path .join (
327
+ common_sensor_share_dir ,
328
+ "config" ,
329
+ "ring_outlier_filter_node.param.yaml" ,
330
+ ),
331
+ description = "path to parameter file of ring outlier filter node" ,
332
+ )
315
333
316
334
set_container_executable = SetLaunchConfiguration (
317
335
"container_executable" ,
0 commit comments