diff --git a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp index 3557429a469..867082306f7 100644 --- a/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp +++ b/core_perception/lidar_localizer/nodes/ndt_matching/ndt_matching.cpp @@ -130,8 +130,9 @@ static pcl_omp::NormalDistributionsTransform omp_n static int max_iter = 30; // Maximum iterations static float ndt_res = 1.0; // Resolution static double step_size = 0.1; // Step size -static double trans_eps = 0.01; // Transformation epsilon - +static double trans_eps = 0.001; // Transformation epsilon. In PCLv1.10 (ros noetic) this value is squared error not base epsilon + // NOTE: A value of 0.0001 can work as well. + // This will increase the required iteration count (and therefore execution time) but might increase accuracy. static ros::Publisher predict_pose_pub; static geometry_msgs::PoseStamped predict_pose_msg; @@ -322,18 +323,27 @@ static void param_callback(const autoware_config_msgs::ConfigNDT::ConstPtr& inpu if (input->trans_epsilon != trans_eps) { trans_eps = input->trans_epsilon; + double rot_threshold = 1.0 - trans_eps; + - if (_method_type == MethodType::PCL_GENERIC) + if (_method_type == MethodType::PCL_GENERIC) { + ROS_INFO_STREAM("Using translation threshold of " << trans_eps); + ROS_INFO_STREAM("Using rotation threshold of " << rot_threshold); ndt.setTransformationEpsilon(trans_eps); - else if (_method_type == MethodType::PCL_ANH) + ndt.setTransformationRotationEpsilon(rot_threshold); + } + else if (_method_type == MethodType::PCL_ANH) { anh_ndt.setTransformationEpsilon(trans_eps); + } #ifdef CUDA_FOUND - else if (_method_type == MethodType::PCL_ANH_GPU) + else if (_method_type == MethodType::PCL_ANH_GPU) { anh_gpu_ndt_ptr->setTransformationEpsilon(trans_eps); + } #endif #ifdef USE_PCL_OPENMP - else if (_method_type == MethodType::PCL_OPENMP) + else if (_method_type == MethodType::PCL_OPENMP) { omp_ndt.setTransformationEpsilon(ndt_res); + } #endif } @@ -460,9 +470,13 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) pcl::PointCloud::Ptr map_ptr(new pcl::PointCloud(map)); + double rot_threshold = 1.0 - trans_eps; + // Setting point cloud to be aligned to. if (_method_type == MethodType::PCL_GENERIC) { + ROS_INFO_STREAM("Using translation threshold of " << trans_eps); + ROS_INFO_STREAM("Using rotation threshold of " << rot_threshold); pcl::NormalDistributionsTransform new_ndt; pcl::PointCloud::Ptr output_cloud(new pcl::PointCloud); new_ndt.setResolution(ndt_res); @@ -470,6 +484,7 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input) new_ndt.setMaximumIterations(max_iter); new_ndt.setStepSize(step_size); new_ndt.setTransformationEpsilon(trans_eps); + new_ndt.setTransformationRotationEpsilon(rot_threshold); new_ndt.align(*output_cloud, Eigen::Matrix4f::Identity()); diff --git a/docker/install.sh b/docker/install.sh index 1b849d42f62..7102fcf1e13 100755 --- a/docker/install.sh +++ b/docker/install.sh @@ -25,4 +25,4 @@ echo "Build with CUDA" sudo mkdir /opt/autoware.ai # Create install directory sudo chown carma /opt/autoware.ai # Set owner to expose permissions for build sudo chgrp carma /opt/autoware.ai # Set group to expose permissions for build -AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --install-base /opt/autoware.ai/ros/install --executor sequential --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=-Wall -DCMAKE_C_FLAGS=-Wall +AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --install-base /opt/autoware.ai/ros/install --cmake-args -DCMAKE_BUILD_TYPE=Release -DCMAKE_LIBRARY_PATH=/usr/local/cuda/lib64/stubs -DCMAKE_CXX_FLAGS=-Wall -DCMAKE_C_FLAGS=-Wall