detect_wheel_ceres.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829
  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. constexpr float kMinProbability = 0.0f;
  8. constexpr float kMaxProbability = 1.f - kMinProbability;
  9. constexpr float kMaxCorrespondenceCost = 1.f - kMinProbability;
  10. constexpr int kPadding = INT_MAX / 4;
  11. class GridArrayAdapter {
  12. public:
  13. enum { DATA_DIMENSION = 1 };
  14. explicit GridArrayAdapter(const cv::Mat& grid) : grid_(grid) {}
  15. void GetValue(const int row, const int column, double* const value) const {
  16. if (row < kPadding || column < kPadding || row >= NumRows() - kPadding ||
  17. column >= NumCols() - kPadding) {
  18. *value = kMaxCorrespondenceCost;
  19. } else {
  20. *value = static_cast<double>(grid_.at<double >(row - kPadding, column - kPadding));
  21. }
  22. }
  23. int NumRows() const {
  24. return grid_.rows + 2 * kPadding;
  25. }
  26. int NumCols() const {
  27. return grid_.cols + 2 * kPadding;
  28. }
  29. private:
  30. const cv::Mat& grid_;
  31. };
  32. class CostFunctor {
  33. private:
  34. cv::Mat m_map;
  35. double m_scale;
  36. mutable double m_costs_lf, m_costs_rf, m_costs_lr, m_costs_rr;
  37. pcl::PointCloud<pcl::PointXYZ> m_left_front_cloud; //左前点云
  38. pcl::PointCloud<pcl::PointXYZ> m_right_front_cloud; //右前点云
  39. pcl::PointCloud<pcl::PointXYZ> m_left_rear_cloud; //左后点云
  40. pcl::PointCloud<pcl::PointXYZ> m_right_rear_cloud; //右后点云
  41. public:
  42. CostFunctor(pcl::PointCloud<pcl::PointXYZ> left_front, pcl::PointCloud<pcl::PointXYZ> right_front,
  43. pcl::PointCloud<pcl::PointXYZ> left_rear, pcl::PointCloud<pcl::PointXYZ> right_rear,
  44. cv::Mat &map, double scale)
  45. {
  46. m_map = map;
  47. m_scale = scale;
  48. m_left_front_cloud = left_front;
  49. m_right_front_cloud = right_front;
  50. m_left_rear_cloud = left_rear;
  51. m_right_rear_cloud = right_rear;
  52. m_costs_lf = 0.0;
  53. m_costs_rf = 0.0;
  54. m_costs_lr = 0.0;
  55. m_costs_rr = 0.0;
  56. }
  57. template <typename T>
  58. bool operator()(const T* const variable, T* residual) const {
  59. // 每一轮重新初始化残差值
  60. T costs[4]={T(0),T(0),T(0),T(0)};
  61. T cx = variable[0];
  62. T cy = variable[1];
  63. T theta = variable[2];
  64. T length = variable[3];
  65. T width = variable[4];
  66. T theta_front = variable[5];
  67. //整车旋转
  68. Eigen::Rotation2D<T> rotation(theta);
  69. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  70. //左前偏移
  71. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  72. //右前偏移
  73. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  74. //左后偏移
  75. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  76. //右后偏移
  77. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  78. //前轮旋转
  79. Eigen::Rotation2D<T> rotation_front(theta_front);
  80. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  81. const GridArrayAdapter adapter(m_map);
  82. ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
  83. double rows = m_map.rows;
  84. double cols = m_map.cols;
  85. //左前轮
  86. int left_front_num = m_left_front_cloud.size();
  87. for (int i = 0; i < m_left_front_cloud.size(); ++i) {
  88. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud[i].x) - cx),
  89. (T(m_left_front_cloud[i].y) - cy));
  90. //减去经过车辆旋转计算的左前中心
  91. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  92. //旋转
  93. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  94. interpolator.Evaluate(point_rotation(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  95. point_rotation(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  96. &residual[i]);
  97. costs[0] += residual[i];
  98. }
  99. //右前轮
  100. int right_front_num = m_right_front_cloud.size();
  101. for (int i = 0; i < m_right_front_cloud.size(); ++i) {
  102. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud[i].x) - cx),
  103. (T(m_right_front_cloud[i].y) - cy));
  104. //减去经过车辆旋转计算的左前中心
  105. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  106. //旋转
  107. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  108. interpolator.Evaluate(point_rotation(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  109. point_rotation(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  110. &residual[left_front_num + i]);
  111. costs[1] += residual[left_front_num+i];
  112. }
  113. //左后轮
  114. int left_rear_num = m_left_rear_cloud.size();
  115. for (int i = 0; i < m_left_rear_cloud.size(); ++i) {
  116. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud[i].x) - cx),
  117. (T(m_left_rear_cloud[i].y) - cy));
  118. //减去经过车辆旋转计算的左前中心
  119. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  120. interpolator.Evaluate(tanslate_point(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  121. tanslate_point(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  122. &residual[left_front_num + right_front_num + i]);
  123. costs[2] += residual[left_front_num + right_front_num + i];
  124. }
  125. //右后轮
  126. for (int i = 0; i < m_right_rear_cloud.size(); ++i) {
  127. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud[i].x) - cx),
  128. (T(m_right_rear_cloud[i].y) - cy));
  129. //减去经过车辆旋转计算的左前中心
  130. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  131. interpolator.Evaluate(tanslate_point(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  132. tanslate_point(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  133. &residual[left_front_num + right_front_num + left_rear_num + i]);
  134. costs[3] += residual[left_front_num + right_front_num + left_rear_num + i];
  135. }
  136. char buf[30];
  137. memset(buf, 0, 30);
  138. sprintf(buf, "%.7f", costs[0]);
  139. m_costs_lf = std::stod(buf) / left_front_num;
  140. memset(buf, 0, 30);
  141. sprintf(buf, "%.7f", costs[1]);
  142. m_costs_rf = std::stod(buf) / right_front_num;
  143. memset(buf, 0, 30);
  144. sprintf(buf, "%.7f", costs[2]);
  145. m_costs_lr = std::stod(buf) / left_rear_num;
  146. memset(buf, 0, 30);
  147. sprintf(buf, "%.7f", costs[3]);
  148. m_costs_rr = std::stod(buf) / m_right_rear_cloud.size();
  149. // m_costs_lf = costs[0];
  150. return true;
  151. }
  152. void get_costs(double &lf, double &rf, double &lr, double &rr)
  153. {
  154. lf = m_costs_lf;
  155. rf = m_costs_rf;
  156. lr = m_costs_lr;
  157. rr = m_costs_rr;
  158. }
  159. };
  160. bool detect_wheel_ceres::update_mat(int rows, int cols)
  161. {
  162. /////创建地图
  163. int L=std::min(rows,cols);
  164. cv::Mat map=cv::Mat::ones(L,L,CV_64F);
  165. //map=map*255;
  166. cv::Point center(L/2,L/2);
  167. float K=L*0.08;
  168. // 从中心开始向外画矩形
  169. // 内层高斯,外层二次函数
  170. for(int n=0;n<L;n+=2)
  171. {
  172. cv::Size size(n+2,n+2);
  173. cv::Rect rect(center-cv::Point(n/2,n/2),size);
  174. double x = n / double(L);
  175. double sigma = 0.06;
  176. double miu = 0.0;
  177. double scale = 0.02;
  178. double translation = -0.05;
  179. double gauss_value = (scale/(sqrt(2*M_PI)*sigma))*exp(-pow(x-miu, 2)/(2*sigma*sigma))+translation;
  180. double quadratic_value = x-0.08;
  181. // LOG(INFO) << rect.tl().x<<", "<<rect.tl().y<<", "<<rect.br().x<<", "<<rect.br().y;
  182. // 对内外分别取色
  183. cv::rectangle(map,rect,std::max(gauss_value, quadratic_value));
  184. // if(n<K*2){
  185. // cv::rectangle(map,rect,1.0*float(K*2-n)/float(L));
  186. // }
  187. // else{
  188. // cv::rectangle(map,rect,float(n-K*2)/float(L));
  189. // }
  190. }
  191. cv::resize(map,map,cv::Size(cols,rows));
  192. cv::GaussianBlur(map,m_map,cv::Size(7,7),3,3);
  193. }
  194. detect_wheel_ceres::detect_wheel_ceres()
  195. {
  196. int cols=800;
  197. int rows=200;
  198. update_mat(rows, cols);
  199. }
  200. detect_wheel_ceres::~detect_wheel_ceres(){}
  201. bool detect_wheel_ceres::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>> cloud_vec, Detect_result &detect_result)
  202. {
  203. //清理点云
  204. m_left_front_cloud.clear();
  205. m_right_front_cloud.clear();
  206. m_left_rear_cloud.clear();
  207. m_right_rear_cloud.clear();
  208. //重新计算点云,按方位分割
  209. //第一步,计算整体中心,主轴方向
  210. pcl::PointCloud<pcl::PointXYZ> cloud_all;
  211. for(int i=0;i<cloud_vec.size();++i)
  212. {
  213. cloud_all+=cloud_vec[i];
  214. }
  215. // std::cout<<"cloud size: "<<cloud_all.size()<<std::endl;
  216. if(cloud_all.size()<20)
  217. return false;
  218. Eigen::Vector4f centroid;
  219. pcl::compute3DCentroid(cloud_all, centroid);
  220. double center_x=centroid[0];
  221. double center_y=centroid[1];
  222. //计算外接旋转矩形
  223. std::vector<cv::Point2f> points_cv;
  224. for(int i=0;i<cloud_all.size();++i)
  225. {
  226. points_cv.push_back(cv::Point2f(cloud_all[i].x,cloud_all[i].y));
  227. }
  228. cv::RotatedRect rotate_rect=cv::minAreaRect(points_cv);
  229. //计算旋转矩形与X轴的夹角
  230. cv::Point2f vec;
  231. cv::Point2f vertice[4];
  232. rotate_rect.points(vertice);
  233. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  234. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  235. // 寻找长边,倾角为长边与x轴夹角
  236. if (len1 > len2)
  237. {
  238. vec.x = vertice[0].x - vertice[1].x;
  239. vec.y = vertice[0].y - vertice[1].y;
  240. }
  241. else
  242. {
  243. vec.x = vertice[1].x - vertice[2].x;
  244. vec.y = vertice[1].y - vertice[2].y;
  245. }
  246. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  247. // printf("rect theta: %.3f\n",angle_x);
  248. //第二步, 将没分点云旋转回去,计算点云重心所在象限
  249. for(int i=0;i<cloud_vec.size();++i)
  250. {
  251. pcl::PointCloud<pcl::PointXYZ> cloud=cloud_vec[i];
  252. Eigen::Affine3f traslation = Eigen::Affine3f::Identity();//初始化变换矩阵为单位矩阵
  253. // 平移
  254. traslation.translation() << -center_x, -center_y, 0.0;
  255. pcl::PointCloud<pcl::PointXYZ> translate_cloud;
  256. pcl::transformPointCloud(cloud, translate_cloud, traslation);
  257. // 旋转; Z 轴上旋转angle_x 弧度,Y轴上旋转0弧度
  258. Eigen::Affine3f rotation = Eigen::Affine3f::Identity();
  259. rotation.rotate(Eigen::AngleAxisf(-angle_x*M_PI/180.0, Eigen::Vector3f::UnitZ()));
  260. pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
  261. pcl::transformPointCloud(translate_cloud, transformed_cloud, rotation);
  262. //计算重心
  263. Eigen::Vector4f centroid;
  264. pcl::compute3DCentroid(transformed_cloud, centroid);
  265. double x=centroid[0];
  266. double y=centroid[1];
  267. //计算象限
  268. if(x>0&&y>0)
  269. {
  270. //第一象限
  271. m_left_front_cloud=cloud;
  272. }
  273. if(x>0 && y<0)
  274. {
  275. //第四象限
  276. m_right_front_cloud=cloud;
  277. }
  278. if(x<0 && y>0)
  279. {
  280. //第二象限
  281. m_left_rear_cloud=cloud;
  282. }
  283. if(x<0 && y<0)
  284. {
  285. //第三象限
  286. m_right_rear_cloud=cloud;
  287. }
  288. }
  289. // // 仅优化一次,不调整图像比例与角度初值。
  290. // detect_result.cx=center_x;
  291. // detect_result.cy=center_y;
  292. // detect_result.theta=-angle_x*M_PI/180.0;
  293. // Loss_result one_shot_loss_result;
  294. // return Solve(detect_result, one_shot_loss_result);
  295. // 多次优化,获取最佳优化结果
  296. detect_result.cx=center_x;
  297. detect_result.cy=center_y;
  298. // 已计算次数,初始传入值正常,之后solve函数会修改初始值,需要恢复角度单位为弧度
  299. int calc_count=0;
  300. // double final_theta = 0;
  301. // 误差结构体,保存左前、右前、左后、右后、整体平均误差
  302. Loss_result loss_result;
  303. // 平均误差值,用于获取最小整体平均误差
  304. double avg_loss = 100;
  305. // 定义图像列数,控制图像大小
  306. int map_cols = 800;
  307. // 优化后图像行数,用于保存优化后结果图像
  308. int optimized_map_rows = 200;
  309. // 优化结果
  310. bool solve_result = false;
  311. double total_solve_time = 0;
  312. bool stop_sign = false;
  313. for (int j = 2; j < 4&&!stop_sign; j++)
  314. {
  315. // double input_vars[] = {detect_result.cx, detect_result.cy, detect_result.theta, detect_result.wheel_base, detect_result.width, detect_result.front_theta};
  316. double map_rows = map_cols * 1.0 / j ;
  317. update_mat(map_rows, map_cols);
  318. Detect_result t_detect_result = detect_result;
  319. // 寻找最小loss值对应的初始旋转角
  320. for (int i = -5; i < 6&&!stop_sign; i+=2)
  321. {
  322. t_detect_result.theta = (-angle_x + i) * M_PI / 180.0;
  323. // printf("double x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",input_vars[0],input_vars[1],input_vars[3],input_vars[4],input_vars[2],input_vars[5]);
  324. Loss_result t_loss_result;
  325. t_loss_result.total_avg_loss = 1000;
  326. //输出角度已变化,需恢复成弧度
  327. if(calc_count > 0)
  328. {
  329. // t_detect_result.theta *= (-M_PI) / 180.0;
  330. t_detect_result.front_theta *= (-M_PI) / 180.0;
  331. }
  332. auto t1=std::chrono::system_clock::now();
  333. bool current_result = Solve(t_detect_result, t_loss_result);
  334. auto t2=std::chrono::system_clock::now();
  335. auto duration=t2-t1;
  336. static double second=0.0;
  337. second=std::chrono::duration_cast<std::chrono::milliseconds>(duration).count()/1000.0;
  338. total_solve_time+=second;
  339. // std::cout<<" time "<<second<<std::endl;
  340. // std::cout<<"current_result: "<<current_result<<std::endl;
  341. if(!current_result)
  342. continue;
  343. // LOG(INFO) << "avg loss, current theta: " << t_loss << ", " << input_vars[2];
  344. if (avg_loss > t_loss_result.total_avg_loss)
  345. {
  346. avg_loss = t_loss_result.total_avg_loss;
  347. // final_theta = -input_vars[2] * M_PI / 180.0;
  348. detect_result = t_detect_result;
  349. solve_result = current_result;
  350. loss_result = t_loss_result;
  351. optimized_map_rows = map_rows;
  352. calc_count++;
  353. /*// 新增,优化时间足够长则认为已找到正确结果
  354. if(second > 0.02)
  355. {
  356. stop_sign = true;
  357. break;
  358. }*/
  359. }
  360. }
  361. }
  362. // std::cout<<"solve time "<<total_solve_time<<std::endl;
  363. // LOG(INFO) << "final avg cost for four wheels: "<<whole_loss[0]<<" "<<whole_loss[1]<<" "<<whole_loss[2]<<" "<<whole_loss[3]<<" ";
  364. // if(solve_result)
  365. // printf("final avg cost for four wheels: %7.6f %7.6f %7.6f %7.6f---%7.6f\n", loss_result.lf_loss, loss_result.rf_loss, loss_result.lb_loss, loss_result.rb_loss, loss_result.total_avg_loss);
  366. // // 生成并保存图片
  367. // update_mat(optimized_map_rows, map_cols);
  368. // Detect_result t_detect_result = detect_result;
  369. // t_detect_result.theta *= (-M_PI) / 180.0;
  370. // t_detect_result.front_theta *= (-M_PI) / 180.0;
  371. // Loss_result t_loss_result;
  372. // // LOG(INFO) <<"going to show img ";
  373. // Solve(detect_result, t_loss_result, true);
  374. return solve_result;
  375. }
  376. // 根据测量结果,生成四轮各中心十字星点云
  377. void detect_wheel_ceres::transform_src(Detect_result detect_result)
  378. {
  379. //整车旋转
  380. Eigen::Rotation2D<double> rotation(-detect_result.theta);
  381. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  382. //左前偏移
  383. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(detect_result.wheel_base / 2.0, detect_result.width / 2.0);
  384. //右前偏移
  385. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(detect_result.wheel_base / 2.0, -detect_result.width / 2.0);
  386. //左后偏移
  387. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-detect_result.wheel_base / 2.0, detect_result.width / 2.0);
  388. //右后偏移
  389. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-detect_result.wheel_base / 2.0, -detect_result.width / 2.0);
  390. Eigen::Matrix<double, 2, 1> translate_car(detect_result.cx,detect_result.cy);
  391. const Eigen::Matrix<double, 2, 1> lt_center = rotation_matrix * wheel_center_normal_left_front+translate_car;
  392. const Eigen::Matrix<double, 2, 1> rt_center = rotation_matrix * wheel_center_normal_right_front+translate_car;
  393. const Eigen::Matrix<double, 2, 1> lb_center = rotation_matrix * wheel_center_normal_left_rear+translate_car;
  394. const Eigen::Matrix<double, 2, 1> rb_center = rotation_matrix * wheel_center_normal_right_rear+translate_car;
  395. create_mark(lt_center(0,0),lt_center(1,0),-detect_result.theta-detect_result.front_theta,m_left_front_cloud_out);
  396. create_mark(rt_center(0,0),rt_center(1,0),-detect_result.theta-detect_result.front_theta,m_right_front_cloud_out);
  397. create_mark(lb_center(0,0),lb_center(1,0),-detect_result.theta,m_left_rear_cloud_out);
  398. create_mark(rb_center(0,0),rb_center(1,0),-detect_result.theta,m_right_rear_cloud_out);
  399. }
  400. // 创建车轮中心十字星点云
  401. void detect_wheel_ceres::create_mark(double x,double y,double theta,pcl::PointCloud<pcl::PointXYZ>& cloud_out)
  402. {
  403. cloud_out.clear();
  404. pcl::PointCloud<pcl::PointXYZ> cloud;
  405. //std::cout<<"1111111111"<<std::endl;
  406. int width=30;
  407. int height=10;
  408. double step=0.015;
  409. for(int i=0;i<width;++i)
  410. {
  411. pcl::PointXYZ point((i-width/2)*step,0,0);
  412. cloud.push_back(point);
  413. }
  414. for(int i=0;i<height;++i)
  415. {
  416. pcl::PointXYZ point(0,(i-height/2)*step,0);
  417. cloud.push_back(point);
  418. }
  419. //std::cout<<"22222222222"<<std::endl;
  420. //整车旋转
  421. Eigen::Rotation2D<double> rotation(theta);
  422. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  423. for(int i=0;i<cloud.size();++i) {
  424. const Eigen::Matrix<double, 2, 1> point((double(cloud[i].x)),
  425. (double(cloud[i].y)));
  426. //减去经过车辆旋转计算的左前中心
  427. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point;
  428. pcl::PointXYZ point_out(tanslate_point(0,0)+x,tanslate_point(1,0)+y,0);
  429. cloud_out.push_back(point_out);
  430. }
  431. }
  432. bool detect_wheel_ceres::Solve(Detect_result &detect_result, double &avg_loss)
  433. {
  434. double SCALE=300.0;
  435. double cx=detect_result.cx;
  436. double cy=detect_result.cy;
  437. double init_theta=detect_result.theta;
  438. double init_wheel_base=2.7;
  439. double init_width=1.55;
  440. double init_theta_front=0*M_PI/180.0;
  441. double variable[] = {cx,cy,init_theta,init_wheel_base,init_width,init_theta_front};
  442. // 第二部分:构建寻优问题
  443. ceres::Problem problem;
  444. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  445. ceres::CostFunction* cost_function =new
  446. ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 6>(
  447. new CostFunctor(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_map,SCALE),
  448. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  449. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  450. //第三部分: 配置并运行求解器
  451. ceres::Solver::Options options;
  452. options.use_nonmonotonic_steps=false;
  453. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  454. options.max_num_iterations=60;
  455. options.num_threads=1;
  456. options.minimizer_progress_to_stdout = false;//输出到cout
  457. ceres::Solver::Summary summary;//优化信息
  458. ceres::Solve(options, &problem, &summary);//求解!!!
  459. // std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  460. /*printf("x:%.3f,y:%.3f,theta:%.3f\nlength:%.3f,width:%.3f\ntheta_front:%.3f\n",
  461. x[0],x[1],x[2]*180.0/M_PI,x[3],x[4],x[5]*180.0/M_PI);*/
  462. 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());
  463. detect_result.cx=variable[0];
  464. detect_result.cy=variable[1];
  465. detect_result.theta=(-variable[2])*180.0/M_PI;
  466. detect_result.wheel_base=variable[3];
  467. detect_result.width=variable[4];
  468. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  469. if(detect_result.theta>180.0)
  470. detect_result.theta=detect_result.theta-180.0;
  471. if(detect_result.theta<0)
  472. detect_result.theta+=180.0;
  473. //检验
  474. if(loss>0.01)
  475. return false;
  476. if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.000 || detect_result.wheel_base < 2.200)
  477. {
  478. return false;
  479. }
  480. detect_result.width+=0.15;//车宽+10cm
  481. // printf(" x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",x,y,wheel_base,width,theta,front_theta);
  482. // //added by yct
  483. avg_loss = loss; // 将loss传出
  484. Detect_result t_detect_result = detect_result;
  485. t_detect_result.theta *= -M_PI/180.0;
  486. t_detect_result.front_theta *= -M_PI/180.0;
  487. transform_src(t_detect_result);
  488. return true;
  489. }
  490. bool detect_wheel_ceres::Solve(Detect_result &detect_result, Loss_result &loss_result, bool save_img)
  491. {
  492. double SCALE=300.0;
  493. double cx=detect_result.cx;
  494. double cy=detect_result.cy;
  495. double init_theta=detect_result.theta;
  496. double init_wheel_base=2.7;
  497. double init_width=1.55;
  498. double init_theta_front=0*M_PI/180.0;
  499. double variable[] = {cx,cy,init_theta,init_wheel_base,init_width,init_theta_front};
  500. // printf("solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n", variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);
  501. // 第二部分:构建寻优问题
  502. ceres::Problem problem;
  503. CostFunctor *cost_func = new CostFunctor(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_map,SCALE);
  504. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  505. ceres::CostFunction* cost_function =new
  506. ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 6>(
  507. cost_func,
  508. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  509. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  510. //第三部分: 配置并运行求解器
  511. ceres::Solver::Options options;
  512. options.use_nonmonotonic_steps=false;
  513. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  514. options.max_num_iterations=60;
  515. options.num_threads=3;
  516. options.minimizer_progress_to_stdout = false;//输出到cout
  517. ceres::Solver::Summary summary;//优化信息
  518. ceres::Solve(options, &problem, &summary);//求解!!!
  519. // std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  520. // debug_img(detect_result, loss_result, true);
  521. 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());
  522. detect_result.cx=variable[0];
  523. detect_result.cy=variable[1];
  524. detect_result.theta=(-variable[2])*180.0/M_PI;
  525. detect_result.wheel_base=variable[3];
  526. detect_result.width=variable[4];
  527. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  528. if(detect_result.theta>180.0)
  529. detect_result.theta=detect_result.theta-180.0;
  530. if(detect_result.theta<0)
  531. detect_result.theta+=180.0;
  532. //检验
  533. // printf("loss: %.5f\n", loss);
  534. // printf("middle x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n", variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);
  535. if(loss>0.0115)
  536. {
  537. // LOG(WARNING) <<"总loss过大 "<<loss;
  538. return false;
  539. }
  540. if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.150 || detect_result.wheel_base < 2.200)
  541. {
  542. // LOG(WARNING) <<"宽度(1.35, 2.00) 轴距(2.20, 3.15): "<<detect_result.width<<", "<<detect_result.wheel_base;
  543. return false;
  544. }
  545. detect_result.width += 0.15; //车宽+10cm
  546. // printf(" x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",x,y,wheel_base,width,theta,front_theta);
  547. // //added by yct
  548. if(detect_result.theta > 120 || detect_result.theta < 60)
  549. {
  550. // LOG(WARNING) <<"总角度错误 "<<detect_result.theta;
  551. return false;
  552. }
  553. if(fabs(detect_result.front_theta)>35)
  554. {
  555. // LOG(WARNING) <<"前轮角度错误 "<<detect_result.front_theta;
  556. return false;
  557. }
  558. // 将loss传出
  559. if(cost_func!=nullptr)
  560. {
  561. double costs_lf, costs_rf, costs_lr, costs_rr;
  562. cost_func->get_costs(costs_lf, costs_rf, costs_lr, costs_rr);
  563. // std::cout << "111"<< std::endl;
  564. loss_result.lf_loss = costs_lf;
  565. loss_result.rf_loss = costs_rf;
  566. loss_result.lb_loss = costs_lr;
  567. loss_result.rb_loss = costs_rr;
  568. loss_result.total_avg_loss = loss;
  569. // std::cout << "222"<< std::endl;
  570. if (costs_lf <= 1e-6 && costs_rf <= 1e-6 && costs_lr <= 1e-6 && costs_rr <= 1e-6)
  571. {
  572. loss_result.lf_loss = loss;
  573. loss_result.rf_loss = loss;
  574. loss_result.lb_loss = loss;
  575. loss_result.rb_loss = loss;
  576. }
  577. // 判断每个轮子平均loss是否满足条件
  578. double single_wheel_loss_threshold = 0.109;
  579. if(loss_result.lf_loss > single_wheel_loss_threshold || loss_result.rf_loss > single_wheel_loss_threshold || loss_result.lb_loss > single_wheel_loss_threshold || loss_result.rb_loss > single_wheel_loss_threshold)
  580. {
  581. // LOG(WARNING) <<"四轮loss过大"<<loss_result.lf_loss<<", "<<loss_result.rf_loss<<", "<<loss_result.lb_loss<<", "<<loss_result.rb_loss;
  582. return false;
  583. }
  584. // std::cout<<"save img: "<<save_img<<std::endl;
  585. // debug_img(detect_result, loss_result, save_img);
  586. }
  587. else
  588. {
  589. return false;
  590. }
  591. Detect_result t_detect_result = detect_result;
  592. t_detect_result.theta *= -M_PI/180.0;
  593. t_detect_result.front_theta *= -M_PI/180.0;
  594. t_detect_result.width -= 0.15;
  595. transform_src(t_detect_result);
  596. return true;
  597. }
  598. // 显示/保存图片供调试用
  599. void detect_wheel_ceres::debug_img(Detect_result detect_result, Loss_result loss_result, bool save_img, std::string out_img_path)
  600. {
  601. double SCALE=300.0;
  602. cv::Mat lf = m_map.clone();
  603. cv::Mat rf = m_map.clone();
  604. cv::Mat lb = m_map.clone();
  605. cv::Mat rb = m_map.clone();
  606. //整车旋转
  607. Eigen::Rotation2D<double> rotation(detect_result.theta);
  608. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  609. //左前偏移
  610. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(detect_result.wheel_base / 2.0, (detect_result.width - 0.15) / 2.0);
  611. //右前偏移
  612. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(detect_result.wheel_base / 2.0, (-detect_result.width + 0.15) / 2.0);
  613. //左后偏移
  614. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-detect_result.wheel_base / 2.0, (detect_result.width - 0.15) / 2.0);
  615. //右后偏移
  616. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-detect_result.wheel_base / 2.0, (-detect_result.width + 0.15) / 2.0);
  617. //前轮旋转
  618. Eigen::Rotation2D<double> rotation_front(detect_result.front_theta);
  619. Eigen::Matrix<double, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  620. // 左前轮
  621. for (size_t i = 0; i < m_left_front_cloud.size(); i++)
  622. {
  623. Eigen::Matrix<double, 2, 1> point((double(m_left_front_cloud[i].x) - detect_result.cx),
  624. (double(m_left_front_cloud[i].y) - detect_result.cy));
  625. //减去经过车辆旋转计算的左前中心
  626. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  627. //旋转
  628. Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  629. int r = (int)(point_rotation(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  630. int c = (int)(point_rotation(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  631. cv::circle(lf, cv::Point(c, r), 1, cv::Scalar(150));
  632. // std::cout<<"map r,c "<<m_map.rows<<", "<<m_map.cols<<std::endl;
  633. // std::cout<<"r,c "<<r<<", "<<c<<std::endl;
  634. // lf.at<uchar>(r, c) = 150;
  635. }
  636. //右前轮
  637. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  638. {
  639. Eigen::Matrix<double, 2, 1> point((double(m_right_front_cloud[i].x) - detect_result.cx),
  640. (double(m_right_front_cloud[i].y) - detect_result.cy));
  641. //减去经过车辆旋转计算的左前中心
  642. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  643. //旋转
  644. Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  645. int r = (int)(point_rotation(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  646. int c = (int)(point_rotation(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  647. cv::circle(rf, cv::Point(c, r), 1, cv::Scalar(150));
  648. }
  649. //左后轮
  650. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  651. {
  652. Eigen::Matrix<double, 2, 1> point((double(m_left_rear_cloud[i].x) - detect_result.cx),
  653. (double(m_left_rear_cloud[i].y) - detect_result.cy));
  654. //减去经过车辆旋转计算的左前中心
  655. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  656. int r = (int)(tanslate_point(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  657. int c = (int)(tanslate_point(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  658. cv::circle(lb, cv::Point(c, r), 1, cv::Scalar(150));
  659. }
  660. //右后轮
  661. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  662. {
  663. Eigen::Matrix<double, 2, 1> point((double(m_right_rear_cloud[i].x) - detect_result.cx),
  664. (double(m_right_rear_cloud[i].y) - detect_result.cy));
  665. //减去经过车辆旋转计算的左前中心
  666. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  667. int r = (int)(tanslate_point(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  668. int c = (int)(tanslate_point(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  669. cv::circle(rb, cv::Point(c, r), 1, cv::Scalar(150));
  670. }
  671. // cv::Mat rot90;// = (cv::Mat_<double>(2, 3)<<cos(90), -sin(90), 0, sin(90), cos(90), 0);
  672. // rot90 = cv::getRotationMatrix2D(cv::Point2f(lf.cols/2, lf.rows/2), 90, 1);
  673. // // std::cout<<rot90<<std::endl;
  674. // cv::warpAffine(lf, lf, rot90, cv::Size(lf.cols, lf.rows));
  675. // cv::flip()
  676. // cv::namedWindow("left front", cv::WINDOW_FREERATIO);
  677. // cv::namedWindow("right front", cv::WINDOW_FREERATIO);
  678. // cv::namedWindow("left back", cv::WINDOW_FREERATIO);
  679. // cv::namedWindow("right back", cv::WINDOW_FREERATIO);
  680. cv::flip(lf, lf, -1);
  681. cv::flip(rf, rf, -1);
  682. cv::flip(lb, lb, -1);
  683. cv::flip(rb, rb, -1);
  684. cv::Mat lft = lf.t(), rft = rf.t(), lbt = lb.t(), rbt = rb.t();
  685. // cv::imshow("left front", lf.t());
  686. // cv::imshow("right front", rf.t());
  687. // cv::imshow("left back", lb.t());
  688. // cv::imshow("right back", rb.t());
  689. // 写入各轮平均误差
  690. cv::putText(lft, (boost::format("lf %.6f") % (loss_result.lf_loss)).str().c_str(),
  691. cv::Point(lft.cols / 6, lft.rows / 4),
  692. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  693. cv::putText(rft, (boost::format("rf %.6f") % (loss_result.rf_loss)).str().c_str(),
  694. cv::Point(rft.cols / 6, rft.rows / 4),
  695. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  696. cv::putText(lbt, (boost::format("lb %.6f") % (loss_result.lb_loss)).str().c_str(),
  697. cv::Point(lbt.cols / 6, lbt.rows / 4),
  698. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  699. cv::putText(rbt, (boost::format("rb %.6f") % (loss_result.rb_loss)).str().c_str(),
  700. cv::Point(rbt.cols / 6, rbt.rows / 4),
  701. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  702. cv::Mat total_img = cv::Mat::zeros(m_map.cols * 2, m_map.rows * 2, m_map.type());
  703. lft.copyTo(total_img(cv::Rect(0, 0, m_map.rows, m_map.cols)));
  704. rft.copyTo(total_img(cv::Rect(m_map.rows, 0, m_map.rows, m_map.cols)));
  705. lbt.copyTo(total_img(cv::Rect(0, m_map.cols, m_map.rows, m_map.cols)));
  706. rbt.copyTo(total_img(cv::Rect(m_map.rows, m_map.cols, m_map.rows, m_map.cols)));
  707. // cv::namedWindow("total img", CV_WINDOW_FREERATIO);
  708. // cv::imshow("total img", total_img);
  709. // cv::waitKey(20);
  710. if(save_img)
  711. {
  712. cv::Mat cvted_img = cv::Mat::zeros(m_map.cols * 2, m_map.rows * 2, CV_8U);
  713. int total_milli = (std::chrono::time_point_cast<std::chrono::milliseconds>(std::chrono::system_clock::now())).time_since_epoch().count();
  714. std::string img_filename="";
  715. if(out_img_path.empty()){
  716. img_filename = std::string("/home/youchen/Documents/measure/MainStructure/elecfence_ws/img/img").append(std::to_string(total_milli)).append(".jpg");
  717. }
  718. else{
  719. img_filename = out_img_path;
  720. }
  721. LOG(INFO) << "write to " << img_filename.c_str();
  722. // cv::cvtColor(total_img*255, cvted_img, CV_8U);
  723. cv::convertScaleAbs(total_img * 255, cvted_img);
  724. cv::imwrite(img_filename, cvted_img);
  725. }
  726. }