lidar_caliber.cpp 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758
  1. //
  2. // Created by zx on 2021/8/17.
  3. //
  4. #include "lidar_caliber.h"
  5. #include <pcl/registration/ndt.h>
  6. lidar_caliber::lidar_caliber()
  7. {
  8. }
  9. bool lidar_caliber::caliber(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_center,pcl::PointCloud<pcl::PointXYZ>::Ptr cloud1
  10. ,pcl::PointCloud<pcl::PointXYZ>::Ptr cloud2,Eigen::Matrix<float,6,1>& transform1
  11. ,Eigen::Matrix<float,6,1>& transfoem2)
  12. {
  13. //transform1=match();
  14. }
  15. Eigen::Matrix4f lidar_caliber::match(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_center
  16. ,pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,Eigen::Matrix<float, 6,1> init_transform)
  17. {
  18. //初始化正态分布变换(NDT)
  19. pcl::NormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ> ndt;
  20. //设置依赖尺度NDT参数
  21. //为终止条件设置最小转换差异
  22. ndt.setTransformationEpsilon(0.01);
  23. //为More-Thuente线搜索设置最大步长
  24. ndt.setStepSize(0.1);
  25. //设置NDT网格结构的分辨率(VoxelGridCovariance)
  26. ndt.setResolution(1.0);
  27. //设置匹配迭代的最大次数
  28. ndt.setMaximumIterations(35);
  29. // 设置要配准的点云
  30. ndt.setInputCloud(cloud);
  31. //设置点云配准目标
  32. ndt.setInputTarget(cloud_center);
  33. //设置使用机器人测距法得到的初始对准估计结果
  34. Eigen::AngleAxisf rollAngle(Eigen::AngleAxisf(init_transform(0), Eigen::Vector3f::UnitX()));
  35. Eigen::AngleAxisf pitchAngle(Eigen::AngleAxisf(init_transform(1), Eigen::Vector3f::UnitY()));
  36. Eigen::AngleAxisf yawAngle(Eigen::AngleAxisf(init_transform(2), Eigen::Vector3f::UnitZ()));
  37. Eigen::AngleAxisf rotation ;
  38. rotation = yawAngle*pitchAngle*rollAngle;
  39. Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity();
  40. transform_2.translation() << init_transform(3),init_transform(4),init_transform(5); // 三个数分别对应X轴、Y轴、Z轴方向上的平移
  41. transform_2.rotate(rotation); //同理,UnitX(),绕X轴;UnitY(
  42. Eigen::Matrix4f init_guess = transform_2.matrix();
  43. //计算需要的刚体变换以便将输入的点云匹配到目标点云
  44. pcl::PointCloud<pcl::PointXYZ>::Ptr output_cloud(new pcl::PointCloud<pcl::PointXYZ>);
  45. ndt.align(*output_cloud, init_guess);
  46. std::cout << "Normal Distributions Transform has converged:" << ndt.hasConverged()
  47. << " score: " << ndt.getFitnessScore() << std::endl;
  48. //使用创建的变换对未过滤的输入点云进行变换
  49. return ndt.getFinalTransformation();
  50. }