detect_wheel_ceres.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #include "detect_wheel_ceres.h"
  5. #include <ceres/cubic_interpolation.h>
  6. #include <pcl/common/transforms.h>
  7. class CostDynFunc{
  8. std::vector<double> line_l_;
  9. std::vector<double> line_r_;
  10. std::vector<double> line_y_;
  11. double length_;
  12. double width_;
  13. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_front_cloud; //左前点云
  14. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_front_cloud; //右前点云
  15. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_rear_cloud; //左后点云
  16. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_rear_cloud; //右后点云
  17. public:
  18. CostDynFunc(pcl::PointCloud<pcl::PointXYZ>::Ptr left_front,pcl::PointCloud<pcl::PointXYZ>::Ptr right_front,
  19. pcl::PointCloud<pcl::PointXYZ>::Ptr left_rear,pcl::PointCloud<pcl::PointXYZ>::Ptr right_rear,
  20. std::vector<double> linel,std::vector<double> liner,std::vector<double> liney,double width,double length)
  21. {
  22. line_l_=linel;
  23. line_r_=liner;
  24. line_y_=liney;
  25. width_=width;
  26. length_=length;
  27. m_left_front_cloud=left_front;
  28. m_right_front_cloud=right_front;
  29. m_left_rear_cloud=left_rear;
  30. m_right_rear_cloud=right_rear;
  31. }
  32. template <typename T>
  33. bool operator()(const T* const variable, T* residual) const {
  34. T cx = variable[0];
  35. T cy = variable[1];
  36. T theta = variable[2];
  37. T theta_front = variable[3];
  38. //整车旋转
  39. Eigen::Rotation2D<T> rotation(-theta);
  40. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  41. //左前偏移
  42. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(T(-width_ / 2.0), T(length_ / 2.0));
  43. //右前偏移
  44. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(T(width_ / 2.0), T(length_ / 2.0));
  45. //左后偏移
  46. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(T(-width_ / 2.0), T(-length_ / 2.0));
  47. //右后偏移
  48. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(T(width_ / 2.0), T(-length_ / 2.0));
  49. //前轮旋转
  50. Eigen::Rotation2D<T> rotation_front(theta_front);
  51. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  52. ceres::Grid1D<double> grid_l(line_l_.data(),0,line_l_.size());
  53. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_l(grid_l);
  54. ceres::Grid1D<double> grid_r(line_r_.data(),0,line_r_.size());
  55. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_r(grid_r);
  56. ceres::Grid1D<double> grid_y(line_y_.data(),0,line_y_.size());
  57. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_y(grid_y);
  58. //左前轮
  59. int left_front_num = m_left_front_cloud->size();
  60. for (int i = 0; i < m_left_front_cloud->size(); ++i) {
  61. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud->points[i].x) - cx),
  62. (T(m_left_front_cloud->points[i].y) - cy));
  63. //减去经过车辆旋转计算的左前中心
  64. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  65. //旋转
  66. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  67. interpolator_l.Evaluate(point_rotation[0]*T(1000.)+T(200.),&residual[2*i]);
  68. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[2*i+1]);
  69. }
  70. //右前轮
  71. int right_front_num = m_right_front_cloud->size();
  72. for (int i = 0; i < m_right_front_cloud->size(); ++i) {
  73. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud->points[i].x) - cx),
  74. (T(m_right_front_cloud->points[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. interpolator_r.Evaluate(point_rotation[0]*T(1000.)+T(1000.),&residual[2*left_front_num + 2*i]);
  80. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[2*left_front_num+2*i+1]);
  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. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud->points[i].x) - cx),
  86. (T(m_left_rear_cloud->points[i].y) - cy));
  87. //减去经过车辆旋转计算的左前中心
  88. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  89. interpolator_l.Evaluate(tanslate_point[0]*T(1000.)+T(200.),&residual[2*(left_front_num + right_front_num + i)]);
  90. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  91. &residual[2*(left_front_num+right_front_num)+2*i+1]);
  92. }
  93. //右后轮
  94. for (int i = 0; i < m_right_rear_cloud->size(); ++i) {
  95. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud->points[i].x) - cx),
  96. (T(m_right_rear_cloud->points[i].y) - cy));
  97. //减去经过车辆旋转计算的左前中心
  98. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  99. interpolator_r.Evaluate(tanslate_point[0]*T(1000.)+T(1000.),
  100. &residual[2*(left_front_num + right_front_num + left_rear_num + i)]);
  101. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  102. &residual[2*(left_front_num+right_front_num+left_rear_num)+2*i+1]);
  103. }
  104. return true;
  105. }
  106. };
  107. class CostRYFunc{
  108. private:
  109. std::vector<double> line_y_;
  110. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_front_cloud; //左前点云
  111. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_front_cloud; //右前点云
  112. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_rear_cloud; //左后点云
  113. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_rear_cloud; //右后点云
  114. public:
  115. CostRYFunc(pcl::PointCloud<pcl::PointXYZ>::Ptr left_front,pcl::PointCloud<pcl::PointXYZ>::Ptr right_front,
  116. pcl::PointCloud<pcl::PointXYZ>::Ptr left_rear,pcl::PointCloud<pcl::PointXYZ>::Ptr right_rear,
  117. std::vector<double> liney)
  118. {
  119. line_y_=liney;
  120. m_left_front_cloud=left_front;
  121. m_right_front_cloud=right_front;
  122. m_left_rear_cloud=left_rear;
  123. m_right_rear_cloud=right_rear;
  124. }
  125. template <typename T>
  126. bool operator()(const T* const variable, T* residual) const {
  127. T cy = variable[0];
  128. T theta = variable[1];
  129. T length = variable[2];
  130. //整车旋转
  131. Eigen::Rotation2D<T> rotation(-theta);
  132. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  133. //左前偏移
  134. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(-0 / 2.0, length / 2.0);
  135. //右前偏移
  136. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(0 / 2.0, length / 2.0);
  137. //左后偏移
  138. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-0 / 2.0, -length / 2.0);
  139. //右后偏移
  140. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(0 / 2.0, -length / 2.0);
  141. ceres::Grid1D<double> grid_y(line_y_.data(),0,line_y_.size());
  142. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_y(grid_y);
  143. T weight=T(0.3);
  144. //左前轮
  145. int left_front_num = m_left_front_cloud->size();
  146. for (int i = 0; i < m_left_front_cloud->size(); ++i) {
  147. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud->points[i].x)),
  148. (T(m_left_front_cloud->points[i].y)));
  149. const Eigen::Matrix<T, 2, 1> tp(T(0),-cy);
  150. //减去经过车辆旋转计算的左前中心
  151. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix * point +tp- wheel_center_normal_left_front;
  152. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[i]);
  153. residual[i]=residual[i]*weight;
  154. }
  155. //右前轮
  156. int right_front_num = m_right_front_cloud->size();
  157. for (int i = 0; i < m_right_front_cloud->size(); ++i) {
  158. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud->points[i].x) ),
  159. (T(m_right_front_cloud->points[i].y)));
  160. const Eigen::Matrix<T, 2, 1> tp(T(0),-cy);
  161. //减去经过车辆旋转计算的左前中心
  162. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix * point +tp- wheel_center_normal_right_front;
  163. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[left_front_num+i]);
  164. residual[left_front_num+i]=residual[left_front_num+i]*weight;
  165. }
  166. //左后轮
  167. int left_rear_num = m_left_rear_cloud->size();
  168. for (int i = 0; i < m_left_rear_cloud->size(); ++i) {
  169. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud->points[i].x)),
  170. (T(m_left_rear_cloud->points[i].y)));
  171. const Eigen::Matrix<T, 2, 1> tp(T(0),-cy);
  172. //减去经过车辆旋转计算的左前中心
  173. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point +tp- wheel_center_normal_left_rear;
  174. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  175. &residual[(left_front_num+right_front_num)+i]);
  176. }
  177. //右后轮
  178. for (int i = 0; i < m_right_rear_cloud->size(); ++i) {
  179. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud->points[i].x)),
  180. (T(m_right_rear_cloud->points[i].y)));
  181. const Eigen::Matrix<T, 2, 1> tp(T(0),-cy);
  182. //减去经过车辆旋转计算的左前中心
  183. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point +tp- wheel_center_normal_right_rear;
  184. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  185. &residual[left_front_num+right_front_num+left_rear_num+i]);
  186. }
  187. return true;
  188. }
  189. private:
  190. };
  191. class CostXYWFFunc{
  192. std::vector<double> line_l_;
  193. std::vector<double> line_r_;
  194. std::vector<double> line_y_;
  195. double length_;
  196. double theta_;
  197. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_front_cloud; //左前点云
  198. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_front_cloud; //右前点云
  199. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_rear_cloud; //左后点云
  200. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_rear_cloud; //右后点云
  201. public:
  202. CostXYWFFunc(pcl::PointCloud<pcl::PointXYZ>::Ptr left_front,pcl::PointCloud<pcl::PointXYZ>::Ptr right_front,
  203. pcl::PointCloud<pcl::PointXYZ>::Ptr left_rear,pcl::PointCloud<pcl::PointXYZ>::Ptr right_rear,
  204. std::vector<double> linel,std::vector<double> liner,std::vector<double> liney,
  205. double theta,double length)
  206. {
  207. line_l_=linel;
  208. line_r_=liner;
  209. line_y_=liney;
  210. length_=length;
  211. theta_=theta;
  212. m_left_front_cloud=left_front;
  213. m_right_front_cloud=right_front;
  214. m_left_rear_cloud=left_rear;
  215. m_right_rear_cloud=right_rear;
  216. }
  217. template <typename T>
  218. bool operator()(const T* const variable, T* residual) const {
  219. T cx = variable[0];
  220. T cy = variable[1];
  221. T width = variable[2];
  222. T theta_front = variable[3];
  223. T theta=T(theta_);
  224. //整车旋转
  225. Eigen::Rotation2D<T> rotation(-theta);
  226. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  227. //左前偏移
  228. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(-width / 2.0, T(length_) / 2.0);
  229. //右前偏移
  230. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(width / 2.0, T(length_) / 2.0);
  231. //左后偏移
  232. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-width / 2.0, -T(length_) / 2.0);
  233. //右后偏移
  234. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(width / 2.0, -T(length_) / 2.0);
  235. //前轮旋转
  236. Eigen::Rotation2D<T> rotation_front(theta_front);
  237. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  238. T weight=T(0.5);
  239. ceres::Grid1D<double> grid_l(line_l_.data(),0,line_l_.size());
  240. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_l(grid_l);
  241. ceres::Grid1D<double> grid_r(line_r_.data(),0,line_r_.size());
  242. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_r(grid_r);
  243. ceres::Grid1D<double> grid_y(line_y_.data(),0,line_y_.size());
  244. ceres::CubicInterpolator<ceres::Grid1D<double>> interpolator_y(grid_y);
  245. //左前轮
  246. int left_front_num = m_left_front_cloud->size();
  247. for (int i = 0; i < m_left_front_cloud->size(); ++i) {
  248. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud->points[i].x) -cx),
  249. (T(m_left_front_cloud->points[i].y) - cy));
  250. //减去经过车辆旋转计算的左前中心
  251. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  252. //旋转
  253. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  254. interpolator_l.Evaluate(point_rotation[0]*T(1000.)+T(200.),&residual[2*i]);
  255. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[2*i+1]);
  256. residual[2*i]=residual[2*i]*weight;
  257. }
  258. //右前轮
  259. int right_front_num = m_right_front_cloud->size();
  260. for (int i = 0; i < m_right_front_cloud->size(); ++i) {
  261. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud->points[i].x) - cx),
  262. (T(m_right_front_cloud->points[i].y) - cy));
  263. //减去经过车辆旋转计算的左前中心
  264. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  265. //旋转
  266. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  267. interpolator_r.Evaluate(point_rotation[0]*T(1000.)+T(1000.),&residual[2*left_front_num + 2*i]);
  268. interpolator_y.Evaluate(point_rotation[1]*T(1000.)+T(1000.),&residual[2*left_front_num+2*i+1]);
  269. residual[2*left_front_num + 2*i]=residual[2*left_front_num + 2*i]*weight;
  270. }
  271. //左后轮
  272. int left_rear_num = m_left_rear_cloud->size();
  273. for (int i = 0; i < m_left_rear_cloud->size(); ++i) {
  274. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud->points[i].x) - cx),
  275. (T(m_left_rear_cloud->points[i].y) - cy));
  276. //减去经过车辆旋转计算的左前中心
  277. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  278. interpolator_l.Evaluate(tanslate_point[0]*T(1000.)+T(200.),&residual[2*(left_front_num + right_front_num + i)]);
  279. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  280. &residual[2*(left_front_num+right_front_num)+2*i+1]);
  281. }
  282. //右后轮
  283. for (int i = 0; i < m_right_rear_cloud->size(); ++i) {
  284. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud->points[i].x) - cx),
  285. (T(m_right_rear_cloud->points[i].y) - cy));
  286. //减去经过车辆旋转计算的左前中心
  287. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  288. interpolator_r.Evaluate(tanslate_point[0]*T(1000.)+T(1000.),
  289. &residual[2*(left_front_num + right_front_num + left_rear_num + i)]);
  290. interpolator_y.Evaluate(tanslate_point[1]*T(1000.)+T(1000.),
  291. &residual[2*(left_front_num+right_front_num+left_rear_num)+2*i+1]);
  292. }
  293. return true;
  294. }
  295. };
  296. detect_wheel_ceres::detect_wheel_ceres()
  297. {
  298. FILE* filel= fopen("./cuve_l.txt","w");
  299. for(int i=0;i<1200;i++){
  300. double x=double(i-200)*0.001;
  301. double y=std::max(1.0/(1.+exp(-400.*(-x-0.02))) , 1.-exp(-x*x));
  302. m_line_l.push_back(y);
  303. fprintf(filel,"%f %f 0\n",x,y);
  304. }
  305. fclose(filel);
  306. FILE* filer= fopen("./cuve_r.txt","w");
  307. for(int i=0;i<1200;i++){
  308. double x=double(i-1000)*0.001;
  309. double y=std::max(1.0/(1.+exp(-400.*(x-0.02))) , 1.-exp(-x*x));
  310. m_line_r.push_back(y);
  311. fprintf(filer,"%f %f 0\n",x,y);
  312. }
  313. fclose(filer);
  314. FILE* filey= fopen("./cuve_y.txt","w");
  315. for(int i=0;i<2000;i++){
  316. double x=double(i-1000)*0.001;
  317. m_line_y.push_back(1.-exp(-0.5*x*x));
  318. m_line_y_2stp.push_back(1.-exp(-2*x*x));
  319. fprintf(filey,"%f %f 0\n",x,1.-exp(-0.5*x*x));
  320. fprintf(filey,"%f %f 0\n",x,1.-exp(-2*x*x));
  321. }
  322. fclose(filey);
  323. }
  324. detect_wheel_ceres::~detect_wheel_ceres(){}
  325. bool detect_wheel_ceres::detect_dynP(pcl::PointCloud<pcl::PointXYZ>::Ptr cl1,pcl::PointCloud<pcl::PointXYZ>::Ptr cl2,
  326. pcl::PointCloud<pcl::PointXYZ>::Ptr cl3,pcl::PointCloud<pcl::PointXYZ>::Ptr cl4,
  327. float& cx,float& cy,float& theta,float& wheel_base,float& width,
  328. float& front_theta,float& loss){
  329. m_left_front_cloud= filter(cl1,1.5);
  330. m_right_front_cloud=filter(cl2,1.5);
  331. m_left_rear_cloud= filter(cl3,1.5);
  332. m_right_rear_cloud= filter(cl4,1.5);
  333. double variable[] = {cx,cy,theta,front_theta};
  334. auto t1=std::chrono::steady_clock::now();
  335. // 第二部分:构建寻优问题
  336. ceres::Problem problem;
  337. ceres::CostFunction* cost_function =new
  338. ceres::AutoDiffCostFunction<CostDynFunc, ceres::DYNAMIC, 4>(
  339. new CostDynFunc(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,
  340. m_line_l,m_line_r,m_line_y,width,wheel_base),
  341. 2*(m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size()));
  342. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  343. //第三部分: 配置并运行求解器
  344. ceres::Solver::Options options;
  345. options.use_nonmonotonic_steps=false;
  346. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  347. options.max_num_iterations=1000;
  348. options.num_threads=2;
  349. options.minimizer_progress_to_stdout = false;//输出到cout
  350. ceres::Solver::Summary summary;//优化信息
  351. ceres::Solve(options, &problem, &summary);//求解!!!
  352. auto t2=std::chrono::steady_clock::now();
  353. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t2 - t1);
  354. double time= double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  355. loss=summary.final_cost/(m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size());
  356. cx=variable[0];
  357. cy=variable[1];
  358. theta=variable[2];
  359. front_theta=variable[3];
  360. if(loss>0.05){
  361. return false;
  362. }
  363. //save(*m_left_front_cloud,*m_right_front_cloud,*m_left_rear_cloud,*m_right_rear_cloud,cx,cy,theta,wheel_base,width,front_theta);
  364. return true;
  365. }
  366. bool detect_wheel_ceres::detect_fall(pcl::PointCloud<pcl::PointXYZ>::Ptr cl1,pcl::PointCloud<pcl::PointXYZ>::Ptr cl2,
  367. pcl::PointCloud<pcl::PointXYZ>::Ptr cl3,pcl::PointCloud<pcl::PointXYZ>::Ptr cl4,
  368. float& cx,float& cy,float& theta,float& wheel_base,
  369. float& width,float& front_theta,float& loss){
  370. pcl::PointXYZ tp1,tp2,tp3,tp4;
  371. float yaw1=0.0;
  372. float yaw2=0.0;
  373. float yaw3=0.0;
  374. float yaw4=0.0;
  375. pcl::PointCloud<pcl::PointXYZ>::Ptr out1,out2,out3,out4;
  376. FallModel::fall(cl1,out1,tp1,yaw1,eNagtive);
  377. FallModel::fall(cl2,out2,tp2,yaw2,ePositive);
  378. FallModel::fall(cl3,out3,tp3,yaw3,eNagtive);
  379. FallModel::fall(cl4,out4,tp4,yaw4,ePositive);
  380. printf("yaw: %f %f %f %f\n",yaw1*180.0/M_PI,yaw2*180.0/M_PI,yaw3*180.0/M_PI,yaw4*180.0/M_PI);
  381. float angle_max = 10 * M_PI / 180.0;
  382. if (fabs(yaw1) > angle_max || fabs(yaw1) > angle_max || fabs(yaw1) > angle_max || fabs(yaw1) > angle_max) {
  383. static int error_index = 0;
  384. LOG(ERROR) << "left front cloud result: tp " << tp1 << " yaw " << yaw1;
  385. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/cl1_" + std::to_string(error_index) + ".txt", cl1);
  386. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/out1_" + std::to_string(error_index) + ".txt", out1);
  387. LOG(ERROR) << "left front cloud result: tp " << tp2 << " yaw " << yaw2;
  388. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/cl2_" + std::to_string(error_index) + ".txt", cl2);
  389. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/out2_" + std::to_string(error_index) + ".txt", out2);
  390. LOG(ERROR) << "left front cloud result: tp " << tp3 << " yaw " << yaw3;
  391. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/cl3_" + std::to_string(error_index) + ".txt", cl3);
  392. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/out3_" + std::to_string(error_index) + ".txt", out3);
  393. LOG(ERROR) << "left front cloud result: tp " << tp4 << " yaw " << yaw4;
  394. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/cl4_" + std::to_string(error_index) + ".txt", cl4);
  395. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/error/out4_" + std::to_string(error_index) + ".txt", out4);
  396. error_index++;
  397. }
  398. return true;
  399. }
  400. bool detect_wheel_ceres::detect_2Step(pcl::PointCloud<pcl::PointXYZ>::Ptr cl1,pcl::PointCloud<pcl::PointXYZ>::Ptr cl2,
  401. pcl::PointCloud<pcl::PointXYZ>::Ptr cl3,pcl::PointCloud<pcl::PointXYZ>::Ptr cl4,
  402. float& cx,float& cy,float& theta,float& wheel_base,float& width,
  403. float& front_theta,float& loss){
  404. m_left_front_cloud= filter(cl1,1.5);
  405. m_right_front_cloud=filter(cl2,1.5);
  406. m_left_rear_cloud= filter(cl3,1.5);
  407. m_right_rear_cloud= filter(cl4,1.5);
  408. bool ryl=detect_RYL(cl1,cl2,cl3,cl4,cx,cy,theta,wheel_base,width,front_theta,loss);
  409. if(ryl==false) return ryl;
  410. bool xwf=detect_XWF(cl1,cl2,cl3,cl4,cx,cy,theta,wheel_base,width,front_theta,loss);
  411. width += 0.04;
  412. return xwf;
  413. }
  414. bool detect_wheel_ceres::detect_RYL(pcl::PointCloud<pcl::PointXYZ>::Ptr cl1,pcl::PointCloud<pcl::PointXYZ>::Ptr cl2,
  415. pcl::PointCloud<pcl::PointXYZ>::Ptr cl3,pcl::PointCloud<pcl::PointXYZ>::Ptr cl4,
  416. float& cx,float& cy,float& theta,float& wheel_base,float& width,
  417. float& front_theta,float& loss){
  418. double variable[] = {cy,theta,wheel_base};
  419. auto t1=std::chrono::steady_clock::now();
  420. // 第二部分:构建寻优问题
  421. ceres::Problem problem;
  422. ceres::CostFunction* cost_function =new
  423. ceres::AutoDiffCostFunction<CostRYFunc, ceres::DYNAMIC, 3>(
  424. new CostRYFunc(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_line_y_2stp),
  425. (m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size()));
  426. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  427. //第三部分: 配置并运行求解器
  428. ceres::Solver::Options options;
  429. options.use_nonmonotonic_steps=false;
  430. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  431. options.max_num_iterations=100;
  432. options.num_threads=2;
  433. options.minimizer_progress_to_stdout = false;//输出到cout
  434. ceres::Solver::Summary summary;//优化信息
  435. ceres::Solve(options, &problem, &summary);//求解!!!
  436. auto t2=std::chrono::steady_clock::now();
  437. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t2 - t1);
  438. double time=double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  439. loss=summary.final_cost/(m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size());
  440. /*printf("loss: %.5f size:%d time:%.5fs\n",loss,m_left_front_cloud->size()+m_right_front_cloud->size()+
  441. m_left_rear_cloud->size()+m_right_rear_cloud->size(),time);*/
  442. //cy=variable[0];
  443. theta=variable[1];
  444. wheel_base=variable[2];
  445. if(loss>0.05){
  446. return false;
  447. }
  448. return true;
  449. }
  450. bool detect_wheel_ceres::detect_XWF(pcl::PointCloud<pcl::PointXYZ>::Ptr cl1,pcl::PointCloud<pcl::PointXYZ>::Ptr cl2,
  451. pcl::PointCloud<pcl::PointXYZ>::Ptr cl3,pcl::PointCloud<pcl::PointXYZ>::Ptr cl4,
  452. float& cx,float& cy,float& theta,float& wheel_base,float& width,
  453. float& front_theta,float& loss){
  454. double variable[] = {cx,cy,width,front_theta};
  455. auto t1=std::chrono::steady_clock::now();
  456. // 第二部分:构建寻优问题
  457. ceres::Problem problem;
  458. CostXYWFFunc* costFuc=new CostXYWFFunc(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,
  459. m_line_l,m_line_r,m_line_y,theta,wheel_base);
  460. ceres::CostFunction* cost_function =new
  461. ceres::AutoDiffCostFunction<CostXYWFFunc, ceres::DYNAMIC, 4>(costFuc,
  462. 2*(m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size()));
  463. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  464. //第三部分: 配置并运行求解器
  465. ceres::Solver::Options options;
  466. options.use_nonmonotonic_steps=false;
  467. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  468. options.max_num_iterations=100;
  469. options.num_threads=2;
  470. options.minimizer_progress_to_stdout = false;//输出到cout
  471. ceres::Solver::Summary summary;//优化信息
  472. ceres::Solve(options, &problem, &summary);//求解!!!
  473. auto t2=std::chrono::steady_clock::now();
  474. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(t2 - t1);
  475. double time=double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  476. loss=summary.final_cost/(m_left_front_cloud->size()+m_right_front_cloud->size()+m_left_rear_cloud->size()+m_right_rear_cloud->size());
  477. /*printf("loss: %.5f size:%d time:%.5fs\n",loss,m_left_front_cloud->size()+m_right_front_cloud->size()+
  478. m_left_rear_cloud->size()+m_right_rear_cloud->size(),time);*/
  479. cx=variable[0];
  480. cy=variable[1];
  481. width=variable[2];
  482. front_theta=variable[3];
  483. if(loss>0.05){
  484. return false;
  485. }
  486. return true;
  487. }
  488. pcl::PointCloud<pcl::PointXYZ>::Ptr detect_wheel_ceres::filter(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,float r){
  489. if(cloud->size()==0)
  490. return cloud;
  491. float sumx=0;
  492. for(int i=0;i<cloud->size();++i){
  493. sumx+=cloud->points[i].x;
  494. }
  495. float avg=sumx/float(cloud->size());
  496. float stdd=0.0;
  497. for(int i=0;i<cloud->size();++i){
  498. stdd+=pow(cloud->points[i].x-avg,2);
  499. }
  500. stdd=sqrt(stdd/(float(cloud->size())));
  501. if(stdd<0.15)
  502. return cloud;
  503. pcl::PointCloud<pcl::PointXYZ>::Ptr out(new pcl::PointCloud<pcl::PointXYZ>);
  504. for(int i=0;i<cloud->size();++i){
  505. if(fabs(cloud->points[i].x-avg)<r*stdd)
  506. out->push_back(cloud->points[i]);
  507. }
  508. return out;
  509. }