detect_wheel_ceres.cpp 39 KB

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