diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml index 1c9201a9af8b3..2232feb6d7c67 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml @@ -85,6 +85,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml index 1a97659b357d8..5b5fabd4dd886 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml @@ -22,6 +22,9 @@ + + + diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml index ce34640bd3179..cec0c3bc05aac 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detector/lidar_rule_detector.launch.xml @@ -26,6 +26,9 @@ + + + diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py index 66c25396a656e..b8d4f61a9cf28 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.py @@ -76,6 +76,13 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else container ) use_low_height_pointcloud_loader = LoadComposableNodes( @@ -83,13 +90,13 @@ def load_composable_node_param(param_path): low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) @@ -106,6 +113,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml index fd1ea82befae0..f4deeccf7b76c 100644 --- a/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py index 00bcd4422bd3c..607e1bf30ccaa 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py @@ -77,6 +77,13 @@ def load_composable_node_param(param_path): executable="component_container", composable_node_descriptions=[], output="screen", + condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + ) + + target_container = ( + LaunchConfiguration("pointcloud_container_name") + if IfCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) + else container ) use_low_height_pointcloud_loader = LoadComposableNodes( @@ -84,13 +91,13 @@ def load_composable_node_param(param_path): low_height_cropbox_filter_component, use_low_height_euclidean_component, ], - target_container=container, + target_container=target_container, condition=IfCondition(LaunchConfiguration("use_low_height_cropbox")), ) disuse_low_height_pointcloud_loader = LoadComposableNodes( composable_node_descriptions=[disuse_low_height_euclidean_component], - target_container=container, + target_container=target_container, condition=UnlessCondition(LaunchConfiguration("use_low_height_cropbox")), ) return [ @@ -110,6 +117,8 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("input_map", "/map/pointcloud_map"), add_launch_arg("output_clusters", "clusters"), add_launch_arg("use_low_height_cropbox", "false"), + add_launch_arg("use_pointcloud_container", "false"), + add_launch_arg("pointcloud_container_name", "pointcloud_container"), add_launch_arg( "voxel_grid_based_euclidean_param_path", [ diff --git a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml index b6a426dabfd12..3a7c685d8f449 100644 --- a/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml +++ b/perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.xml @@ -5,6 +5,8 @@ + + @@ -12,5 +14,8 @@ + + + diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 33781461fa1cc..db13d73e37fa7 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -26,6 +26,9 @@ + + + @@ -38,7 +41,53 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml index ed378ffa44a70..baea087c96bca 100644 --- a/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml +++ b/perception/lidar_centerpoint/config/detection_class_remapper.param.yaml @@ -29,9 +29,9 @@ max_area_matrix: #UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE, PEDESTRIAN [ 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #UNKNOWN - 0.000, 0.000, 36.000, 0.000, inf, 0.000, 0.000, 0.000, #CAR - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #TRUCK - 0.000, 0.000, 0.000, 0.000, inf, 0.000, 0.000, 0.000, #BUS + 0.000, 0.000, 36.000, 0.000, 999.999, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 999.999, 0.000, 0.000, 0.000, #BUS 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #TRAILER 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #MOTORBIKE 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, 0.000, #BICYCLE diff --git a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml index a7f181ab78ac6..1210875770510 100644 --- a/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml +++ b/perception/lidar_centerpoint/launch/lidar_centerpoint.launch.xml @@ -11,20 +11,45 @@ - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +