detect_ceres3d.cpp 7.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #include "detect_ceres3d.h"
  5. #include "interpolated_grid.hpp"
  6. #include <pcl/common/transforms.h>
  7. class CostFunctor3d
  8. {
  9. private:
  10. const InterpolatedProbabilityGrid m_interpolated_grid;
  11. pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud; //左前点云
  12. public:
  13. CostFunctor3d(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  14. const HybridGrid& interpolated_grid)
  15. :m_interpolated_grid(interpolated_grid),m_cloud(cloud)
  16. {
  17. }
  18. template<typename T>
  19. bool operator()(const T *const variable, T *residual) const
  20. {
  21. T cx = variable[0];
  22. T cy = variable[1];
  23. T theta = variable[2];
  24. //整车旋转
  25. Eigen::Rotation2D<T> rotation(theta);
  26. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  27. //
  28. int right_rear_num = m_cloud->size();
  29. for (int i = 0; i < m_cloud->size(); ++i)
  30. {
  31. //先平移后旋转
  32. const Eigen::Matrix<T, 2, 1> point((T(m_cloud->points[i].x)+cx),
  33. (T(m_cloud->points[i].y)+cy));
  34. //绕原点旋转
  35. const Eigen::Matrix<T, 2, 1> rotate_point = rotation_matrix * point;
  36. residual[i] = T(1.0) -
  37. m_interpolated_grid.GetInterpolatedValue(rotate_point[0],rotate_point[1],
  38. T(m_cloud->points[i].z));
  39. }
  40. return true;
  41. }
  42. };
  43. detect_ceres3d::detect_ceres3d(pcl::PointCloud<pcl::PointXYZ>::Ptr model_grid_cloud)
  44. {
  45. float del_x=0.05;
  46. float del_y=0.03;
  47. float del_z=0.05;
  48. Eigen::Matrix3f delta=Eigen::MatrixXf::Identity(3,3);
  49. delta(0,0)=del_x*del_x;
  50. delta(1,1)=del_y*del_y;
  51. delta(2,2)=del_z*del_z;
  52. Eigen::Matrix3f delta_inv=delta.inverse();
  53. Eigen::Vector3f d(0,0,0.02);
  54. Eigen::MatrixXf ce=-0.5*((d).transpose()*delta_inv*(d));
  55. float cut_p=exp(ce(0,0));
  56. float resolution=0.02;
  57. mp_model_grid=new HybridGrid(resolution);
  58. for(int i=0;i<model_grid_cloud->size();++i)
  59. {
  60. pcl::PointXYZ pt=model_grid_cloud->points[i];
  61. Eigen::Vector3f u(pt.x,pt.y,pt.z);
  62. for(float x=pt.x-0.1;x<pt.x+0.1;x+=mp_model_grid->resolution())
  63. {
  64. for(float y=pt.y-0.1;y<pt.y+0.1;y+=mp_model_grid->resolution())
  65. {
  66. for(float z=pt.z-0.1;z<pt.z+0.1;z+=mp_model_grid->resolution())
  67. {
  68. Eigen::Vector3f p(x,y,z);
  69. Eigen::MatrixXf B=-0.5*((p-u).transpose()*delta_inv*(p-u));
  70. float prob=exp(B(0,0));
  71. if(prob>cut_p)
  72. prob=cut_p;
  73. Eigen::Array3i index=mp_model_grid->GetCellIndex(p);
  74. const Eigen::Array3i shifted_index = index+ (mp_model_grid->grid_size() >> 1);
  75. if ((shifted_index.cast<unsigned int>() >= mp_model_grid->grid_size()).any())
  76. {
  77. std::cout<<index.transpose()<<","<<u.transpose()<<std::endl;
  78. }
  79. if(mp_model_grid->GetProbability(index)<prob)
  80. mp_model_grid->SetProbability(index,prob);
  81. }
  82. }
  83. }
  84. }
  85. save_model("./");
  86. }
  87. #include "point_tool.h"
  88. void detect_ceres3d::save_model(std::string dir)
  89. {
  90. InterpolatedProbabilityGrid inter_grid(*mp_model_grid);
  91. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_grid(new pcl::PointCloud<pcl::PointXYZRGB>);
  92. for(int x=0;x<mp_model_grid->grid_size();++x)
  93. {
  94. for(int y=0;y<mp_model_grid->grid_size();++y)
  95. {
  96. for(int z=0;z<mp_model_grid->grid_size();++z)
  97. {
  98. Eigen::Array3i index(x-mp_model_grid->grid_size()/2,
  99. y-mp_model_grid->grid_size()/2,z-mp_model_grid->grid_size()/2);
  100. Eigen::Vector3f pt=mp_model_grid->GetCenterOfCell(index);
  101. float prob=inter_grid.GetInterpolatedValue(double(pt[0]),double(pt[1]),double(pt[2]));
  102. if(prob>0.01)
  103. {
  104. Eigen::Vector3f pt=mp_model_grid->GetCenterOfCell(index);
  105. int rgb=int((prob-0.01)*255);
  106. pcl::PointXYZRGB point;
  107. point.x=pt[0];
  108. point.y=pt[1];
  109. point.z=pt[2];
  110. point.r=rgb;
  111. point.g=0;
  112. point.b=255-rgb;
  113. cloud_grid->push_back(point);
  114. }
  115. }
  116. }
  117. }
  118. std::cout<<" save model :"<<dir<<std::endl;
  119. save_cloud_txt(cloud_grid,dir+"/model.txt");
  120. }
  121. detect_ceres3d::~detect_ceres3d()
  122. {
  123. delete mp_model_grid;
  124. mp_model_grid= nullptr;
  125. }
  126. bool detect_ceres3d::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
  127. Detect_result &detect_result, std::string &error_info)
  128. {
  129. error_info = "";
  130. double cx=detect_result.cx;
  131. double cy=detect_result.cy;
  132. double init_theta=detect_result.theta;
  133. double variable[] = {cx, cy, init_theta};
  134. /*printf("init solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  135. variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);*/
  136. // 第二部分:构建寻优问题
  137. ceres::Problem problem;
  138. CostFunctor3d *cost_func = new CostFunctor3d(cloud,*mp_model_grid);
  139. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  140. ceres::CostFunction* cost_function =new
  141. ceres::AutoDiffCostFunction<CostFunctor3d, ceres::DYNAMIC, 3>(
  142. cost_func,cloud->size());
  143. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  144. //第三部分: 配置并运行求解器
  145. ceres::Solver::Options options;
  146. options.use_nonmonotonic_steps=false;
  147. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  148. //options.logging_type = ceres::LoggingType::SILENT;
  149. options.max_num_iterations=500;
  150. options.num_threads=2;
  151. options.minimizer_progress_to_stdout = false;//输出到cout
  152. ceres::Solver::Summary summary;//优化信息
  153. ceres::Solve(options, &problem, &summary);//求解!!!
  154. double loss=summary.final_cost/(cloud->size());
  155. if(loss>0.05)
  156. {
  157. char buf[64]={0};
  158. sprintf(buf," loss : %.5f > 0.05",loss);
  159. error_info=buf;
  160. return false;
  161. }
  162. detect_result.cx=variable[0];
  163. detect_result.cy=variable[1];
  164. detect_result.theta=variable[2];
  165. return true;
  166. }
  167. bool detect_ceres3d::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,Detect_result &detect_result,
  168. pcl::PointCloud<pcl::PointXYZ>::Ptr transformed_cloud,std::string &error_info)
  169. {
  170. if(detect(cloud,detect_result,error_info))
  171. {
  172. Eigen::Affine3f transform_2 = Eigen::Affine3f::Identity();
  173. pcl::PointCloud<pcl::PointXYZ>::Ptr transform_cloud0(new pcl::PointCloud<pcl::PointXYZ>());
  174. transform_2.translation() << detect_result.cx, detect_result.cy, 0;
  175. pcl::transformPointCloud(*cloud, *transform_cloud0, transform_2);
  176. transform_2=Eigen::Affine3f::Identity();
  177. transform_2.rotate(Eigen::AngleAxisf(detect_result.theta, Eigen::Vector3f::UnitZ()));
  178. pcl::transformPointCloud(*transform_cloud0, *transformed_cloud, transform_2);
  179. return true;
  180. }
  181. std::cout << "error: " << error_info << std::endl;
  182. return false;
  183. }