From c7bf8f314658f019a3a00304a6d6df33310af624 Mon Sep 17 00:00:00 2001 From: sykwer Date: Thu, 4 Jan 2024 08:35:45 +0900 Subject: [PATCH] autoware-on-linux xx1 ver-20240104 --- .../config/localization/ndt_scan_matcher.param.yaml | 2 +- .../lidar_model/detection_class_remapper.param.yaml | 6 +++--- autoware_launch/launch/pointcloud_container.launch.py | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml index a5befcb1a7..5fb91cec10 100644 --- a/autoware_launch/config/localization/ndt_scan_matcher.param.yaml +++ b/autoware_launch/config/localization/ndt_scan_matcher.param.yaml @@ -48,7 +48,7 @@ neighborhood_search_method: 0 # Number of threads used for parallel computing - num_threads: 4 + num_threads: 2 # The covariance of output pose # Do note that this covariance matrix is empirically derived diff --git a/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml b/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml index ed378ffa44..6d9eed20ef 100644 --- a/autoware_launch/config/perception/object_recognition/detection/lidar_model/detection_class_remapper.param.yaml +++ b/autoware_launch/config/perception/object_recognition/detection/lidar_model/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, 10000.0, 0.000, 0.000, 0.000, #CAR + 0.000, 0.000, 0.000, 0.000, 10000.0, 0.000, 0.000, 0.000, #TRUCK + 0.000, 0.000, 0.000, 0.000, 10000.0, 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/autoware_launch/launch/pointcloud_container.launch.py b/autoware_launch/launch/pointcloud_container.launch.py index 87c46bce69..b0bed5dcb2 100644 --- a/autoware_launch/launch/pointcloud_container.launch.py +++ b/autoware_launch/launch/pointcloud_container.launch.py @@ -40,8 +40,8 @@ def add_launch_arg(name: str, default_value=None): pointcloud_container = ComposableNodeContainer( name=LaunchConfiguration("container_name"), namespace="/", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), + package="rclcpp_component_container_callback_isolated", + executable="component_container_callback_isolated", composable_node_descriptions=[], output="screen", )