car_pose_detector.cpp 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899
  1. #include <ceres/ceres.h>
  2. #include <ceres/cubic_interpolation.h>
  3. #include "car_pose_detector.h"
  4. struct DiscreteCostFunction {
  5. std::vector<double> line_;
  6. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_;
  7. explicit DiscreteCostFunction(std::vector<double> &line,pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
  8. line_ = line;
  9. cloud_=cloud;
  10. }
  11. template<typename JetT>
  12. bool operator()(const JetT* const x, JetT* residual) const {
  13. ceres::Grid1D<double> grid(line_.data(), 0, line_.size());
  14. ceres::CubicInterpolator<ceres::Grid1D<double>> cubic(grid);
  15. JetT tx=x[0];
  16. JetT theta=x[1];
  17. for(int i=0;i<cloud_->size();++i){
  18. pcl::PointXYZ pt=cloud_->points[i];
  19. JetT cx= JetT(pt.x) * ceres::cos(theta) - JetT(pt.y) * ceres::sin(theta) + tx + 1.5;
  20. cubic.Evaluate(cx*100.,&residual[i]);
  21. residual[i]=JetT(1.0)-residual[i];
  22. }
  23. return true;
  24. }
  25. };
  26. Car_pose_detector::Car_pose_detector(){
  27. float width = 1.8;
  28. float sigma=25.;
  29. float solution = 0.01;
  30. for (int i=-130;i<130;++i) {
  31. float x=i*solution;
  32. double y = 1.0 / (1.0 + ceres::exp(-sigma * (x+width/2.))) -
  33. 1.0 / (1.0 + ceres::exp(-sigma * (x-width/2.)));
  34. line_.emplace_back(y);
  35. // printf("---Debug %s %d : [%d %f %f]. \n", __func__, __LINE__, i, x, y);
  36. }
  37. }
  38. // 检测底盘z方向值,去中心,使用mat加速
  39. bool Car_pose_detector::detect_pose_mat(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr,
  40. pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud, float &x,
  41. float &theta) {
  42. //离群点过滤
  43. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  44. sor.setInputCloud(cloud_ptr);
  45. sor.setMeanK(50); //K近邻搜索点个数
  46. sor.setStddevMulThresh(0.7); //标准差倍数
  47. sor.setNegative(false); //保留未滤波点(内点)
  48. sor.filter(*cloud_ptr); //保存滤波结果到cloud_filter
  49. double t_vars[2] = {0, 0};
  50. // 去中心化
  51. // 构建最小二乘问题
  52. ceres::Problem problem;
  53. // tp_trans_mat_cost->debug_img(t_cloud, m_model);
  54. problem.AddResidualBlock( // 向问题中添加误差项
  55. // 使用自动求导,模板参数:误差类型,输出维度,输入维度,维数要与前面struct中一致
  56. new ceres::AutoDiffCostFunction<DiscreteCostFunction, ceres::DYNAMIC, 2>(
  57. (new DiscreteCostFunction(line_,cloud_ptr)), cloud_ptr->size()),
  58. nullptr, // 核函数,这里不使用,为空
  59. t_vars // 待估计参数
  60. );
  61. // problem.SetParameterLowerBound(t_vars, 0, -0.1);
  62. // problem.SetParameterUpperBound(t_vars, 0, 0.1);
  63. problem.SetParameterLowerBound(t_vars, 1, (-20) * M_PI / 180.0f);
  64. problem.SetParameterUpperBound(t_vars, 1, (20) * M_PI / 180.0f);
  65. // 配置求解器
  66. ceres::Solver::Options options; // 这里有很多配置项可以填
  67. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  68. options.minimizer_progress_to_stdout = false; // 输出到cout
  69. options.max_num_iterations = 100;
  70. ceres::Solver::Summary summary; // 优化信息
  71. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  72. ceres::Solve(options, &problem, &summary); // 开始优化
  73. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  74. std::chrono::duration<double> time_used = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  75. std::cout << "solve time cost = " << time_used.count() << " seconds. " << std::endl;
  76. x = t_vars[0];
  77. theta = t_vars[1] * 180 / M_PI;
  78. for (auto &point: cloud_ptr->points) {
  79. pcl::PointXYZ result;
  80. result.x = - point.y * std::sin(t_vars[1]) + point.x * std::cos(t_vars[1]) + t_vars[0];
  81. result.y = point.y * std::cos(t_vars[1]) + point.x * std::sin(t_vars[1]);
  82. result.z = point.z;
  83. out_cloud->emplace_back(result);
  84. }
  85. return true;
  86. }