Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit 0e92a83

Browse files
authored
Merge branch 'main' into feature/pointcloud_preprocessor_launch_load_param
2 parents 56e9e4e + a5e7a2d commit 0e92a83

File tree

7 files changed

+124
-18
lines changed

7 files changed

+124
-18
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
/**:
2+
ros__parameters:
3+
distance_ratio: 1.03
4+
object_length_threshold: 0.1
5+
num_points_threshold: 4
6+
max_rings_num: 128
7+
max_points_num_per_ring: 4000
8+
publish_outlier_pointcloud: false
9+
min_azimuth_deg: 0.0
10+
max_azimuth_deg: 360.0
11+
max_distance: 12.0
12+
vertical_bins: 128
13+
horizontal_bins: 36
14+
noise_threshold: 2

common_sensor_launch/launch/nebula_node_container.launch.py

+32-14
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@ def get_lidar_make(sensor_name):
3434
return "Hesai", ".csv"
3535
elif sensor_name[:3].lower() in ["hdl", "vlp", "vls"]:
3636
return "Velodyne", ".yaml"
37+
elif sensor_name.lower() in ["helios", "bpearl"]:
38+
return "Robosense", None
3739
return "unrecognized_sensor_model"
3840

3941

@@ -75,21 +77,28 @@ def create_parameter_dict(*args):
7577
nebula_decoders_share_dir = get_package_share_directory("nebula_decoders")
7678

7779
# 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 = ""
8792

8893
# Pointcloud preprocessor parameters
8994
distortion_corrector_node_param = ParameterFile(
9095
param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context),
9196
allow_substs=True,
9297
)
98+
ring_outlier_filter_node_param = ParameterFile(
99+
param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(context),
100+
allow_substs=True,
101+
)
93102

94103
nodes = []
95104

@@ -129,6 +138,8 @@ def create_parameter_dict(*args):
129138
# cSpell:ignore knzo25
130139
# TODO(knzo25): fix the remapping once nebula gets updated
131140
("velodyne_points", "pointcloud_raw_ex"),
141+
# ("robosense_points", "pointcloud_raw_ex"), #for robosense
142+
# ("pandar_points", "pointcloud_raw_ex"), # for hesai
132143
],
133144
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
134145
)
@@ -199,11 +210,9 @@ def create_parameter_dict(*args):
199210

200211
# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
201212
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")}
203214
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
207216
nodes.append(
208217
ComposableNode(
209218
package="autoware_pointcloud_preprocessor",
@@ -213,7 +222,7 @@ def create_parameter_dict(*args):
213222
("input", "rectified/pointcloud_ex"),
214223
("output", "pointcloud_before_sync"),
215224
],
216-
parameters=[ring_outlier_filter_parameters],
225+
parameters=[ring_outlier_filter_node_param, ring_outlier_output_frame],
217226
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
218227
)
219228
)
@@ -312,6 +321,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
312321
),
313322
description="path to parameter file of distortion correction node",
314323
)
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+
)
315333

316334
set_container_executable = SetLaunchConfiguration(
317335
"container_executable",
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
<launch>
2+
<!-- Params -->
3+
<arg name="launch_driver" default="true"/>
4+
<arg name="model" default="Bpearl"/>
5+
<arg name="max_range" default="30.0"/>
6+
<arg name="min_range" default="0.4"/>
7+
<arg name="sensor_frame" default="robosense"/>
8+
<arg name="return_mode" default="SingleStrongest"/>
9+
<arg name="sensor_ip" default="192.168.1.200"/>
10+
<arg name="host_ip" default="255.255.255.255"/>
11+
<arg name="data_port" default="2368"/>
12+
<arg name="gnss_port" default="7788"/>
13+
<arg name="scan_phase" default="0.0"/>
14+
<arg name="cloud_min_angle" default="0"/>
15+
<arg name="cloud_max_angle" default="360"/>
16+
<arg name="vehicle_mirror_param_file"/>
17+
<arg name="container_name" default="robosense_node_container"/>
18+
19+
<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
20+
<arg name="launch_driver" value="$(var launch_driver)"/>
21+
<arg name="sensor_model" value="$(var model)"/>
22+
<arg name="return_mode" value="$(var return_mode)"/>
23+
<arg name="max_range" value="$(var max_range)"/>
24+
<arg name="min_range" value="$(var min_range)"/>
25+
<arg name="frame_id" value="$(var sensor_frame)"/>
26+
<arg name="sensor_ip" value="$(var sensor_ip)"/>
27+
<arg name="host_ip" value="$(var host_ip)"/>
28+
<arg name="data_port" value="$(var data_port)"/>
29+
<arg name="scan_phase" value="$(var scan_phase)"/>
30+
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
31+
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
32+
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
33+
<arg name="use_intra_process" value="true"/>
34+
<arg name="use_multithread" value="false"/>
35+
<arg name="container_name" value="$(var container_name)"/>
36+
</include>
37+
</launch>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
<launch>
2+
<!-- Params -->
3+
<arg name="launch_driver" default="true"/>
4+
<arg name="model" default="Helios"/>
5+
<arg name="max_range" default="150.0"/>
6+
<arg name="min_range" default="0.2"/>
7+
<arg name="sensor_frame" default="robosense"/>
8+
<arg name="return_mode" default="SingleStrongest"/>
9+
<arg name="sensor_ip" default="192.168.1.200"/>
10+
<arg name="host_ip" default="255.255.255.255"/>
11+
<arg name="data_port" default="2368"/>
12+
<arg name="gnss_port" default="7788"/>
13+
<arg name="scan_phase" default="0.0"/>
14+
<arg name="cloud_min_angle" default="0"/>
15+
<arg name="cloud_max_angle" default="360"/>
16+
<arg name="vehicle_mirror_param_file"/>
17+
<arg name="container_name" default="robosense_node_container"/>
18+
19+
<include file="$(find-pkg-share common_sensor_launch)/launch/nebula_node_container.launch.py">
20+
<arg name="launch_driver" value="$(var launch_driver)"/>
21+
<arg name="sensor_model" value="$(var model)"/>
22+
<arg name="return_mode" value="$(var return_mode)"/>
23+
<arg name="max_range" value="$(var max_range)"/>
24+
<arg name="min_range" value="$(var min_range)"/>
25+
<arg name="frame_id" value="$(var sensor_frame)"/>
26+
<arg name="sensor_ip" value="$(var sensor_ip)"/>
27+
<arg name="host_ip" value="$(var host_ip)"/>
28+
<arg name="data_port" value="$(var data_port)"/>
29+
<arg name="scan_phase" value="$(var scan_phase)"/>
30+
<arg name="cloud_min_angle" value="$(var cloud_min_angle)"/>
31+
<arg name="cloud_max_angle" value="$(var cloud_max_angle)"/>
32+
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
33+
<arg name="use_intra_process" value="true"/>
34+
<arg name="use_multithread" value="false"/>
35+
<arg name="container_name" value="$(var container_name)"/>
36+
</include>
37+
</launch>

sample_sensor_kit_launch/launch/gnss.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
</group>
2525

2626
<!-- NavSatFix to MGRS Pose -->
27-
<include file="$(find-pkg-share gnss_poser)/launch/gnss_poser.launch.xml">
27+
<include file="$(find-pkg-share autoware_gnss_poser)/launch/gnss_poser.launch.xml">
2828
<arg name="input_topic_fix" value="$(var navsatfix_topic_name)"/>
2929
<arg name="input_topic_orientation" value="$(var orientation_topic_name)"/>
3030

sample_sensor_kit_launch/launch/imu.launch.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,13 +15,13 @@
1515

1616
<arg name="imu_raw_name" default="tamagawa/imu_raw"/>
1717
<arg name="imu_corrector_param_file" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/sample_sensor_kit/imu_corrector.param.yaml"/>
18-
<include file="$(find-pkg-share imu_corrector)/launch/imu_corrector.launch.xml">
18+
<include file="$(find-pkg-share autoware_imu_corrector)/launch/imu_corrector.launch.xml">
1919
<arg name="input_topic" value="$(var imu_raw_name)"/>
2020
<arg name="output_topic" value="imu_data"/>
2121
<arg name="param_file" value="$(var imu_corrector_param_file)"/>
2222
</include>
2323

24-
<include file="$(find-pkg-share imu_corrector)/launch/gyro_bias_estimator.launch.xml">
24+
<include file="$(find-pkg-share autoware_imu_corrector)/launch/gyro_bias_estimator.launch.xml">
2525
<arg name="input_imu_raw" value="$(var imu_raw_name)"/>
2626
<arg name="input_odom" value="/localization/kinematic_state"/>
2727
<arg name="imu_corrector_param_file" value="$(var imu_corrector_param_file)"/>

sample_sensor_kit_launch/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,9 @@
1010

1111
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1212

13+
<exec_depend>autoware_gnss_poser</exec_depend>
1314
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
1415
<exec_depend>common_sensor_launch</exec_depend>
15-
<exec_depend>gnss_poser</exec_depend>
1616
<exec_depend>tamagawa_imu_driver</exec_depend>
1717
<exec_depend>topic_tools</exec_depend>
1818
<exec_depend>ublox_gps</exec_depend>

0 commit comments

Comments
 (0)