detect_wheel_ceres3d.h 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #ifndef DETECT_WHEEL_CERES_3D_H
  5. #define DETECT_WHEEL_CERES_3D_H
  6. #include <ceres/ceres.h>
  7. #include <glog/logging.h>
  8. #include <pcl/point_types.h>
  9. #include <pcl/point_cloud.h>
  10. #include <pcl/common/centroid.h>
  11. #include <opencv2/opencv.hpp>
  12. #include <iostream>
  13. #include <string>
  14. #include <chrono>
  15. #include "boost/format.hpp"
  16. #include "hybrid_grid.hpp"
  17. class detect_wheel_ceres3d {
  18. public:
  19. struct Loss_result
  20. {
  21. public:
  22. double lf_loss;
  23. double rf_loss;
  24. double lb_loss;
  25. double rb_loss;
  26. double total_avg_loss;
  27. Loss_result& operator=(const Loss_result& loss_result)
  28. {
  29. this->lf_loss = loss_result.lf_loss;
  30. this->rf_loss = loss_result.rf_loss;
  31. this->lb_loss = loss_result.lb_loss;
  32. this->rb_loss = loss_result.rb_loss;
  33. this->total_avg_loss = loss_result.total_avg_loss;
  34. return *this;
  35. }
  36. };
  37. struct Detect_result
  38. {
  39. public:
  40. double cx;
  41. double cy;
  42. double theta;
  43. double wheel_base;
  44. double width;
  45. double body_width;
  46. double front_theta;
  47. // 220110 added by yct
  48. double single_wheel_width;
  49. double single_wheel_length;
  50. bool success;
  51. Loss_result loss;
  52. Detect_result& operator=(const Detect_result& detect_result)
  53. {
  54. this->cx = detect_result.cx;
  55. this->cy = detect_result.cy;
  56. this->theta = detect_result.theta;
  57. this->wheel_base = detect_result.wheel_base;
  58. this->width = detect_result.width;
  59. this->front_theta = detect_result.front_theta;
  60. this->single_wheel_width = detect_result.single_wheel_width;
  61. this->single_wheel_length = detect_result.single_wheel_length;
  62. this->success = detect_result.success;
  63. this->body_width=detect_result.body_width;
  64. this->loss=detect_result.loss;
  65. return *this;
  66. }
  67. std::string to_string()
  68. {
  69. char buf[512];
  70. sprintf(buf, "cx:%.3f cy:%.3f th:%.3f wb:%.3f wd:%.3f fth:%.3f suc:%s sww:%.3f swl:%.3f\n", cx, cy, theta, wheel_base, width, front_theta, success ? "true" : "false", single_wheel_width, single_wheel_length);
  71. return std::string(buf);
  72. }
  73. };
  74. detect_wheel_ceres3d(pcl::PointCloud<pcl::PointXYZ>::Ptr left_grid_cloud,
  75. pcl::PointCloud<pcl::PointXYZ>::Ptr right_grid_cloud);
  76. ~detect_wheel_ceres3d();
  77. bool detect(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cloud_vec, Detect_result &detect_result, std::string &error_info);
  78. void save_debug_data(std::string file );
  79. protected:
  80. void save_model(std::string file);
  81. // 投影车轮点云,获取外接矩形,以此矩形中心估算轴距
  82. bool wheebase_estimate(double &wheelbase, double &wheel_width, double &wheel_length);
  83. // 外接矩形估算车轮宽度,以此调整模型比例,此比例变换点云贴合模型
  84. bool wheel_size_estimate(double &wheel_width, double &wheel_length, double car_angle, float &ratio);
  85. // 根据点云计算外接矩形
  86. bool get_wheel_rect(pcl::PointCloud<pcl::PointXYZ> cloud, cv::RotatedRect &rect, double &theta, double &length, double &width);
  87. // 根据点云与模型比例参数更新模型
  88. // 模型更新很慢,通常仅初始化时调用该函数
  89. bool update_model(float ratio = 1.0f);
  90. bool Solve(Detect_result &detect_result, Loss_result &loss_result, std::string &error_info);
  91. void get_costs(double* variable,double &lf, double &rf, double &lr, double &rr);
  92. public:
  93. pcl::PointCloud<pcl::PointXYZ> m_left_front_transformed_cloud; //左前点云
  94. pcl::PointCloud<pcl::PointXYZ> m_right_front_transformed_cloud; //右前点云
  95. pcl::PointCloud<pcl::PointXYZ> m_left_rear_transformed_cloud; //左后点云
  96. pcl::PointCloud<pcl::PointXYZ> m_right_rear_transformed_cloud; //右后点云
  97. pcl::PointCloud<pcl::PointXYZ> m_left_front_cloud; //左前点云
  98. pcl::PointCloud<pcl::PointXYZ> m_right_front_cloud; //右前点云
  99. pcl::PointCloud<pcl::PointXYZ> m_left_rear_cloud; //左后点云
  100. pcl::PointCloud<pcl::PointXYZ> m_right_rear_cloud; //右后点云
  101. private:
  102. HybridGrid* mp_left_grid;
  103. HybridGrid* mp_right_grid;
  104. // 左右模型原始点云, 用于动态调整模型大小
  105. pcl::PointCloud<pcl::PointXYZ> m_left_model_cloud;
  106. pcl::PointCloud<pcl::PointXYZ> m_right_model_cloud;
  107. };
  108. #endif //DETECT_WHEEL_CERES_3D_H