detect_wheel_ceres3d.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #include "detect_wheel_ceres3d.h"
  5. #include "interpolated_grid.hpp"
  6. #include <pcl/common/transforms.h>
  7. class CostFunctor3d
  8. {
  9. private:
  10. const InterpolatedProbabilityGrid m_left_interpolated_grid;
  11. const InterpolatedProbabilityGrid m_right_interpolated_grid;
  12. mutable double m_costs_lf, m_costs_rf, m_costs_lr, m_costs_rr;
  13. pcl::PointCloud<pcl::PointXYZ> m_left_front_cloud; //左前点云
  14. pcl::PointCloud<pcl::PointXYZ> m_right_front_cloud; //右前点云
  15. pcl::PointCloud<pcl::PointXYZ> m_left_rear_cloud; //左后点云
  16. pcl::PointCloud<pcl::PointXYZ> m_right_rear_cloud; //右后点云
  17. public:
  18. CostFunctor3d(pcl::PointCloud<pcl::PointXYZ> left_front, pcl::PointCloud<pcl::PointXYZ> right_front,
  19. pcl::PointCloud<pcl::PointXYZ> left_rear, pcl::PointCloud<pcl::PointXYZ> right_rear,
  20. const HybridGrid& left_interpolated_grid,
  21. const HybridGrid& right_interpolated_grid)
  22. :m_left_interpolated_grid(left_interpolated_grid),m_right_interpolated_grid(right_interpolated_grid)
  23. {
  24. m_left_front_cloud = left_front;
  25. m_right_front_cloud = right_front;
  26. m_left_rear_cloud = left_rear;
  27. m_right_rear_cloud = right_rear;
  28. m_costs_lf = 0.0;
  29. m_costs_rf = 0.0;
  30. m_costs_lr = 0.0;
  31. m_costs_rr = 0.0;
  32. }
  33. template<typename T>
  34. bool operator()(const T *const variable, T *residual) const
  35. {
  36. T cx = variable[0];
  37. T cy = variable[1];
  38. T theta = variable[2];
  39. T length = variable[3];
  40. T width = variable[4];
  41. T theta_front = variable[5];
  42. //整车旋转
  43. Eigen::Rotation2D<T> rotation(theta);
  44. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  45. //左前偏移
  46. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  47. //右前偏移
  48. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  49. //左后偏移
  50. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  51. //右后偏移
  52. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  53. //前轮旋转
  54. Eigen::Rotation2D<T> rotation_front(theta_front);
  55. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  56. //左前轮
  57. int left_front_num = m_left_front_cloud.size();
  58. for (int i = 0; i < m_left_front_cloud.size(); ++i)
  59. {
  60. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud[i].x) - cx),
  61. (T(m_left_front_cloud[i].y) - cy));
  62. //减去经过车辆旋转计算的左前中心
  63. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  64. //旋转
  65. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  66. residual[i] = T(1.0) - m_left_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  67. T(m_left_front_cloud[i].z));
  68. }
  69. //右前轮
  70. int right_front_num = m_right_front_cloud.size();
  71. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  72. {
  73. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud[i].x) - cx),
  74. (T(m_right_front_cloud[i].y) - cy));
  75. //减去经过车辆旋转计算的左前中心
  76. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  77. //旋转
  78. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  79. residual[left_front_num + i] = T(1.0) - m_right_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  80. T(m_right_front_cloud[i].z));
  81. }
  82. //左后轮
  83. int left_rear_num = m_left_rear_cloud.size();
  84. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  85. {
  86. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud[i].x) - cx),
  87. (T(m_left_rear_cloud[i].y) - cy));
  88. //减去经过车辆旋转计算的左前中心
  89. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  90. residual[left_front_num + right_front_num + i] = T(1.0) -
  91. m_left_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  92. T(m_left_rear_cloud[i].z));
  93. }
  94. //右后轮
  95. int right_rear_num = m_right_rear_cloud.size();
  96. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  97. {
  98. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud[i].x) - cx),
  99. (T(m_right_rear_cloud[i].y) - cy));
  100. //减去经过车辆旋转计算的左前中心
  101. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  102. residual[left_front_num + right_front_num + left_rear_num+i] = T(1.0) -
  103. m_right_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  104. T(m_right_rear_cloud[i].z));
  105. }
  106. return true;
  107. }
  108. };
  109. detect_wheel_ceres3d::detect_wheel_ceres3d(pcl::PointCloud<pcl::PointXYZ>::Ptr left_grid_cloud,
  110. pcl::PointCloud<pcl::PointXYZ>::Ptr right_grid_cloud)
  111. {
  112. float del_x=0.05;
  113. float del_y=0.03;
  114. float del_z=0.05;
  115. Eigen::Matrix3f delta=Eigen::MatrixXf::Identity(3,3);
  116. delta(0,0)=del_x*del_x;
  117. delta(1,1)=del_y*del_y;
  118. delta(2,2)=del_z*del_z;
  119. Eigen::Matrix3f delta_inv=delta.inverse();
  120. Eigen::Vector3f d(0,0,0.02);
  121. Eigen::MatrixXf ce=-0.5*((d).transpose()*delta_inv*(d));
  122. float cut_p=exp(ce(0,0));
  123. // std::cout << "1111" << std::endl;
  124. float resolution=0.01;
  125. mp_left_grid=new HybridGrid(resolution);
  126. mp_right_grid=new HybridGrid(resolution);
  127. // std::cout << "2222" << std::endl;
  128. for(int i=0;i<left_grid_cloud->size();++i)
  129. {
  130. pcl::PointXYZ pt=left_grid_cloud->points[i];
  131. Eigen::Vector3f u(pt.x,pt.y,pt.z);
  132. for(float x=pt.x-0.1;x<pt.x+0.1;x+=mp_left_grid->resolution())
  133. {
  134. // std::cout << "aa" << std::endl;
  135. for(float y=pt.y-0.1;y<pt.y+0.1;y+=mp_left_grid->resolution())
  136. {
  137. // std::cout << "bb" << std::endl;
  138. for(float z=pt.z-0.1;z<pt.z+0.1;z+=mp_left_grid->resolution())
  139. {
  140. // std::cout << "cc" << std::endl;
  141. Eigen::Vector3f p(x,y,z);
  142. Eigen::MatrixXf B=-0.5*((p-u).transpose()*delta_inv*(p-u));
  143. float prob=exp(B(0,0));
  144. if(prob>cut_p)
  145. prob=cut_p;
  146. Eigen::Array3i index=mp_left_grid->GetCellIndex(p);
  147. // std::cout << "dd "<< index << std::endl;
  148. if(mp_left_grid->GetProbability(index)<prob){
  149. // std::cout << "e1 "<<index << std::endl;
  150. mp_left_grid->SetProbability(index,prob);
  151. // std::cout << "e2 "<<index << std::endl;
  152. }
  153. // std::cout << "ee "<<index << std::endl;
  154. }
  155. }
  156. }
  157. }
  158. std::cout << "3333" << std::endl;
  159. for(int i=0;i<right_grid_cloud->size();++i)
  160. {
  161. pcl::PointXYZ pt=right_grid_cloud->points[i];
  162. Eigen::Vector3f u(pt.x,pt.y,pt.z);
  163. for(float x=pt.x-0.1;x<pt.x+0.1;x+=mp_right_grid->resolution())
  164. {
  165. for(float y=pt.y-0.1;y<pt.y+0.1;y+=mp_right_grid->resolution())
  166. {
  167. for(float z=pt.z-0.1;z<pt.z+0.1;z+=mp_right_grid->resolution())
  168. {
  169. Eigen::Vector3f p(x,y,z);
  170. Eigen::MatrixXf B=-0.5*((p-u).transpose()*delta_inv*(p-u));
  171. float prob=exp(B(0,0));
  172. if(prob>cut_p)
  173. prob=cut_p;
  174. Eigen::Array3i index=mp_right_grid->GetCellIndex(p);
  175. if(mp_right_grid->GetProbability(index)<prob)
  176. mp_right_grid->SetProbability(index,prob);
  177. }
  178. }
  179. }
  180. }
  181. std::cout << "4444" << std::endl;
  182. // save_model("/home/zx/zzw/catkin_ws/src/feature_extra");
  183. }
  184. #include "point_tool.h"
  185. void detect_wheel_ceres3d::save_model(std::string dir)
  186. {
  187. InterpolatedProbabilityGrid inter_grid(*mp_left_grid);
  188. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_grid(new pcl::PointCloud<pcl::PointXYZRGB>);
  189. for(int x=0;x<mp_left_grid->grid_size();++x)
  190. {
  191. for(int y=0;y<mp_left_grid->grid_size();++y)
  192. {
  193. for(int z=0;z<mp_left_grid->grid_size();++z)
  194. {
  195. Eigen::Array3i index(x-mp_left_grid->grid_size()/2,
  196. y-mp_left_grid->grid_size()/2,z-mp_left_grid->grid_size()/2);
  197. Eigen::Vector3f pt=mp_left_grid->GetCenterOfCell(index);
  198. float prob=inter_grid.GetInterpolatedValue(double(pt[0]),double(pt[1]),double(pt[2]));
  199. if(prob>0.01)
  200. {
  201. Eigen::Vector3f pt=mp_left_grid->GetCenterOfCell(index);
  202. int rgb=int((prob-0.01)*255);
  203. pcl::PointXYZRGB point;
  204. point.x=pt[0];
  205. point.y=pt[1];
  206. point.z=pt[2];
  207. point.r=rgb;
  208. point.g=0;
  209. point.b=255-rgb;
  210. cloud_grid->push_back(point);
  211. }
  212. }
  213. }
  214. }
  215. InterpolatedProbabilityGrid right_grid(*mp_right_grid);
  216. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_right_grid(new pcl::PointCloud<pcl::PointXYZRGB>);
  217. for(int x=0;x<mp_right_grid->grid_size();++x)
  218. {
  219. for(int y=0;y<mp_right_grid->grid_size();++y)
  220. {
  221. for(int z=0;z<mp_right_grid->grid_size();++z)
  222. {
  223. Eigen::Array3i index(x-mp_right_grid->grid_size()/2,
  224. y-mp_right_grid->grid_size()/2,z-mp_right_grid->grid_size()/2);
  225. Eigen::Vector3f pt=mp_right_grid->GetCenterOfCell(index);
  226. float prob=right_grid.GetInterpolatedValue(double(pt[0]),double(pt[1]),double(pt[2]));
  227. if(prob>0.01)
  228. {
  229. Eigen::Vector3f pt=mp_right_grid->GetCenterOfCell(index);
  230. int rgb=int((prob-0.01)*255);
  231. pcl::PointXYZRGB point;
  232. point.x=pt[0];
  233. point.y=pt[1];
  234. point.z=pt[2];
  235. point.r=rgb;
  236. point.g=0;
  237. point.b=255-rgb;
  238. cloud_right_grid->push_back(point);
  239. }
  240. }
  241. }
  242. }
  243. //std::cout<<" save model :"<<dir<<std::endl;
  244. //save_cloud_txt(cloud_grid,dir+"/left_model.txt");
  245. //save_cloud_txt(cloud_right_grid,dir+"/right_model.txt");
  246. }
  247. detect_wheel_ceres3d::~detect_wheel_ceres3d(){
  248. delete mp_left_grid;
  249. delete mp_right_grid;
  250. mp_left_grid= nullptr;
  251. mp_right_grid= nullptr;
  252. }
  253. bool detect_wheel_ceres3d::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cloud_vec,
  254. Detect_result &detect_result, std::string &error_info)
  255. {
  256. error_info = "";
  257. //清理点云
  258. m_left_front_cloud.clear();
  259. m_right_front_cloud.clear();
  260. m_left_rear_cloud.clear();
  261. m_right_rear_cloud.clear();
  262. //重新计算点云,按方位分割
  263. //第一步,计算整体中心,主轴方向
  264. pcl::PointCloud<pcl::PointXYZ> cloud_all;
  265. for (int i = 0; i < cloud_vec.size(); ++i)
  266. {
  267. cloud_all += (*cloud_vec[i]);
  268. }
  269. // std::cout<<"cloud size: "<<cloud_all.size()<<std::endl;
  270. if (cloud_all.size() < 20)
  271. return false;
  272. Eigen::Vector4f centroid;
  273. pcl::compute3DCentroid(cloud_all, centroid);
  274. double center_x = centroid[0];
  275. double center_y = centroid[1];
  276. //计算外接旋转矩形
  277. std::vector<cv::Point2f> points_cv;
  278. for (int i = 0; i < cloud_all.size(); ++i)
  279. {
  280. points_cv.push_back(cv::Point2f(cloud_all[i].x, cloud_all[i].y));
  281. }
  282. cv::RotatedRect rotate_rect = cv::minAreaRect(points_cv);
  283. //计算旋转矩形与X轴的夹角
  284. cv::Point2f vec;
  285. cv::Point2f vertice[4];
  286. rotate_rect.points(vertice);
  287. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  288. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  289. // 寻找长边,倾角为长边与x轴夹角
  290. if (len1 > len2)
  291. {
  292. vec.x = vertice[0].x - vertice[1].x;
  293. vec.y = vertice[0].y - vertice[1].y;
  294. }
  295. else
  296. {
  297. vec.x = vertice[1].x - vertice[2].x;
  298. vec.y = vertice[1].y - vertice[2].y;
  299. }
  300. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  301. // printf("rect theta: %.3f\n",angle_x);
  302. //第二步, 将每份点云旋转回去,计算点云重心所在象限
  303. for (int i = 0; i < cloud_vec.size(); ++i)
  304. {
  305. pcl::PointCloud<pcl::PointXYZ> cloud = (*cloud_vec[i]);
  306. Eigen::Affine3f traslation = Eigen::Affine3f::Identity();//初始化变换矩阵为单位矩阵
  307. // 平移
  308. traslation.translation() << -center_x, -center_y, 0.0;
  309. pcl::PointCloud<pcl::PointXYZ> translate_cloud;
  310. pcl::transformPointCloud(cloud, translate_cloud, traslation);
  311. // 旋转; Z 轴上旋转angle_x 弧度,Y轴上旋转0弧度
  312. Eigen::Affine3f rotation = Eigen::Affine3f::Identity();
  313. rotation.rotate(Eigen::AngleAxisf(-angle_x * M_PI / 180.0, Eigen::Vector3f::UnitZ()));
  314. pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
  315. pcl::transformPointCloud(translate_cloud, transformed_cloud, rotation);
  316. //计算重心
  317. Eigen::Vector4f centroid;
  318. pcl::compute3DCentroid(transformed_cloud, centroid);
  319. double x = centroid[0];
  320. double y = centroid[1];
  321. //计算象限
  322. if (x > 0 && y > 0)
  323. {
  324. //第一象限
  325. m_left_front_cloud = cloud;
  326. }
  327. if (x > 0 && y < 0)
  328. {
  329. //第四象限
  330. m_right_front_cloud = cloud;
  331. }
  332. if (x < 0 && y > 0)
  333. {
  334. //第二象限
  335. m_left_rear_cloud = cloud;
  336. }
  337. if (x < 0 && y < 0)
  338. {
  339. //第三象限
  340. m_right_rear_cloud = cloud;
  341. }
  342. }
  343. // 多次优化,获取最佳优化结果
  344. detect_result.cx = center_x;
  345. detect_result.cy = center_y;
  346. detect_result.wheel_base=std::max(len1,len2);
  347. // 已计算次数,初始传入值正常,之后solve函数会修改初始值,需要恢复角度单位为弧度
  348. int calc_count = 0;
  349. // double final_theta = 0;
  350. // 误差结构体,保存左前、右前、左后、右后、整体平均误差
  351. Loss_result loss_result;
  352. // 平均误差值,用于获取最小整体平均误差
  353. double avg_loss = 100;
  354. // 定义图像列数,控制图像大小
  355. int map_cols = 800;
  356. // 优化后图像行数,用于保存优化后结果图像
  357. int optimized_map_rows = 200;
  358. // 优化结果
  359. bool solve_result = false;
  360. double total_solve_time = 0;
  361. bool stop_sign = false;
  362. Detect_result t_detect_result = detect_result;
  363. // 寻找最小loss值对应的初始旋转角
  364. t_detect_result.theta = (-angle_x ) * M_PI / 180.0;
  365. Loss_result t_loss_result;
  366. t_loss_result.total_avg_loss = 1000;
  367. //输出角度已变化,需恢复成弧度
  368. if (calc_count > 0)
  369. {
  370. t_detect_result.front_theta *= (-M_PI) / 180.0;
  371. }
  372. std::string t_error_info;
  373. bool current_result = Solve(t_detect_result, t_loss_result, t_error_info);
  374. error_info = t_error_info;
  375. // std::cout<<"current_result: "<<current_result<<std::endl;
  376. if (current_result)
  377. {
  378. avg_loss = t_loss_result.total_avg_loss;
  379. // final_theta = -input_vars[2] * M_PI / 180.0;
  380. detect_result = t_detect_result;
  381. detect_result.loss = t_loss_result;
  382. solve_result = current_result;
  383. loss_result = t_loss_result;
  384. }
  385. return solve_result;
  386. }
  387. void detect_wheel_ceres3d::get_costs(double* variable,double &lf, double &rf, double &lr, double &rr)
  388. {
  389. double losses[4]={0};
  390. double cx = variable[0];
  391. double cy = variable[1];
  392. double theta = variable[2];
  393. double length = variable[3];
  394. double width = variable[4];
  395. double theta_front = variable[5];
  396. //整车旋转
  397. Eigen::Rotation2D<double> rotation(theta);
  398. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  399. //左前偏移
  400. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  401. //右前偏移
  402. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  403. //左后偏移
  404. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  405. //右后偏移
  406. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  407. //前轮旋转
  408. Eigen::Rotation2D<double> rotation_front(theta_front);
  409. Eigen::Matrix<double, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  410. InterpolatedProbabilityGrid left_interpolated_grid(*mp_left_grid);
  411. InterpolatedProbabilityGrid right_interpolated_grid(*mp_right_grid);
  412. //左前轮
  413. int left_front_num = m_left_front_cloud.size();
  414. m_left_front_transformed_cloud.clear();
  415. for (int i = 0; i < m_left_front_cloud.size(); ++i)
  416. {
  417. const Eigen::Matrix<double, 2, 1> point((double(m_left_front_cloud[i].x) - cx),
  418. (double(m_left_front_cloud[i].y) - cy));
  419. //减去经过车辆旋转计算的左前中心
  420. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  421. //旋转
  422. const Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  423. losses[0] += 1.0 - left_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  424. double(m_left_front_cloud[i].z));
  425. m_left_front_transformed_cloud.push_back(pcl::PointXYZ(point_rotation[0],point_rotation[1],m_left_front_cloud[i].z));
  426. }
  427. //右前轮
  428. int right_front_num = m_right_front_cloud.size();
  429. m_right_front_transformed_cloud.clear();
  430. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  431. {
  432. const Eigen::Matrix<double, 2, 1> point((double(m_right_front_cloud[i].x) - cx),
  433. (double(m_right_front_cloud[i].y) - cy));
  434. //减去经过车辆旋转计算的左前中心
  435. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  436. //旋转
  437. const Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  438. losses[1]+= 1.0 - right_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  439. double(m_right_front_cloud[i].z));
  440. m_right_front_transformed_cloud.push_back(pcl::PointXYZ(point_rotation[0],point_rotation[1],
  441. double(m_right_front_cloud[i].z)));
  442. }
  443. //左后轮
  444. int left_rear_num = m_left_rear_cloud.size();
  445. m_left_rear_transformed_cloud.clear();
  446. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  447. {
  448. const Eigen::Matrix<double, 2, 1> point((double(m_left_rear_cloud[i].x) - cx),
  449. (double(m_left_rear_cloud[i].y) - cy));
  450. //减去经过车辆旋转计算的左前中心
  451. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  452. losses[2] += 1.0 -
  453. left_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  454. double(m_left_rear_cloud[i].z));
  455. m_left_rear_transformed_cloud.push_back(pcl::PointXYZ(tanslate_point[0],tanslate_point[1],
  456. double(m_left_rear_cloud[i].z)));
  457. }
  458. //右后轮
  459. int right_rear_num = m_right_rear_cloud.size();
  460. m_right_rear_transformed_cloud.clear();
  461. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  462. {
  463. const Eigen::Matrix<double, 2, 1> point((double(m_right_rear_cloud[i].x) - cx),
  464. (double(m_right_rear_cloud[i].y) - cy));
  465. //减去经过车辆旋转计算的左前中心
  466. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  467. losses[3]+= 1.0 -
  468. right_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  469. double(m_right_rear_cloud[i].z));
  470. m_right_rear_transformed_cloud.push_back(pcl::PointXYZ(tanslate_point[0],tanslate_point[1],
  471. double(m_right_rear_cloud[i].z)));
  472. }
  473. lf=losses[0];
  474. rf=losses[1];
  475. lr =losses[2];
  476. rr =losses[3];
  477. }
  478. void detect_wheel_ceres3d::save_debug_data(std::string dir )
  479. {
  480. save_cloud_txt(m_left_front_transformed_cloud.makeShared(),dir+"/left_front_tranformed.txt");
  481. save_cloud_txt(m_right_front_transformed_cloud.makeShared(),dir+"/right_front_tranformed.txt");
  482. save_cloud_txt(m_left_rear_transformed_cloud.makeShared(),dir+"/left_rear_tranformed.txt");
  483. save_cloud_txt(m_right_rear_transformed_cloud.makeShared(),dir+"/right_rear_tranformed.txt");
  484. }
  485. bool detect_wheel_ceres3d::Solve(Detect_result &detect_result, Loss_result &loss_result, std::string &error_info)
  486. {
  487. double cx=detect_result.cx;
  488. double cy=detect_result.cy;
  489. double init_theta=detect_result.theta;
  490. double init_wheel_base=2.7;
  491. if(detect_result.wheel_base>2.55 && detect_result.wheel_base<3.2)
  492. init_wheel_base=detect_result.wheel_base;
  493. double init_width=1.85;
  494. double init_theta_front=0*M_PI/180.0;
  495. double variable[] = {cx, cy, init_theta, init_wheel_base, init_width, init_theta_front};
  496. /*printf("init solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  497. variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);*/
  498. // 第二部分:构建寻优问题
  499. ceres::Problem problem;
  500. CostFunctor3d *cost_func = new CostFunctor3d(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,
  501. *mp_left_grid,*mp_right_grid);
  502. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  503. ceres::CostFunction* cost_function =new
  504. ceres::AutoDiffCostFunction<CostFunctor3d, ceres::DYNAMIC, 6>(
  505. cost_func,
  506. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  507. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  508. //第三部分: 配置并运行求解器
  509. ceres::Solver::Options options;
  510. options.use_nonmonotonic_steps=false;
  511. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  512. //options.logging_type = ceres::LoggingType::SILENT;
  513. options.max_num_iterations=500;
  514. options.num_threads=2;
  515. options.minimizer_progress_to_stdout = false;//输出到cout
  516. ceres::Solver::Summary summary;//优化信息
  517. ceres::Solve(options, &problem, &summary);//求解!!!
  518. double loss=summary.final_cost/(m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  519. detect_result.cx=variable[0];
  520. detect_result.cy=variable[1];
  521. detect_result.theta=(-variable[2])*180.0/M_PI;
  522. detect_result.wheel_base=variable[3];
  523. detect_result.width=variable[4];
  524. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  525. if(detect_result.theta>180.0)
  526. detect_result.theta=detect_result.theta-180.0;
  527. if(detect_result.theta<0)
  528. detect_result.theta+=180.0;
  529. if(summary.iterations.size()<=1)
  530. return false;
  531. if(summary.iterations[summary.iterations.size()-1].iteration<=1)
  532. return false;
  533. /*printf("it : %d ,summary loss: %.5f \n",
  534. summary.iterations.size(),loss);*/
  535. if (detect_result.width < 1.25 || detect_result.width > 2.000 || detect_result.wheel_base > 3.15 || detect_result.wheel_base < 2.200)
  536. {
  537. error_info.append(std::string("宽度(1.25, 2.00) 轴距(2.20, 3.15): ").append(
  538. std::to_string(detect_result.width).append(", ").append(
  539. std::to_string(detect_result.wheel_base)).append("\t")));
  540. return false;
  541. }
  542. if(detect_result.theta > 120 || detect_result.theta < 60)
  543. {
  544. error_info.append("车身角度错误 ").append(std::to_string(detect_result.theta)).append("\t");
  545. // LOG(WARNING) <<"总角度错误 "<<detect_result.theta;
  546. return false;
  547. }
  548. if(fabs(detect_result.front_theta)>35)
  549. {
  550. error_info.append("前轮角度错误 ").append(std::to_string(detect_result.front_theta)).append("\t");
  551. return false;
  552. }
  553. // 将loss传出
  554. if(cost_func!=nullptr)
  555. {
  556. double costs_lf, costs_rf, costs_lr, costs_rr;
  557. get_costs(variable,costs_lf, costs_rf, costs_lr, costs_rr);
  558. loss_result.lf_loss = costs_lf/float(m_left_front_cloud.size()+1e-6);
  559. loss_result.rf_loss = costs_rf/float(m_right_front_cloud.size()+1e-6);
  560. loss_result.lb_loss = costs_lr/float(m_left_rear_cloud.size()+1e-6);
  561. loss_result.rb_loss = costs_rr/float(m_right_rear_cloud.size()+1e-6);
  562. loss_result.total_avg_loss = loss;
  563. detect_result.loss=loss_result;
  564. if(loss_result.lf_loss>0.4 || loss_result.rf_loss>0.4
  565. ||loss_result.lb_loss>0.4||loss_result.rb_loss>0.4)
  566. {
  567. return false;
  568. }
  569. }
  570. else
  571. {
  572. return false;
  573. }
  574. return true;
  575. }