chassis_ceres_solver.cpp 10 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. //
  2. // Created by zx on 2021/9/17.
  3. //
  4. #include "chassis_ceres_solver.h"
  5. const float CERES_PA=(100.);
  6. const float CERES_PB=(300.);
  7. const float CERES_PC=(300.);
  8. class chassis_ceres_cost
  9. {
  10. private:
  11. pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud; //点云
  12. public:
  13. chassis_ceres_cost(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud)
  14. :m_cloud(cloud)
  15. {
  16. }
  17. template<typename T>
  18. bool operator()(const T *const variable, T *residual) const
  19. {
  20. T cx = variable[0];
  21. T cy = variable[1];
  22. T w=variable[2];
  23. T h=variable[3];
  24. const T PA=T(CERES_PA);
  25. const T PB=T(CERES_PB);
  26. const T PC=T(CERES_PC);
  27. //
  28. for (int i = 0; i < m_cloud->size(); ++i)
  29. {
  30. //先平移后旋转
  31. const Eigen::Matrix<T, 2, 1> point((T(m_cloud->points[i].x)),
  32. (T(m_cloud->points[i].z)));
  33. T kx=point(0,0);
  34. T ky=point(1,0);
  35. T fx=1.0/(1.0+ceres::exp(-PA*(kx-cx+w/2.0)))-1.0/(1.0+ceres::exp(-PA*(kx-cx-w/2.0)));
  36. T fy=1.0/(1.0+ceres::exp(-PB*(ky-cy+h/2.0)))-1.0/(1.0+ceres::exp(-PC*((ky-cy)-h/2.0)));
  37. residual[i] = fx * fy; //+(50./m_cloud->size())/(w*h+1e-16);
  38. }
  39. residual[m_cloud->size()] = T(1.0) / (w * h + 1e-16);
  40. return true;
  41. }
  42. };
  43. // 公式转图片优化
  44. #include <ceres/cubic_interpolation.h>
  45. class GridArrayAdapter
  46. {
  47. public:
  48. enum { DATA_DIMENSION = 1 };
  49. explicit GridArrayAdapter(const cv::Mat& grid) : grid_(grid) {}
  50. void GetValue(const int row, const int column, double* const value) const {
  51. if (row < kPadding || column < kPadding || row >= NumRows() - kPadding ||
  52. column >= NumCols() - kPadding) {
  53. *value = kMaxCorrespondenceCost;
  54. } else {
  55. *value = static_cast<double>(grid_.at<double >(row - kPadding, column - kPadding));
  56. }
  57. }
  58. int NumRows() const {
  59. return grid_.rows + 2 * kPadding;
  60. }
  61. int NumCols() const {
  62. return grid_.cols + 2 * kPadding;
  63. }
  64. private:
  65. const cv::Mat& grid_;
  66. };
  67. class chassis_mat_cost
  68. {
  69. private:
  70. pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud; //点云
  71. cv::Mat m_mat;
  72. public:
  73. chassis_mat_cost(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, cv::Mat mat)
  74. :m_cloud(cloud),m_mat(mat)
  75. {
  76. }
  77. template<typename T>
  78. bool operator()(const T *const variable, T *residual) const
  79. {
  80. T cx = variable[0];
  81. T cy = variable[1];
  82. T w_ratio = variable[2]/T(inner_width);
  83. T h_ratio = variable[3]/T(chassis_height);
  84. const GridArrayAdapter adapter(m_mat);
  85. ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
  86. //
  87. for (int i = 0; i < m_cloud->size(); ++i)
  88. {
  89. //先平移后旋转
  90. const Eigen::Matrix<T, 2, 1> point((T(m_cloud->points[i].x)-cx),
  91. (T(m_cloud->points[i].z)-cy));
  92. T kx=(point(0,0)*w_ratio-T(startx)) / T(resolutionx);
  93. T ky=(point(1,0)*h_ratio-T(starty)) / T(resolutiony);
  94. interpolator.Evaluate(kx, ky, &residual[i]);
  95. // residual[i] = fx * fy; //+(50./m_cloud->size())/(w*h+1e-16);
  96. }
  97. residual[m_cloud->size()] = (w_ratio - T(1.0));
  98. residual[m_cloud->size()+1] = (h_ratio - T(1.0));
  99. return true;
  100. }
  101. // 生成debug图片
  102. void generate_mat(cv::Mat &mat, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud, double *variables)
  103. {
  104. mat = m_mat.clone();
  105. double w_ratio = variables[2] / inner_width;
  106. double h_ratio = variables[3] / chassis_height;
  107. for (size_t i = 0; i < cloud->size(); i++)
  108. {
  109. const Eigen::Vector2d point(
  110. ((cloud->points[i].x - variables[0]) * w_ratio - startx) / resolutionx,
  111. ((cloud->points[i].z - variables[1]) * h_ratio - starty) / resolutiony);
  112. cv::circle(mat, cv::Point2d(point.y(), point.x()), 2, cv::Scalar(0.4), 1);
  113. // std::cout << point.y() << ", " << point.x() << std::endl;
  114. }
  115. }
  116. };
  117. cv::Mat chassis_ceres_solver::m_model = chassis_ceres_solver::create_mat();
  118. chassis_ceres_solver::chassis_ceres_solver(){}
  119. chassis_ceres_solver::~chassis_ceres_solver(){}
  120. /**
  121. * @description: 使用sigmoid函数寻找xoz平面平移以及内宽、底盘高度
  122. */
  123. Error_manager chassis_ceres_solver::solve(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,double& x,double& y,double& w,double& h)
  124. {
  125. double variable[] = {x, y, w, h};
  126. /*printf("init solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  127. variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);*/
  128. // 第二部分:构建寻优问题
  129. ceres::Problem problem;
  130. chassis_ceres_cost *cost_func = new chassis_ceres_cost(cloud);
  131. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  132. ceres::CostFunction* cost_function =new
  133. ceres::AutoDiffCostFunction<chassis_ceres_cost, ceres::DYNAMIC, 4>(
  134. cost_func,cloud->size()+1);
  135. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  136. //第三部分: 配置并运行求解器
  137. ceres::Solver::Options options;
  138. options.use_nonmonotonic_steps=false;
  139. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  140. //options.logging_type = ceres::LoggingType::SILENT;
  141. options.max_num_iterations=500;
  142. options.num_threads=1;
  143. options.minimizer_progress_to_stdout = false;//输出到cout
  144. ceres::Solver::Summary summary;//优化信息
  145. ceres::Solve(options, &problem, &summary);//求解!!!
  146. double loss=summary.final_cost/(cloud->size());
  147. x=variable[0];
  148. y=variable[1];
  149. // printf(" loss : %f x:%.5f y:%.5f w:%.5f h:%.5f\n",
  150. // loss,variable[0],variable[1],variable[2],variable[3]);
  151. return SUCCESS;
  152. }
  153. /**
  154. * @description: 图片代替函数十倍提升优化速度
  155. */
  156. Error_manager chassis_ceres_solver::solve_mat(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,double& x,double& y,double& w,double& h, bool update_debug_img)
  157. {
  158. // std::chrono::steady_clock::time_point t0 = std::chrono::steady_clock::now();
  159. // create_mat(m_model);
  160. // cv::imshow("model", m_model);
  161. // cv::waitKey(30);
  162. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  163. // std::chrono::duration<double> time_used_mat = std::chrono::duration_cast<std::chrono::duration<double>>(t1 - t0);
  164. double variable[] = {x, y, w, h};
  165. /*printf("init solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  166. variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);*/
  167. // 第二部分:构建寻优问题
  168. ceres::Problem problem;
  169. chassis_mat_cost *cost_func = new chassis_mat_cost(cloud, m_model);
  170. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  171. ceres::CostFunction* cost_function =new
  172. ceres::AutoDiffCostFunction<chassis_mat_cost, ceres::DYNAMIC, 4>(
  173. cost_func, cloud->size()+2);
  174. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  175. //第三部分: 配置并运行求解器
  176. ceres::Solver::Options options;
  177. options.use_nonmonotonic_steps=false;
  178. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  179. //options.logging_type = ceres::LoggingType::SILENT;
  180. options.max_num_iterations=500;
  181. options.num_threads=1;
  182. options.minimizer_progress_to_stdout = false;//输出到cout
  183. ceres::Solver::Summary summary;//优化信息
  184. ceres::Solve(options, &problem, &summary);//求解!!!
  185. double loss=summary.final_cost/(cloud->size());
  186. x = variable[0];
  187. y = variable[1];
  188. w = variable[2];
  189. h = variable[3];
  190. // printf(" loss : %f x:%.5f y:%.5f w:%.5f h:%.5f\n",
  191. // loss,variable[0],variable[1],variable[2],variable[3]);
  192. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  193. std::chrono::duration<double> time_used_solve = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  194. if(update_debug_img)
  195. {
  196. cost_func->generate_mat(m_projected_mat, cloud, variable);
  197. cv::namedWindow("win", cv::WINDOW_FREERATIO);
  198. cv::imshow("win", m_projected_mat);
  199. cv::waitKey(30);
  200. }
  201. std::chrono::steady_clock::time_point t3 = std::chrono::steady_clock::now();
  202. std::chrono::duration<double> time_used_disp = std::chrono::duration_cast<std::chrono::duration<double>>(t3 - t2);
  203. // std::cout << "\ntime used for solve, display in ms: " << time_used_solve.count() << ", " << time_used_disp.count() << std::endl
  204. // << std::endl;
  205. return SUCCESS;
  206. }
  207. cv::Mat chassis_ceres_solver::create_mat()
  208. {
  209. int rows = (endx - startx) / resolutionx + 1;
  210. int cols = (endy - starty) / resolutiony + 1;
  211. if(rows<=1 || cols <=1)
  212. return cv::Mat();
  213. cv::Mat t_mat(rows, cols, CV_32FC1);
  214. for (size_t i = 0; i < rows; i++)
  215. {
  216. for (size_t j = 0; j < cols; j++)
  217. {
  218. double x = i * resolutionx + startx;
  219. double y = j * resolutiony + starty;
  220. double fx = 1.0 / (1.0 + std::exp(-CERES_PA * (x + inner_width / 2.0))) - 1.0 / (1.0 + std::exp(-CERES_PA * (x - inner_width / 2.0)));
  221. double fy = 1.0 / (1.0 + std::exp(-CERES_PB * (y + chassis_height / 2.0))) - 1.0 / (1.0 + std::exp(-CERES_PC * (y - chassis_height / 2.0)));
  222. t_mat.at<float>(i, j) = fx * fy;
  223. // std::cout << "x,y: " << x << ", " << y << "-----value: " << 1.0 / (1.0 + std::exp(-CERES_PA * (x + default_width / 2.0)))<<", "<<
  224. // 1.0 / (1.0 + std::exp(-CERES_PA * (x - default_width / 2.0))) << std::endl;
  225. // if(fx*fy>0)
  226. // std::cout << "x,y: " << x << "," << y << ", fx,fy: " << fx << ", " << fy << ", " << fx * fy << std::endl;
  227. }
  228. }
  229. cv::normalize(t_mat, t_mat, 1.0, 0.1, cv::NORM_MINMAX);
  230. // std::cout << t_mat << std::endl;
  231. // cv::namedWindow("win", cv::WINDOW_FREERATIO);
  232. // cv::imshow("win", t_mat);
  233. // cv::waitKey(0);
  234. return t_mat;
  235. }