detect_wheel_ceres.cpp 39 KB

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