Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feature(single_lidar_common_launch): load from parameter #3

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@
base_frame: base_link
use_imu: true
use_3d_distortion_correction: false
update_azimuth_and_distance: false
8 changes: 8 additions & 0 deletions single_lidar_common_launch/config/filter.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
input_frame: ""
output_frame: ""
max_queue_size: 5
use_indices: false
latched_indices: false
approximate_sync: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
distance_ratio: 1.03
object_length_threshold: 0.1
num_points_threshold: 4
max_rings_num: 128
max_points_num_per_ring: 4000
publish_outlier_pointcloud: false
min_azimuth_deg: 0.0
max_azimuth_deg: 360.0
max_distance: 12.0
vertical_bins: 128
horizontal_bins: 36
noise_threshold: 2
42 changes: 33 additions & 9 deletions single_lidar_common_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,18 @@ def create_parameter_dict(*args):
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)

# Pointcloud preprocessor parameters
filter_param = ParameterFile(
param_file=LaunchConfiguration("filter_param_path").perform(context),
allow_substs=True,
)
distortion_corrector_node_param = ParameterFile(
param_file=LaunchConfiguration("distortion_correction_node_param_path").perform(context),
allow_substs=True,
)
ring_outlier_filter_node_param = ParameterFile(
param_file=LaunchConfiguration("ring_outlier_filter_node_param_path").perform(context),
allow_substs=True,
)

nodes = []

Expand Down Expand Up @@ -159,7 +167,7 @@ def create_parameter_dict(*args):
("input", "pointcloud_raw_ex"),
("output", "self_cropped/pointcloud_ex"),
],
parameters=[cropbox_parameters],
parameters=[filter_param, cropbox_parameters],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)
Expand All @@ -181,7 +189,7 @@ def create_parameter_dict(*args):
("input", "self_cropped/pointcloud_ex"),
("output", "mirror_cropped/pointcloud_ex"),
],
parameters=[cropbox_parameters],
parameters=[filter_param, cropbox_parameters],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)
Expand All @@ -204,21 +212,19 @@ def create_parameter_dict(*args):

# Ring Outlier Filter is the last component in the pipeline, so control the output frame here
if LaunchConfiguration("output_as_sensor_frame").perform(context).lower() == "true":
ring_outlier_filter_parameters = {"output_frame": LaunchConfiguration("frame_id")}
ring_outlier_output_frame = {"output_frame": LaunchConfiguration("frame_id")}
else:
ring_outlier_filter_parameters = {
"output_frame": ""
} # keep the output frame as the input frame
ring_outlier_output_frame = {"output_frame": ""} # keep the output frame as the input frame
nodes.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::RingOutlierFilterComponent",
package="autoware_pointcloud_preprocessor",
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
name="ring_outlier_filter",
remappings=[
("input", "rectified/pointcloud_ex"),
("output", "pointcloud_before_sync"),
],
parameters=[ring_outlier_filter_parameters],
parameters=[filter_param, ring_outlier_filter_node_param, ring_outlier_output_frame],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)
)
Expand Down Expand Up @@ -274,6 +280,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg(
"vehicle_mirror_param_file", description="path to the file of vehicle mirror position yaml"
)
add_launch_arg(
"filter_param_path",
os.path.join(
common_sensor_share_dir,
"config",
"filter.param.yaml",
),
description="path to parameter file of filter",
)
add_launch_arg(
"distortion_correction_node_param_path",
os.path.join(
Expand All @@ -283,6 +298,15 @@ def add_launch_arg(name: str, default_value=None, description=None):
),
description="path to parameter file of distortion correction node",
)
add_launch_arg(
"ring_outlier_filter_node_param_path",
os.path.join(
common_sensor_share_dir,
"config",
"ring_outlier_filter_node.param.yaml",
),
description="path to parameter file of ring outlier filter node",
)

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down