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

fix(tier4_perception_launch): rearrange downsample #870

Closed
wants to merge 2 commits into from
Closed
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 @@ -80,37 +80,13 @@ def create_no_compare_map_pipeline(self):

def create_compare_map_pipeline(self):
components = []
down_sample_topic = (
"/perception/obstacle_segmentation/pointcloud_map_filtered/downsampled/pointcloud"
)
components.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::ApproximateDownsampleFilterComponent",
name="voxel_grid_downsample_filter",
remappings=[
("input", LaunchConfiguration("input_topic")),
("output", down_sample_topic),
],
parameters=[
{
"voxel_size_x": self.voxel_size,
"voxel_size_y": self.voxel_size,
"voxel_size_z": self.voxel_size,
}
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
),
)
components.append(
ComposableNode(
package="compare_map_segmentation",
plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent",
name="voxel_based_compare_map_filter",
remappings=[
("input", down_sample_topic),
("input", LaunchConfiguration("input_topic")),
("map", "/map/pointcloud_map"),
("output", LaunchConfiguration("output_topic")),
("map_loader_service", "/map/get_differential_pointcloud_map"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -225,14 +225,36 @@ def create_common_pipeline(self, input_topic, output_topic):
],
)
)

components.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent",
name="voxel_grid_downsample_filter",
remappings=[
("input", "range_cropped/pointcloud"),
("output", "range_cropped/downsampled/pointcloud"),
],
parameters=[
{
"input_frame": LaunchConfiguration("base_frame"),
"output_frame": LaunchConfiguration("base_frame"),
"voxel_size_x": LaunchConfiguration("voxel_size"),
"voxel_size_y": LaunchConfiguration("voxel_size"),
"voxel_size_z": LaunchConfiguration("voxel_size"),
}
],
extra_arguments=[
{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}
],
)
)
components.append(
ComposableNode(
package="ground_segmentation",
plugin=self.ground_segmentation_param["common_ground_filter"]["plugin"],
name="common_ground_filter",
remappings=[
("input", "range_cropped/pointcloud"),
("input", "range_cropped/downsampled/pointcloud"),
("output", output_topic),
],
parameters=[
Expand Down Expand Up @@ -521,6 +543,7 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "perception_pipeline_container")
add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud")
add_launch_arg("voxel_size", "0.1")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
Loading