Skip to content

Commit

Permalink
feat: insert inside area filter before clustering
Browse files Browse the repository at this point in the history
Signed-off-by: yoshiri <[email protected]>
  • Loading branch information
YoshiRi committed Jun 7, 2024
1 parent a358cd2 commit cb2ea3a
Showing 1 changed file with 23 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ def create_compare_map_pipeline(self):
down_sample_topic = (
"/perception/obstacle_segmentation/pointcloud_map_filtered/downsampled/pointcloud"
)
intermediate_topic = "/perception/obstacle_segmentation/pointcloud_map_filtered/before_area_filter/pointcloud"
components.append(
ComposableNode(
package="pointcloud_preprocessor",
Expand Down Expand Up @@ -112,7 +113,7 @@ def create_compare_map_pipeline(self):
remappings=[
("input", down_sample_topic),
("map", "/map/pointcloud_map"),
("output", LaunchConfiguration("output_topic")),
("output", intermediate_topic),
("map_loader_service", "/map/get_differential_pointcloud_map"),
("kinematic_state", "/localization/kinematic_state"),
],
Expand All @@ -133,6 +134,27 @@ def create_compare_map_pipeline(self):
],
)
)
components.append(
ComposableNode(
package="pointcloud_preprocessor",
plugin="pointcloud_preprocessor::VectorMapInsideAreaFilterComponent",
name="vector_map_inside_area_filter",
remappings=[
("input/vector_map", "/map/vector_map"),
("input", intermediate_topic),
("output", LaunchConfiguration("output_topic")),
],
parameters=[
{
"use_z_filter": True,
"z_threshold": 0.15,
}
],
extra_arguments=[
{"use_intra_process_comms": False},
],
)
)
return components


Expand Down

0 comments on commit cb2ea3a

Please sign in to comment.