diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index 99074d4ae4a98..09d61823235d8 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -40,7 +40,7 @@ def __init__(self, context): self.ground_segmentation_param = yaml.safe_load(f)["/**"]["ros__parameters"] self.single_frame_obstacle_seg_output = ( - "/perception/obstacle_segmentation/single_frame/pointcloud_raw" + "/perception/obstacle_segmentation/single_frame/pointcloud" ) self.output_topic = "/perception/obstacle_segmentation/pointcloud" self.use_single_frame_filter = self.ground_segmentation_param["use_single_frame_filter"] @@ -297,7 +297,7 @@ def create_time_series_outlier_filter_components(input_topic, output_topic): ComposableNode( package="occupancy_grid_map_outlier_filter", plugin="occupancy_grid_map_outlier_filter::OccupancyGridMapOutlierFilterComponent", - name="occupancy_grid_map_outlier_filter", + name="occupancy_grid_based_outlier_filter", remappings=[ ("~/input/occupancy_grid_map", "/perception/occupancy_grid_map/map"), ("~/input/pointcloud", input_topic), diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml index 16396ef2961d8..c6213ee313c2b 100644 --- a/launch/tier4_perception_launch/launch/perception.launch.xml +++ b/launch/tier4_perception_launch/launch/perception.launch.xml @@ -139,7 +139,7 @@ - + diff --git a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md index 6f4d4e22aa26e..cb86ebe7eea85 100644 --- a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md +++ b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md @@ -97,7 +97,7 @@ You need to generate OGMs in each sensor frame before achieving grid map fusion. ```xml - +