ParametersSolver.cpp 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147
  1. //
  2. // Created by zx on 22-11-9.
  3. //
  4. #include "ParametersSolver.h"
  5. #include "ceres/ceres.h"
  6. #include <chrono>
  7. class CostFunctor{
  8. public:
  9. std::vector<cv::Point2d> ixy_;
  10. std::vector<cv::Point3d> wpt_;
  11. public:
  12. CostFunctor(std::vector<cv::Point2d> ixy,std::vector<cv::Point3d> wpt)
  13. {
  14. ixy_=ixy;
  15. wpt_=wpt;
  16. }
  17. template <typename T>
  18. bool operator()(const T* const value, T* residual) const
  19. {
  20. if (ixy_.size()!=wpt_.size())
  21. printf("Error : ixy_.size()!=wpt_.size() \n");
  22. //参数拜访顺序:R P Y tx ty tz fx fy cx cy k1 k2 k3 r 共14个参数
  23. T R=value[0];
  24. T P=value[1];
  25. T Y=value[2];
  26. T tx=value[3];
  27. T ty=value[4];
  28. T tz=value[5];
  29. T fx=value[6];
  30. T fy=value[7];
  31. T cx=value[8];
  32. T cy=value[9];
  33. T k1=value[10];
  34. T k2=value[11];
  35. T p1=value[12];
  36. T p2=value[13];
  37. T k3=value[14];
  38. Eigen::AngleAxis<T> rollAngle(Eigen::AngleAxis<T>(R,Eigen::Matrix<T,3,1>::UnitX()));
  39. Eigen::AngleAxis<T> pitchAngle(Eigen::AngleAxis<T>(P,Eigen::Matrix<T,3,1>::UnitY()));
  40. Eigen::AngleAxis<T> yawAngle(Eigen::AngleAxis<T>(Y,Eigen::Matrix<T,3,1>::UnitZ()));
  41. Eigen::Matrix<T,3,3> rotation_matrix;
  42. rotation_matrix=yawAngle*pitchAngle*rollAngle;
  43. //每个样本,产生2n维残差项
  44. for (int i=0;i<ixy_.size();++i)
  45. {
  46. Eigen::Matrix<T,3,1> wp;
  47. wp[0]=T(wpt_[i].x)-tx;
  48. wp[1]=T(wpt_[i].y)-ty;
  49. wp[2]=T(wpt_[i].z)-tz;
  50. Eigen::Matrix<T,3,1> Rwp=rotation_matrix.inverse()*wp;
  51. T X=Rwp[0];
  52. T Y=Rwp[1];
  53. T Z=Rwp[2];
  54. T ix=T(ixy_[i].x);
  55. T iy=T(ixy_[i].y);
  56. T rr=X*X+Y*Y;
  57. T nx=X*(T(1.0)+k1*rr+k2*rr*rr+k3*rr*rr*rr) + T(2.0)*p1*X*Y + p2*(rr+T(2.0)*X*X);
  58. T ny=Y*(T(1.0)+k1*rr+k2*rr*rr+k3*rr*rr*rr) + p1*(rr+T(2.0)*Y*Y) + T(2.0)*p2*X*Y;
  59. residual[2*i]=nx*fx/Z+cx-ix;
  60. residual[2*i+1]=ny*fy/Z+cy-iy;
  61. }
  62. return true;
  63. }
  64. };
  65. ParametersSolver::ParametersSolver()
  66. {
  67. }
  68. ParametersSolver::~ParametersSolver()
  69. {
  70. }
  71. void ParametersSolver::Solve(std::vector<cv::Point2d> ixy,std::vector<cv::Point3d> wpt)
  72. {
  73. if(ixy.size()!=wpt.size())
  74. {
  75. printf("Error : ixy.size()!=wpt.size()\n");
  76. return ;
  77. }
  78. // 寻优参数x的初始值
  79. auto t0 = std::chrono::steady_clock::now();
  80. double R=0;
  81. double P=0;
  82. double Y=0;
  83. double tx=0;
  84. double ty=0;
  85. double tz=0;
  86. double fx=0;
  87. double fy=0;
  88. double cx=0;
  89. double cy=0;
  90. double k1=0;
  91. double k2=0;
  92. double p1=0;
  93. double p2=0;
  94. double k3=0;
  95. const int NUM=15;
  96. double x[NUM]={R,P,Y,tx,ty,tz,fx,fy,cx,cy,k1,k2,p1,p2,k3};
  97. const int samples=ixy.size();
  98. // 第二部分:构建寻优问题
  99. ceres::Problem problem;
  100. //使用自动求导,将之前的代价函数结构体传入,残差维度2n,参数x的维度NUM。
  101. ceres::CostFunction* cost_function =new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, NUM>(
  102. new CostFunctor(ixy,wpt),2*samples);
  103. problem.AddResidualBlock(cost_function, NULL, x); //向问题中添加误差项
  104. //第三部分: 配置并运行求解器
  105. ceres::Solver::Options options;
  106. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  107. options.minimizer_progress_to_stdout = true;//输出到cout
  108. ceres::Solver::Summary summary;//优化信息
  109. ceres::Solve(options, &problem, &summary);//求解!!!
  110. auto t1 = std::chrono::steady_clock::now();
  111. std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  112. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t1 - t0);
  113. double time=double(duration.count()) * std::chrono::microseconds::period::num /
  114. std::chrono::microseconds::period::den;
  115. std::cout << "time : "<<time<<std::endl;
  116. }