diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index faa0486bd52ee..cf1ca758f3945 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -102,13 +102,13 @@ def launch_setup(context, *args, **kwargs): ( "~/input/obstacle_pointcloud", LaunchConfiguration("input/obstacle_pointcloud") - if downsample_input_pointcloud + if not downsample_input_pointcloud else "/perception/obstacle_segmentation/downsample/pointcloud", ), ( "~/input/raw_pointcloud", LaunchConfiguration("input/raw_pointcloud") - if downsample_input_pointcloud + if not downsample_input_pointcloud else "/sensing/lidar/concatenated/downsample/pointcloud", ), ("~/output/occupancy_grid_map", LaunchConfiguration("output")),