detect_wheel_ceres.cpp 36 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855
  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. // // added by yct
  234. // // 找极值,确定图像大小
  235. // cv::Point2f min_p, max_p, delta;
  236. // double resolution = 0.01;
  237. // for (size_t i = 0; i < points_cv.size(); i++)
  238. // {
  239. // if(points_cv[i].x < min_p.x)
  240. // min_p.x = points_cv[i].x;
  241. // if(points_cv[i].x > max_p.x)
  242. // max_p.x = points_cv[i].x;
  243. // if(points_cv[i].y < min_p.y)
  244. // min_p.y = points_cv[i].y;
  245. // if(points_cv[i].y > max_p.y)
  246. // max_p.y = points_cv[i].y;
  247. // }
  248. // delta.x = (max_p.x - min_p.x) / resolution;
  249. // delta.y = (max_p.y - min_p.y) / resolution;
  250. // cv::Mat t_mat = cv::Mat::ones((int)delta.y, (int)delta.x, CV_8UC1);
  251. // std::vector<cv::Point2f> pixels;
  252. // t_mat *= 255;
  253. // for (size_t i = 0; i < points_cv.size(); i++)
  254. // {
  255. // cv::Point2f curr_p;
  256. // curr_p.x = (int)((points_cv[i].x - min_p.x) / resolution);
  257. // curr_p.y = (int)(delta.y - (points_cv[i].y - min_p.y) / resolution);
  258. // t_mat.at<uchar>( curr_p ) = 30;
  259. // pixels.push_back(curr_p);
  260. // }
  261. // cv::RotatedRect rotate_img_rect=cv::minAreaRect(pixels);
  262. // cv::rectangle(t_mat, rotate_img_rect.boundingRect(), cv::Scalar(50));
  263. // cv::namedWindow("rotate rect", cv::WINDOW_FREERATIO);
  264. // cv::imshow("rotate rect", t_mat);
  265. // cv::waitKey();
  266. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  267. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  268. // 寻找长边,倾角为长边与x轴夹角
  269. if (len1 > len2)
  270. {
  271. vec.x = vertice[0].x - vertice[1].x;
  272. vec.y = vertice[0].y - vertice[1].y;
  273. }
  274. else
  275. {
  276. vec.x = vertice[1].x - vertice[2].x;
  277. vec.y = vertice[1].y - vertice[2].y;
  278. }
  279. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  280. // printf("rect theta: %.3f\n",angle_x);
  281. //第二步, 将没分点云旋转回去,计算点云重心所在象限
  282. for(int i=0;i<cloud_vec.size();++i)
  283. {
  284. pcl::PointCloud<pcl::PointXYZ> cloud=cloud_vec[i];
  285. Eigen::Affine3f traslation = Eigen::Affine3f::Identity();//初始化变换矩阵为单位矩阵
  286. // 平移
  287. traslation.translation() << -center_x, -center_y, 0.0;
  288. pcl::PointCloud<pcl::PointXYZ> translate_cloud;
  289. pcl::transformPointCloud(cloud, translate_cloud, traslation);
  290. // 旋转; Z 轴上旋转angle_x 弧度,Y轴上旋转0弧度
  291. Eigen::Affine3f rotation = Eigen::Affine3f::Identity();
  292. rotation.rotate(Eigen::AngleAxisf(-angle_x*M_PI/180.0, Eigen::Vector3f::UnitZ()));
  293. pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
  294. pcl::transformPointCloud(translate_cloud, transformed_cloud, rotation);
  295. //计算重心
  296. Eigen::Vector4f centroid;
  297. pcl::compute3DCentroid(transformed_cloud, centroid);
  298. double x=centroid[0];
  299. double y=centroid[1];
  300. //计算象限
  301. if(x>0&&y>0)
  302. {
  303. //第一象限
  304. m_left_front_cloud=cloud;
  305. }
  306. if(x>0 && y<0)
  307. {
  308. //第四象限
  309. m_right_front_cloud=cloud;
  310. }
  311. if(x<0 && y>0)
  312. {
  313. //第二象限
  314. m_left_rear_cloud=cloud;
  315. }
  316. if(x<0 && y<0)
  317. {
  318. //第三象限
  319. m_right_rear_cloud=cloud;
  320. }
  321. }
  322. // // 仅优化一次,不调整图像比例与角度初值。
  323. // detect_result.cx=center_x;
  324. // detect_result.cy=center_y;
  325. // detect_result.theta=-angle_x*M_PI/180.0;
  326. // Loss_result one_shot_loss_result;
  327. // return Solve(detect_result, one_shot_loss_result);
  328. // 多次优化,获取最佳优化结果
  329. detect_result.cx=center_x;
  330. detect_result.cy=center_y;
  331. // 已计算次数,初始传入值正常,之后solve函数会修改初始值,需要恢复角度单位为弧度
  332. int calc_count=0;
  333. // double final_theta = 0;
  334. // 误差结构体,保存左前、右前、左后、右后、整体平均误差
  335. Loss_result loss_result;
  336. // 平均误差值,用于获取最小整体平均误差
  337. double avg_loss = 100;
  338. // 定义图像列数,控制图像大小
  339. int map_cols = 800;
  340. // 优化后图像行数,用于保存优化后结果图像
  341. int optimized_map_rows = 200;
  342. // 优化结果
  343. bool solve_result = false;
  344. double total_solve_time = 0;
  345. for (int j = 2; j < 4; j++)
  346. {
  347. // double input_vars[] = {detect_result.cx, detect_result.cy, detect_result.theta, detect_result.wheel_base, detect_result.width, detect_result.front_theta};
  348. double map_rows = map_cols * 1.0 / j ;
  349. update_mat(map_rows, map_cols);
  350. Detect_result t_detect_result = detect_result;
  351. // 寻找最小loss值对应的初始旋转角
  352. for (int i = -5; i < 6; i++)
  353. {
  354. t_detect_result.theta = (-angle_x + i) * M_PI / 180.0;
  355. // 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]);
  356. Loss_result t_loss_result;
  357. t_loss_result.total_avg_loss = 1000;
  358. //输出角度已变化,需恢复成弧度
  359. if(calc_count > 0)
  360. {
  361. // t_detect_result.theta *= (-M_PI) / 180.0;
  362. t_detect_result.front_theta *= (-M_PI) / 180.0;
  363. }
  364. // auto t1=std::chrono::system_clock::now();
  365. bool current_result = Solve(t_detect_result, t_loss_result);
  366. // auto t2=std::chrono::system_clock::now();
  367. // auto duration=t2-t1;
  368. // double second=std::chrono::duration_cast<std::chrono::milliseconds>(duration).count()/1000.0;
  369. // total_solve_time+=second;
  370. // std::cout<<" time "<<second<<std::endl;
  371. // std::cout<<"current_result: "<<current_result<<std::endl;
  372. if(!current_result)
  373. continue;
  374. // LOG(INFO) << "avg loss, current theta: " << t_loss << ", " << input_vars[2];
  375. if (avg_loss > t_loss_result.total_avg_loss)
  376. {
  377. avg_loss = t_loss_result.total_avg_loss;
  378. // final_theta = -input_vars[2] * M_PI / 180.0;
  379. detect_result = t_detect_result;
  380. solve_result = current_result;
  381. loss_result = t_loss_result;
  382. optimized_map_rows = map_rows;
  383. calc_count++;
  384. }
  385. }
  386. }
  387. // std::cout<<"solve time "<<total_solve_time<<std::endl;
  388. // LOG(INFO) << "final avg cost for four wheels: "<<whole_loss[0]<<" "<<whole_loss[1]<<" "<<whole_loss[2]<<" "<<whole_loss[3]<<" ";
  389. if(solve_result)
  390. 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);
  391. // // 生成并保存图片
  392. // update_mat(optimized_map_rows, map_cols);
  393. // Detect_result t_detect_result = detect_result;
  394. // t_detect_result.theta *= (-M_PI) / 180.0;
  395. // t_detect_result.front_theta *= (-M_PI) / 180.0;
  396. // Loss_result t_loss_result;
  397. // // LOG(INFO) <<"going to show img ";
  398. // Solve(detect_result, t_loss_result, true);
  399. return solve_result;
  400. }
  401. // 根据测量结果,生成四轮各中心十字星点云
  402. void detect_wheel_ceres::transform_src(Detect_result detect_result)
  403. {
  404. //整车旋转
  405. Eigen::Rotation2D<double> rotation(-detect_result.theta);
  406. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  407. //左前偏移
  408. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(detect_result.wheel_base / 2.0, detect_result.width / 2.0);
  409. //右前偏移
  410. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(detect_result.wheel_base / 2.0, -detect_result.width / 2.0);
  411. //左后偏移
  412. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-detect_result.wheel_base / 2.0, detect_result.width / 2.0);
  413. //右后偏移
  414. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-detect_result.wheel_base / 2.0, -detect_result.width / 2.0);
  415. Eigen::Matrix<double, 2, 1> translate_car(detect_result.cx,detect_result.cy);
  416. const Eigen::Matrix<double, 2, 1> lt_center = rotation_matrix * wheel_center_normal_left_front+translate_car;
  417. const Eigen::Matrix<double, 2, 1> rt_center = rotation_matrix * wheel_center_normal_right_front+translate_car;
  418. const Eigen::Matrix<double, 2, 1> lb_center = rotation_matrix * wheel_center_normal_left_rear+translate_car;
  419. const Eigen::Matrix<double, 2, 1> rb_center = rotation_matrix * wheel_center_normal_right_rear+translate_car;
  420. create_mark(lt_center(0,0),lt_center(1,0),-detect_result.theta-detect_result.front_theta,m_left_front_cloud_out);
  421. create_mark(rt_center(0,0),rt_center(1,0),-detect_result.theta-detect_result.front_theta,m_right_front_cloud_out);
  422. create_mark(lb_center(0,0),lb_center(1,0),-detect_result.theta,m_left_rear_cloud_out);
  423. create_mark(rb_center(0,0),rb_center(1,0),-detect_result.theta,m_right_rear_cloud_out);
  424. }
  425. // 创建车轮中心十字星点云
  426. void detect_wheel_ceres::create_mark(double x,double y,double theta,pcl::PointCloud<pcl::PointXYZ>& cloud_out)
  427. {
  428. cloud_out.clear();
  429. pcl::PointCloud<pcl::PointXYZ> cloud;
  430. //std::cout<<"1111111111"<<std::endl;
  431. int width=30;
  432. int height=10;
  433. double step=0.015;
  434. for(int i=0;i<width;++i)
  435. {
  436. pcl::PointXYZ point((i-width/2)*step,0,0);
  437. cloud.push_back(point);
  438. }
  439. for(int i=0;i<height;++i)
  440. {
  441. pcl::PointXYZ point(0,(i-height/2)*step,0);
  442. cloud.push_back(point);
  443. }
  444. //std::cout<<"22222222222"<<std::endl;
  445. //整车旋转
  446. Eigen::Rotation2D<double> rotation(theta);
  447. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  448. for(int i=0;i<cloud.size();++i) {
  449. const Eigen::Matrix<double, 2, 1> point((double(cloud[i].x)),
  450. (double(cloud[i].y)));
  451. //减去经过车辆旋转计算的左前中心
  452. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point;
  453. pcl::PointXYZ point_out(tanslate_point(0,0)+x,tanslate_point(1,0)+y,0);
  454. cloud_out.push_back(point_out);
  455. }
  456. }
  457. bool detect_wheel_ceres::Solve(Detect_result &detect_result, double &avg_loss)
  458. {
  459. double SCALE=300.0;
  460. double cx=detect_result.cx;
  461. double cy=detect_result.cy;
  462. double init_theta=detect_result.theta;
  463. double init_wheel_base=2.7;
  464. double init_width=1.55;
  465. double init_theta_front=0*M_PI/180.0;
  466. double variable[] = {cx,cy,init_theta,init_wheel_base,init_width,init_theta_front};
  467. // 第二部分:构建寻优问题
  468. ceres::Problem problem;
  469. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  470. ceres::CostFunction* cost_function =new
  471. ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 6>(
  472. new CostFunctor(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_map,SCALE),
  473. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  474. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  475. //第三部分: 配置并运行求解器
  476. ceres::Solver::Options options;
  477. options.use_nonmonotonic_steps=false;
  478. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  479. options.max_num_iterations=60;
  480. options.num_threads=1;
  481. options.minimizer_progress_to_stdout = false;//输出到cout
  482. ceres::Solver::Summary summary;//优化信息
  483. ceres::Solve(options, &problem, &summary);//求解!!!
  484. // std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  485. /*printf("x:%.3f,y:%.3f,theta:%.3f\nlength:%.3f,width:%.3f\ntheta_front:%.3f\n",
  486. x[0],x[1],x[2]*180.0/M_PI,x[3],x[4],x[5]*180.0/M_PI);*/
  487. 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());
  488. detect_result.cx=variable[0];
  489. detect_result.cy=variable[1];
  490. detect_result.theta=(-variable[2])*180.0/M_PI;
  491. detect_result.wheel_base=variable[3];
  492. detect_result.width=variable[4];
  493. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  494. if(detect_result.theta>180.0)
  495. detect_result.theta=detect_result.theta-180.0;
  496. if(detect_result.theta<0)
  497. detect_result.theta+=180.0;
  498. //检验
  499. if(loss>0.01)
  500. return false;
  501. if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.000 || detect_result.wheel_base < 2.200)
  502. {
  503. return false;
  504. }
  505. detect_result.width+=0.15;//车宽+10cm
  506. // printf(" x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",x,y,wheel_base,width,theta,front_theta);
  507. // //added by yct
  508. avg_loss = loss; // 将loss传出
  509. Detect_result t_detect_result = detect_result;
  510. t_detect_result.theta *= -M_PI/180.0;
  511. t_detect_result.front_theta *= -M_PI/180.0;
  512. transform_src(t_detect_result);
  513. return true;
  514. }
  515. bool detect_wheel_ceres::Solve(Detect_result &detect_result, Loss_result &loss_result, bool save_img)
  516. {
  517. double SCALE=300.0;
  518. double cx=detect_result.cx;
  519. double cy=detect_result.cy;
  520. double init_theta=detect_result.theta;
  521. double init_wheel_base=2.7;
  522. double init_width=1.55;
  523. double init_theta_front=0*M_PI/180.0;
  524. double variable[] = {cx,cy,init_theta,init_wheel_base,init_width,init_theta_front};
  525. // 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]);
  526. // 第二部分:构建寻优问题
  527. ceres::Problem problem;
  528. CostFunctor *cost_func = new CostFunctor(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_map,SCALE);
  529. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  530. ceres::CostFunction* cost_function =new
  531. ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 6>(
  532. cost_func,
  533. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  534. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  535. //第三部分: 配置并运行求解器
  536. ceres::Solver::Options options;
  537. options.use_nonmonotonic_steps=false;
  538. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  539. options.max_num_iterations=60;
  540. options.num_threads=1;
  541. options.minimizer_progress_to_stdout = false;//输出到cout
  542. ceres::Solver::Summary summary;//优化信息
  543. ceres::Solve(options, &problem, &summary);//求解!!!
  544. // std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  545. // debug_img(detect_result, loss_result, true);
  546. 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());
  547. detect_result.cx=variable[0];
  548. detect_result.cy=variable[1];
  549. detect_result.theta=(-variable[2])*180.0/M_PI;
  550. detect_result.wheel_base=variable[3];
  551. detect_result.width=variable[4];
  552. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  553. if(detect_result.theta>180.0)
  554. detect_result.theta=detect_result.theta-180.0;
  555. if(detect_result.theta<0)
  556. detect_result.theta+=180.0;
  557. //检验
  558. // printf("loss: %.5f\n", loss);
  559. // 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]);
  560. if(loss>0.01)
  561. {
  562. // LOG(WARNING) <<"总loss过大 "<<loss;
  563. return false;
  564. }
  565. if (detect_result.width < 1.350 || detect_result.width > 2.000 || detect_result.wheel_base > 3.000 || detect_result.wheel_base < 2.200)
  566. {
  567. // LOG(WARNING) <<"宽度(1.35, 2.00) 轴距(2.20, 3.00): "<<detect_result.width<<", "<<detect_result.wheel_base;
  568. return false;
  569. }
  570. detect_result.width += 0.15; //车宽+10cm
  571. // printf(" x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",x,y,wheel_base,width,theta,front_theta);
  572. // //added by yct
  573. if(detect_result.theta > 120 || detect_result.theta < 60)
  574. {
  575. // LOG(WARNING) <<"总角度错误 "<<detect_result.theta;
  576. return false;
  577. }
  578. if(fabs(detect_result.front_theta)>35)
  579. {
  580. // LOG(WARNING) <<"前轮角度错误 "<<detect_result.front_theta;
  581. return false;
  582. }
  583. // 将loss传出
  584. if(cost_func!=nullptr)
  585. {
  586. double costs_lf, costs_rf, costs_lr, costs_rr;
  587. cost_func->get_costs(costs_lf, costs_rf, costs_lr, costs_rr);
  588. // std::cout << "111"<< std::endl;
  589. loss_result.lf_loss = costs_lf;
  590. loss_result.rf_loss = costs_rf;
  591. loss_result.lb_loss = costs_lr;
  592. loss_result.rb_loss = costs_rr;
  593. loss_result.total_avg_loss = loss;
  594. // std::cout << "222"<< std::endl;
  595. if (costs_lf <= 1e-6 && costs_rf <= 1e-6 && costs_lr <= 1e-6 && costs_rr <= 1e-6)
  596. {
  597. loss_result.lf_loss = loss;
  598. loss_result.rf_loss = loss;
  599. loss_result.lb_loss = loss;
  600. loss_result.rb_loss = loss;
  601. }
  602. // 判断每个轮子平均loss是否满足条件
  603. double single_wheel_loss_threshold = 0.09;
  604. 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)
  605. {
  606. // LOG(WARNING) <<"四轮loss过大";
  607. return false;
  608. }
  609. // std::cout<<"save img: "<<save_img<<std::endl;
  610. debug_img(detect_result, loss_result, save_img);
  611. }
  612. else
  613. {
  614. return false;
  615. }
  616. Detect_result t_detect_result = detect_result;
  617. t_detect_result.theta *= -M_PI/180.0;
  618. t_detect_result.front_theta *= -M_PI/180.0;
  619. t_detect_result.width -= 0.15;
  620. transform_src(t_detect_result);
  621. return true;
  622. }
  623. // 显示/保存图片供调试用
  624. void detect_wheel_ceres::debug_img(Detect_result detect_result, Loss_result loss_result, bool save_img, std::string out_img_path)
  625. {
  626. double SCALE=300.0;
  627. cv::Mat lf = m_map.clone();
  628. cv::Mat rf = m_map.clone();
  629. cv::Mat lb = m_map.clone();
  630. cv::Mat rb = m_map.clone();
  631. //整车旋转
  632. Eigen::Rotation2D<double> rotation(detect_result.theta);
  633. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  634. //左前偏移
  635. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(detect_result.wheel_base / 2.0, (detect_result.width - 0.15) / 2.0);
  636. //右前偏移
  637. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(detect_result.wheel_base / 2.0, (-detect_result.width + 0.15) / 2.0);
  638. //左后偏移
  639. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-detect_result.wheel_base / 2.0, (detect_result.width - 0.15) / 2.0);
  640. //右后偏移
  641. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-detect_result.wheel_base / 2.0, (-detect_result.width + 0.15) / 2.0);
  642. //前轮旋转
  643. Eigen::Rotation2D<double> rotation_front(detect_result.front_theta);
  644. Eigen::Matrix<double, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  645. // 左前轮
  646. for (size_t i = 0; i < m_left_front_cloud.size(); i++)
  647. {
  648. Eigen::Matrix<double, 2, 1> point((double(m_left_front_cloud[i].x) - detect_result.cx),
  649. (double(m_left_front_cloud[i].y) - detect_result.cy));
  650. //减去经过车辆旋转计算的左前中心
  651. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  652. //旋转
  653. Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  654. int r = (int)(point_rotation(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  655. int c = (int)(point_rotation(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  656. cv::circle(lf, cv::Point(c, r), 1, cv::Scalar(150));
  657. // std::cout<<"map r,c "<<m_map.rows<<", "<<m_map.cols<<std::endl;
  658. // std::cout<<"r,c "<<r<<", "<<c<<std::endl;
  659. // lf.at<uchar>(r, c) = 150;
  660. }
  661. //右前轮
  662. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  663. {
  664. Eigen::Matrix<double, 2, 1> point((double(m_right_front_cloud[i].x) - detect_result.cx),
  665. (double(m_right_front_cloud[i].y) - detect_result.cy));
  666. //减去经过车辆旋转计算的左前中心
  667. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  668. //旋转
  669. Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  670. int r = (int)(point_rotation(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  671. int c = (int)(point_rotation(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  672. cv::circle(rf, cv::Point(c, r), 1, cv::Scalar(150));
  673. }
  674. //左后轮
  675. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  676. {
  677. Eigen::Matrix<double, 2, 1> point((double(m_left_rear_cloud[i].x) - detect_result.cx),
  678. (double(m_left_rear_cloud[i].y) - detect_result.cy));
  679. //减去经过车辆旋转计算的左前中心
  680. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  681. int r = (int)(tanslate_point(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  682. int c = (int)(tanslate_point(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  683. cv::circle(lb, cv::Point(c, r), 1, cv::Scalar(150));
  684. }
  685. //右后轮
  686. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  687. {
  688. Eigen::Matrix<double, 2, 1> point((double(m_right_rear_cloud[i].x) - detect_result.cx),
  689. (double(m_right_rear_cloud[i].y) - detect_result.cy));
  690. //减去经过车辆旋转计算的左前中心
  691. Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  692. int r = (int)(tanslate_point(1, 0) * SCALE + m_map.rows / 2.0 + 0.5);
  693. int c = (int)(tanslate_point(0, 0) * SCALE + m_map.cols / 2.0 + 0.5);
  694. cv::circle(rb, cv::Point(c, r), 1, cv::Scalar(150));
  695. }
  696. // cv::Mat rot90;// = (cv::Mat_<double>(2, 3)<<cos(90), -sin(90), 0, sin(90), cos(90), 0);
  697. // rot90 = cv::getRotationMatrix2D(cv::Point2f(lf.cols/2, lf.rows/2), 90, 1);
  698. // // std::cout<<rot90<<std::endl;
  699. // cv::warpAffine(lf, lf, rot90, cv::Size(lf.cols, lf.rows));
  700. // cv::flip()
  701. // cv::namedWindow("left front", cv::WINDOW_FREERATIO);
  702. // cv::namedWindow("right front", cv::WINDOW_FREERATIO);
  703. // cv::namedWindow("left back", cv::WINDOW_FREERATIO);
  704. // cv::namedWindow("right back", cv::WINDOW_FREERATIO);
  705. cv::flip(lf, lf, -1);
  706. cv::flip(rf, rf, -1);
  707. cv::flip(lb, lb, -1);
  708. cv::flip(rb, rb, -1);
  709. cv::Mat lft = lf.t(), rft = rf.t(), lbt = lb.t(), rbt = rb.t();
  710. // cv::imshow("left front", lf.t());
  711. // cv::imshow("right front", rf.t());
  712. // cv::imshow("left back", lb.t());
  713. // cv::imshow("right back", rb.t());
  714. // 写入各轮平均误差
  715. cv::putText(lft, (boost::format("lf %.6f") % (loss_result.lf_loss)).str().c_str(),
  716. cv::Point(lft.cols / 6, lft.rows / 4),
  717. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  718. cv::putText(rft, (boost::format("rf %.6f") % (loss_result.rf_loss)).str().c_str(),
  719. cv::Point(rft.cols / 6, rft.rows / 4),
  720. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  721. cv::putText(lbt, (boost::format("lb %.6f") % (loss_result.lb_loss)).str().c_str(),
  722. cv::Point(lbt.cols / 6, lbt.rows / 4),
  723. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  724. cv::putText(rbt, (boost::format("rb %.6f") % (loss_result.rb_loss)).str().c_str(),
  725. cv::Point(rbt.cols / 6, rbt.rows / 4),
  726. cv::FONT_HERSHEY_COMPLEX, 1, cv::Scalar(0, 0, 0));
  727. cv::Mat total_img = cv::Mat::zeros(m_map.cols * 2, m_map.rows * 2, m_map.type());
  728. lft.copyTo(total_img(cv::Rect(0, 0, m_map.rows, m_map.cols)));
  729. rft.copyTo(total_img(cv::Rect(m_map.rows, 0, m_map.rows, m_map.cols)));
  730. lbt.copyTo(total_img(cv::Rect(0, m_map.cols, m_map.rows, m_map.cols)));
  731. rbt.copyTo(total_img(cv::Rect(m_map.rows, m_map.cols, m_map.rows, m_map.cols)));
  732. // cv::namedWindow("total img", CV_WINDOW_FREERATIO);
  733. // cv::imshow("total img", total_img);
  734. // cv::waitKey(20);
  735. if(save_img)
  736. {
  737. cv::Mat cvted_img = cv::Mat::zeros(m_map.cols * 2, m_map.rows * 2, CV_8U);
  738. int total_milli = (std::chrono::time_point_cast<std::chrono::milliseconds>(std::chrono::system_clock::now())).time_since_epoch().count();
  739. std::string img_filename="";
  740. if(out_img_path.empty()){
  741. img_filename = std::string("/home/youchen/Documents/measure/MainStructure/elecfence_ws/img/img").append(std::to_string(total_milli)).append(".jpg");
  742. }
  743. else{
  744. img_filename = out_img_path;
  745. }
  746. LOG(INFO) << "write to " << img_filename.c_str();
  747. // cv::cvtColor(total_img*255, cvted_img, CV_8U);
  748. cv::convertScaleAbs(total_img * 255, cvted_img);
  749. cv::imwrite(img_filename, cvted_img);
  750. }
  751. }