Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix pcl version 1.10 compatibility with ndt #190

Merged
merged 3 commits into from
Dec 14, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,9 @@ static pcl_omp::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> 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;

Expand Down Expand Up @@ -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
}

Expand Down Expand Up @@ -460,16 +470,21 @@ static void map_callback(const sensor_msgs::PointCloud2::ConstPtr& input)

pcl::PointCloud<pcl::PointXYZ>::Ptr map_ptr(new pcl::PointCloud<pcl::PointXYZ>(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<pcl::PointXYZ, pcl::PointXYZ> new_ndt;
pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
new_ndt.setResolution(ndt_res);
new_ndt.setInputTarget(map_ptr);
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());

Expand Down
2 changes: 1 addition & 1 deletion docker/install.sh
Original file line number Diff line number Diff line change
Expand Up @@ -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