detect_wheel_ceres3d.cpp 38 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #include "detect_wheel_ceres3d.h"
  5. #include "interpolated_grid.hpp"
  6. #include <pcl/common/transforms.h>
  7. #include "point_tool.h"
  8. class CostFunctor3d
  9. {
  10. private:
  11. const InterpolatedProbabilityGrid m_left_interpolated_grid;
  12. const InterpolatedProbabilityGrid m_right_interpolated_grid;
  13. mutable double m_costs_lf, m_costs_rf, m_costs_lr, m_costs_rr;
  14. pcl::PointCloud<pcl::PointXYZ> m_left_front_cloud; //左前点云
  15. pcl::PointCloud<pcl::PointXYZ> m_right_front_cloud; //右前点云
  16. pcl::PointCloud<pcl::PointXYZ> m_left_rear_cloud; //左后点云
  17. pcl::PointCloud<pcl::PointXYZ> m_right_rear_cloud; //右后点云
  18. // 20220118 added by yct
  19. float m_ratio; // 模型变换比例,用于贴合模型,cloud / ratio --> model
  20. public:
  21. CostFunctor3d(pcl::PointCloud<pcl::PointXYZ> left_front, pcl::PointCloud<pcl::PointXYZ> right_front,
  22. pcl::PointCloud<pcl::PointXYZ> left_rear, pcl::PointCloud<pcl::PointXYZ> right_rear,
  23. const HybridGrid& left_interpolated_grid,
  24. const HybridGrid& right_interpolated_grid, float ratio)
  25. :m_left_interpolated_grid(left_interpolated_grid),m_right_interpolated_grid(right_interpolated_grid)
  26. {
  27. m_left_front_cloud = left_front;
  28. m_right_front_cloud = right_front;
  29. m_left_rear_cloud = left_rear;
  30. m_right_rear_cloud = right_rear;
  31. m_costs_lf = 0.0;
  32. m_costs_rf = 0.0;
  33. m_costs_lr = 0.0;
  34. m_costs_rr = 0.0;
  35. m_ratio = ratio;
  36. }
  37. template<typename T>
  38. bool operator()(const T *const variable, T *residual) const
  39. {
  40. T cx = variable[0];
  41. T cy = variable[1];
  42. T theta = variable[2];
  43. T length = variable[3];
  44. T width = variable[4];
  45. T theta_front = variable[5];
  46. //整车旋转
  47. Eigen::Rotation2D<T> rotation(theta);
  48. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  49. //左前偏移
  50. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  51. //右前偏移
  52. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  53. //左后偏移
  54. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  55. //右后偏移
  56. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  57. //前轮旋转
  58. Eigen::Rotation2D<T> rotation_front(theta_front);
  59. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  60. //左前轮
  61. int left_front_num = m_left_front_cloud.size();
  62. for (int i = 0; i < m_left_front_cloud.size(); ++i)
  63. {
  64. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud[i].x) - cx),
  65. (T(m_left_front_cloud[i].y) - cy));
  66. //减去经过车辆旋转计算的左前中心
  67. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  68. //旋转
  69. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * (tanslate_point*T(m_ratio));
  70. residual[i] = T(1.0) - m_left_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  71. T(m_left_front_cloud[i].z));
  72. }
  73. //右前轮
  74. int right_front_num = m_right_front_cloud.size();
  75. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  76. {
  77. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud[i].x) - cx),
  78. (T(m_right_front_cloud[i].y) - cy));
  79. //减去经过车辆旋转计算的左前中心
  80. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  81. //旋转
  82. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * (tanslate_point*T(m_ratio));
  83. residual[left_front_num + i] = T(1.0) - m_right_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  84. T(m_right_front_cloud[i].z));
  85. }
  86. //左后轮
  87. int left_rear_num = m_left_rear_cloud.size();
  88. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  89. {
  90. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud[i].x) - cx),
  91. (T(m_left_rear_cloud[i].y) - cy));
  92. //减去经过车辆旋转计算的左前中心
  93. const Eigen::Matrix<T, 2, 1> tanslate_point = (rotation_matrix * point - wheel_center_normal_left_rear)*T(m_ratio);;
  94. residual[left_front_num + right_front_num + i] = T(1.0) -
  95. m_left_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  96. T(m_left_rear_cloud[i].z));
  97. }
  98. //右后轮
  99. int right_rear_num = m_right_rear_cloud.size();
  100. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  101. {
  102. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud[i].x) - cx),
  103. (T(m_right_rear_cloud[i].y) - cy));
  104. //减去经过车辆旋转计算的左前中心
  105. const Eigen::Matrix<T, 2, 1> tanslate_point = (rotation_matrix * point - wheel_center_normal_right_rear)*T(m_ratio);
  106. residual[left_front_num + right_front_num + left_rear_num+i] = T(1.0) -
  107. m_right_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  108. T(m_right_rear_cloud[i].z));
  109. }
  110. return true;
  111. }
  112. };
  113. detect_wheel_ceres3d::detect_wheel_ceres3d(pcl::PointCloud<pcl::PointXYZ>::Ptr left_grid_cloud,
  114. pcl::PointCloud<pcl::PointXYZ>::Ptr right_grid_cloud)
  115. {
  116. m_left_model_cloud.clear();
  117. m_right_model_cloud.clear();
  118. m_left_model_cloud += *left_grid_cloud;
  119. m_right_model_cloud += *right_grid_cloud;
  120. mp_left_grid = nullptr;
  121. mp_right_grid = nullptr;
  122. // LOG(INFO) << "init model start";
  123. update_model();
  124. // LOG(INFO) <<"init model end";
  125. // save_model("/home/zx/zzw/catkin_ws/src/feature_extra");
  126. }
  127. // 根据点云与模型比例参数更新模型
  128. bool detect_wheel_ceres3d::update_model(float ratio)
  129. {
  130. float del_x=0.05;
  131. float del_y=0.03;
  132. float del_z=0.05;
  133. Eigen::Matrix3f delta=Eigen::MatrixXf::Identity(3,3);
  134. delta(0,0)=del_x*del_x;
  135. delta(1,1)=del_y*del_y;
  136. delta(2,2)=del_z*del_z;
  137. Eigen::Matrix3f delta_inv=delta.inverse();
  138. Eigen::Vector3f d(0,0,0.02);
  139. Eigen::MatrixXf ce=-0.5*((d).transpose()*delta_inv*(d));
  140. float cut_p=exp(ce(0,0));
  141. // std::cout << "1111" << std::endl;
  142. float resolution=0.01;
  143. if(mp_left_grid!=nullptr){
  144. delete mp_left_grid;
  145. mp_left_grid = nullptr;
  146. }
  147. if(mp_right_grid != nullptr){
  148. delete mp_right_grid;
  149. mp_right_grid = nullptr;
  150. }
  151. mp_left_grid=new HybridGrid(resolution);
  152. mp_right_grid=new HybridGrid(resolution);
  153. // 变换模型点云
  154. pcl::PointCloud<pcl::PointXYZ> t_left_model;
  155. t_left_model += m_left_model_cloud;
  156. pcl::PointCloud<pcl::PointXYZ> t_right_model;
  157. t_right_model += m_right_model_cloud;
  158. for (size_t i = 0; i < t_left_model.size(); i++)
  159. {
  160. t_left_model[i].x = t_left_model[i].x * ratio;
  161. t_left_model[i].y = t_left_model[i].y * ratio;
  162. t_left_model[i].z = t_left_model[i].z * ratio;
  163. }
  164. for (size_t i = 0; i < t_right_model.size(); i++)
  165. {
  166. t_right_model[i].x = t_right_model[i].x * ratio;
  167. t_right_model[i].y = t_right_model[i].y * ratio;
  168. t_right_model[i].z = t_right_model[i].z * ratio;
  169. }
  170. for(int i=0;i<t_left_model.size();++i)
  171. {
  172. pcl::PointXYZ pt=t_left_model[i];
  173. Eigen::Vector3f u(pt.x,pt.y,pt.z);
  174. for(float x=pt.x-0.1;x<pt.x+0.1;x+=mp_left_grid->resolution())
  175. {
  176. for(float y=pt.y-0.1;y<pt.y+0.1;y+=mp_left_grid->resolution())
  177. {
  178. for(float z=pt.z-0.1;z<pt.z+0.1;z+=mp_left_grid->resolution())
  179. {
  180. Eigen::Vector3f p(x,y,z);
  181. Eigen::MatrixXf B=-0.5*((p-u).transpose()*delta_inv*(p-u));
  182. float prob=exp(B(0,0));
  183. if(prob>cut_p)
  184. prob=cut_p;
  185. Eigen::Array3i index=mp_left_grid->GetCellIndex(p);
  186. if(mp_left_grid->GetProbability(index)<prob){
  187. mp_left_grid->SetProbability(index,prob);
  188. }
  189. }
  190. }
  191. }
  192. }
  193. // std::cout << "3333" << std::endl;
  194. for(int i=0;i<t_right_model.size();++i)
  195. {
  196. pcl::PointXYZ pt=t_right_model[i];
  197. Eigen::Vector3f u(pt.x,pt.y,pt.z);
  198. for(float x=pt.x-0.1;x<pt.x+0.1;x+=mp_right_grid->resolution())
  199. {
  200. for(float y=pt.y-0.1;y<pt.y+0.1;y+=mp_right_grid->resolution())
  201. {
  202. for(float z=pt.z-0.1;z<pt.z+0.1;z+=mp_right_grid->resolution())
  203. {
  204. Eigen::Vector3f p(x,y,z);
  205. Eigen::MatrixXf B=-0.5*((p-u).transpose()*delta_inv*(p-u));
  206. float prob=exp(B(0,0));
  207. if(prob>cut_p)
  208. prob=cut_p;
  209. Eigen::Array3i index=mp_right_grid->GetCellIndex(p);
  210. if(mp_right_grid->GetProbability(index)<prob)
  211. mp_right_grid->SetProbability(index,prob);
  212. }
  213. }
  214. }
  215. }
  216. return true;
  217. }
  218. void detect_wheel_ceres3d::save_model(std::string dir)
  219. {
  220. InterpolatedProbabilityGrid inter_grid(*mp_left_grid);
  221. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_grid(new pcl::PointCloud<pcl::PointXYZRGB>);
  222. for(int x=0;x<mp_left_grid->grid_size();++x)
  223. {
  224. for(int y=0;y<mp_left_grid->grid_size();++y)
  225. {
  226. for(int z=0;z<mp_left_grid->grid_size();++z)
  227. {
  228. Eigen::Array3i index(x-mp_left_grid->grid_size()/2,
  229. y-mp_left_grid->grid_size()/2,z-mp_left_grid->grid_size()/2);
  230. Eigen::Vector3f pt=mp_left_grid->GetCenterOfCell(index);
  231. float prob=inter_grid.GetInterpolatedValue(double(pt[0]),double(pt[1]),double(pt[2]));
  232. if(prob>0.01)
  233. {
  234. Eigen::Vector3f pt=mp_left_grid->GetCenterOfCell(index);
  235. int rgb=int((prob-0.01)*255);
  236. pcl::PointXYZRGB point;
  237. point.x=pt[0];
  238. point.y=pt[1];
  239. point.z=pt[2];
  240. point.r=rgb;
  241. point.g=0;
  242. point.b=255-rgb;
  243. cloud_grid->push_back(point);
  244. }
  245. }
  246. }
  247. }
  248. InterpolatedProbabilityGrid right_grid(*mp_right_grid);
  249. pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_right_grid(new pcl::PointCloud<pcl::PointXYZRGB>);
  250. for(int x=0;x<mp_right_grid->grid_size();++x)
  251. {
  252. for(int y=0;y<mp_right_grid->grid_size();++y)
  253. {
  254. for(int z=0;z<mp_right_grid->grid_size();++z)
  255. {
  256. Eigen::Array3i index(x-mp_right_grid->grid_size()/2,
  257. y-mp_right_grid->grid_size()/2,z-mp_right_grid->grid_size()/2);
  258. Eigen::Vector3f pt=mp_right_grid->GetCenterOfCell(index);
  259. float prob=right_grid.GetInterpolatedValue(double(pt[0]),double(pt[1]),double(pt[2]));
  260. if(prob>0.01)
  261. {
  262. Eigen::Vector3f pt=mp_right_grid->GetCenterOfCell(index);
  263. int rgb=int((prob-0.01)*255);
  264. pcl::PointXYZRGB point;
  265. point.x=pt[0];
  266. point.y=pt[1];
  267. point.z=pt[2];
  268. point.r=rgb;
  269. point.g=0;
  270. point.b=255-rgb;
  271. cloud_right_grid->push_back(point);
  272. }
  273. }
  274. }
  275. }
  276. //std::cout<<" save model :"<<dir<<std::endl;
  277. //save_cloud_txt(cloud_grid,dir+"/left_model.txt");
  278. //save_cloud_txt(cloud_right_grid,dir+"/right_model.txt");
  279. }
  280. detect_wheel_ceres3d::~detect_wheel_ceres3d(){
  281. delete mp_left_grid;
  282. delete mp_right_grid;
  283. mp_left_grid= nullptr;
  284. mp_right_grid= nullptr;
  285. }
  286. bool detect_wheel_ceres3d::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> cloud_vec,
  287. Detect_result &detect_result, std::string &error_info)
  288. {
  289. error_info = "";
  290. //清理点云
  291. m_left_front_cloud.clear();
  292. m_right_front_cloud.clear();
  293. m_left_rear_cloud.clear();
  294. m_right_rear_cloud.clear();
  295. //重新计算点云,按方位分割
  296. //第一步,计算整体中心,主轴方向
  297. pcl::PointCloud<pcl::PointXYZ> cloud_all;
  298. for (int i = 0; i < cloud_vec.size(); ++i)
  299. {
  300. cloud_all += (*cloud_vec[i]);
  301. }
  302. // std::cout<<"cloud size: "<<cloud_all.size()<<std::endl;
  303. if (cloud_all.size() < 20)
  304. return false;
  305. Eigen::Vector4f centroid;
  306. pcl::compute3DCentroid(cloud_all, centroid);
  307. double center_x = centroid[0];
  308. double center_y = centroid[1];
  309. // printf("3dwheel x,y:%.3f, %.3f\n", center_x, center_y);
  310. // save_cloud_txt(cloud_all.makeShared(), "total_wheel.txt");
  311. //计算外接旋转矩形
  312. std::vector<cv::Point2f> points_cv;
  313. for (int i = 0; i < cloud_all.size(); ++i)
  314. {
  315. points_cv.push_back(cv::Point2f(cloud_all[i].x, cloud_all[i].y));
  316. }
  317. cv::RotatedRect rotate_rect = cv::minAreaRect(points_cv);
  318. //计算旋转矩形与X轴的夹角
  319. cv::Point2f vec;
  320. cv::Point2f vertice[4];
  321. rotate_rect.points(vertice);
  322. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  323. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  324. // 寻找长边,倾角为长边与x轴夹角
  325. if (len1 > len2)
  326. {
  327. vec.x = vertice[0].x - vertice[1].x;
  328. vec.y = vertice[0].y - vertice[1].y;
  329. }
  330. else
  331. {
  332. vec.x = vertice[1].x - vertice[2].x;
  333. vec.y = vertice[1].y - vertice[2].y;
  334. }
  335. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  336. // printf("rect theta: %.3f\n",angle_x);
  337. // 20211203 added by yct, 初始xy不准确,逻辑调整
  338. pcl::PointCloud<pcl::PointXYZ> t_cloud_left, t_cloud_right, t_cloud_front, t_cloud_rear;
  339. //第二步, 将每份点云旋转回去,计算点云重心所在象限
  340. for (int i = 0; i < cloud_vec.size(); ++i)
  341. {
  342. pcl::PointCloud<pcl::PointXYZ> cloud = (*cloud_vec[i]);
  343. Eigen::Affine3f traslation = Eigen::Affine3f::Identity();//初始化变换矩阵为单位矩阵
  344. // 平移
  345. traslation.translation() << -center_x, -center_y, 0.0;
  346. pcl::PointCloud<pcl::PointXYZ> translate_cloud;
  347. pcl::transformPointCloud(cloud, translate_cloud, traslation);
  348. // 旋转; Z 轴上旋转angle_x 弧度,Y轴上旋转0弧度
  349. Eigen::Affine3f rotation = Eigen::Affine3f::Identity();
  350. rotation.rotate(Eigen::AngleAxisf(-angle_x * M_PI / 180.0, Eigen::Vector3f::UnitZ()));
  351. pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
  352. pcl::transformPointCloud(translate_cloud, transformed_cloud, rotation);
  353. //计算重心
  354. Eigen::Vector4f centroid;
  355. pcl::compute3DCentroid(transformed_cloud, centroid);
  356. double x = centroid[0];
  357. double y = centroid[1];
  358. //计算象限
  359. if (x > 0 && y > 0)
  360. {
  361. //第一象限
  362. m_left_front_cloud = cloud;
  363. t_cloud_left+=(m_left_front_cloud);
  364. t_cloud_front+=(m_left_front_cloud);
  365. }
  366. if (x > 0 && y < 0)
  367. {
  368. //第四象限
  369. m_right_front_cloud = cloud;
  370. t_cloud_right+=(m_right_front_cloud);
  371. t_cloud_front+=(m_right_front_cloud);
  372. }
  373. if (x < 0 && y > 0)
  374. {
  375. //第二象限
  376. m_left_rear_cloud = cloud;
  377. t_cloud_left+=(m_left_rear_cloud);
  378. t_cloud_rear+=(m_left_rear_cloud);
  379. }
  380. if (x < 0 && y < 0)
  381. {
  382. //第三象限
  383. m_right_rear_cloud = cloud;
  384. t_cloud_right+=(m_right_rear_cloud);
  385. t_cloud_rear+=(m_right_rear_cloud);
  386. }
  387. }
  388. // 20211203 added by yct, 重新计算xy
  389. Eigen::Vector4f centroid_left,centroid_right,centroid_front,centroid_rear;
  390. // 计算x
  391. pcl::compute3DCentroid(t_cloud_left, centroid_left);
  392. pcl::compute3DCentroid(t_cloud_right, centroid_right);
  393. // 计算y
  394. pcl::compute3DCentroid(t_cloud_front, centroid_front);
  395. pcl::compute3DCentroid(t_cloud_rear, centroid_rear);
  396. // LOG(WARNING)<<"x,y: "<<(centroid_left.x()+centroid_right.x())/2.0f<<", "<<(centroid_front.y()+centroid_rear.y())/2.0f;
  397. // 使用外部第一步优化产生的x,以及当前计算后的y作为初值
  398. // 多次优化,获取最佳优化结果
  399. // detect_result.cx = center_x;
  400. detect_result.cx = detect_result.cx;
  401. detect_result.cy = (centroid_front.y()+centroid_rear.y())/2.0f;
  402. detect_result.wheel_base = centroid_front.y() - centroid_rear.y() + 0.12; //std::max(len1,len2);
  403. // 已计算次数,初始传入值正常,之后solve函数会修改初始值,需要恢复角度单位为弧度
  404. int calc_count = 0;
  405. // double final_theta = 0;
  406. // 误差结构体,保存左前、右前、左后、右后、整体平均误差
  407. Loss_result loss_result;
  408. // 平均误差值,用于获取最小整体平均误差
  409. double avg_loss = 100;
  410. // 定义图像列数,控制图像大小
  411. int map_cols = 800;
  412. // 优化后图像行数,用于保存优化后结果图像
  413. int optimized_map_rows = 200;
  414. // 优化结果
  415. bool solve_result = false;
  416. double total_solve_time = 0;
  417. bool stop_sign = false;
  418. Detect_result t_detect_result = detect_result;
  419. // 寻找最小loss值对应的初始旋转角
  420. // LOG(WARNING) <<cloud_all.size()<< ", car angle: "<<t_detect_result.theta<<", "<<(-angle_x ) * M_PI / 180.0;
  421. // t_detect_result.theta = (-angle_x ) * M_PI / 180.0;
  422. Loss_result t_loss_result;
  423. t_loss_result.total_avg_loss = 1000;
  424. //输出角度已变化,需恢复成弧度
  425. if (calc_count > 0)
  426. {
  427. t_detect_result.front_theta *= (-M_PI) / 180.0;
  428. }
  429. std::string t_error_info;
  430. bool current_result = Solve(t_detect_result, t_loss_result, t_error_info);
  431. error_info = t_error_info;
  432. // std::cout<<"current_result: "<<current_result<<std::endl;
  433. if (current_result)
  434. {
  435. avg_loss = t_loss_result.total_avg_loss;
  436. // final_theta = -input_vars[2] * M_PI / 180.0;
  437. detect_result = t_detect_result;
  438. detect_result.loss = t_loss_result;
  439. solve_result = current_result;
  440. loss_result = t_loss_result;
  441. }
  442. detect_result.success = solve_result;
  443. return solve_result;
  444. }
  445. void detect_wheel_ceres3d::get_costs(double* variable,double &lf, double &rf, double &lr, double &rr)
  446. {
  447. double losses[4]={0};
  448. double cx = variable[0];
  449. double cy = variable[1];
  450. double theta = variable[2];
  451. double length = variable[3];
  452. double width = variable[4];
  453. double theta_front = variable[5];
  454. //整车旋转
  455. Eigen::Rotation2D<double> rotation(theta);
  456. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  457. //左前偏移
  458. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  459. //右前偏移
  460. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  461. //左后偏移
  462. Eigen::Matrix<double, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  463. //右后偏移
  464. Eigen::Matrix<double, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  465. //前轮旋转
  466. Eigen::Rotation2D<double> rotation_front(theta_front);
  467. Eigen::Matrix<double, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  468. InterpolatedProbabilityGrid left_interpolated_grid(*mp_left_grid);
  469. InterpolatedProbabilityGrid right_interpolated_grid(*mp_right_grid);
  470. //左前轮
  471. int left_front_num = m_left_front_cloud.size();
  472. m_left_front_transformed_cloud.clear();
  473. for (int i = 0; i < m_left_front_cloud.size(); ++i)
  474. {
  475. const Eigen::Matrix<double, 2, 1> point((double(m_left_front_cloud[i].x) - cx),
  476. (double(m_left_front_cloud[i].y) - cy));
  477. //减去经过车辆旋转计算的左前中心
  478. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  479. //旋转
  480. const Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  481. losses[0] += 1.0 - left_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  482. double(m_left_front_cloud[i].z));
  483. m_left_front_transformed_cloud.push_back(pcl::PointXYZ(point_rotation[0],point_rotation[1],m_left_front_cloud[i].z));
  484. }
  485. //右前轮
  486. int right_front_num = m_right_front_cloud.size();
  487. m_right_front_transformed_cloud.clear();
  488. for (int i = 0; i < m_right_front_cloud.size(); ++i)
  489. {
  490. const Eigen::Matrix<double, 2, 1> point((double(m_right_front_cloud[i].x) - cx),
  491. (double(m_right_front_cloud[i].y) - cy));
  492. //减去经过车辆旋转计算的左前中心
  493. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  494. //旋转
  495. const Eigen::Matrix<double, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  496. losses[1]+= 1.0 - right_interpolated_grid.GetInterpolatedValue(point_rotation[0],point_rotation[1],
  497. double(m_right_front_cloud[i].z));
  498. m_right_front_transformed_cloud.push_back(pcl::PointXYZ(point_rotation[0],point_rotation[1],
  499. double(m_right_front_cloud[i].z)));
  500. }
  501. //左后轮
  502. int left_rear_num = m_left_rear_cloud.size();
  503. m_left_rear_transformed_cloud.clear();
  504. for (int i = 0; i < m_left_rear_cloud.size(); ++i)
  505. {
  506. const Eigen::Matrix<double, 2, 1> point((double(m_left_rear_cloud[i].x) - cx),
  507. (double(m_left_rear_cloud[i].y) - cy));
  508. //减去经过车辆旋转计算的左前中心
  509. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  510. losses[2] += 1.0 -
  511. left_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  512. double(m_left_rear_cloud[i].z));
  513. m_left_rear_transformed_cloud.push_back(pcl::PointXYZ(tanslate_point[0],tanslate_point[1],
  514. double(m_left_rear_cloud[i].z)));
  515. }
  516. //右后轮
  517. int right_rear_num = m_right_rear_cloud.size();
  518. m_right_rear_transformed_cloud.clear();
  519. for (int i = 0; i < m_right_rear_cloud.size(); ++i)
  520. {
  521. const Eigen::Matrix<double, 2, 1> point((double(m_right_rear_cloud[i].x) - cx),
  522. (double(m_right_rear_cloud[i].y) - cy));
  523. //减去经过车辆旋转计算的左前中心
  524. const Eigen::Matrix<double, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  525. losses[3]+= 1.0 -
  526. right_interpolated_grid.GetInterpolatedValue(tanslate_point[0],tanslate_point[1],
  527. double(m_right_rear_cloud[i].z));
  528. m_right_rear_transformed_cloud.push_back(pcl::PointXYZ(tanslate_point[0],tanslate_point[1],
  529. double(m_right_rear_cloud[i].z)));
  530. }
  531. lf=losses[0];
  532. rf=losses[1];
  533. lr =losses[2];
  534. rr =losses[3];
  535. }
  536. void detect_wheel_ceres3d::save_debug_data(std::string dir )
  537. {
  538. ::save_cloud_txt(m_left_front_transformed_cloud.makeShared(),dir+"/left_front_tranformed.txt");
  539. ::save_cloud_txt(m_right_front_transformed_cloud.makeShared(),dir+"/right_front_tranformed.txt");
  540. ::save_cloud_txt(m_left_rear_transformed_cloud.makeShared(),dir+"/left_rear_tranformed.txt");
  541. ::save_cloud_txt(m_right_rear_transformed_cloud.makeShared(),dir+"/right_rear_tranformed.txt");
  542. }
  543. // 外接矩形估算车轮宽度,以此调整模型比例
  544. bool detect_wheel_ceres3d::wheel_size_estimate(double &wheel_width, double &wheel_length, double car_angle, float &ratio)
  545. {
  546. // 分别对四轮寻找外接矩形
  547. int rect_res = 0;
  548. cv::RotatedRect rects[4]; // t_left_front_rect, t_right_front_rect, t_left_rear_rect, t_right_rear_rect;
  549. double rot_angles[4], lengths[4], widths[4];
  550. rect_res += get_wheel_rect(m_left_front_cloud, rects[0], rot_angles[0], lengths[0], widths[0]) ? 0 : 1;
  551. rect_res += get_wheel_rect(m_right_front_cloud, rects[1], rot_angles[1], lengths[1], widths[1]) ? 0 : 1;
  552. rect_res += get_wheel_rect(m_left_rear_cloud, rects[2], rot_angles[2], lengths[2], widths[2]) ? 0 : 1;
  553. rect_res += get_wheel_rect(m_right_rear_cloud, rects[3], rot_angles[3], lengths[3], widths[3]) ? 0 : 1;
  554. // 只允许一个异常轮胎
  555. if(rect_res > 1)
  556. {
  557. // std::cout << "异常轮胎过多 " << rect_res << std::endl;
  558. return false;
  559. }
  560. // 计算轮宽
  561. double avg_width = 0.0;
  562. double avg_length = 0.0;
  563. for (size_t i = 2; i < 4; i++)
  564. {
  565. avg_width += widths[i];
  566. avg_length += lengths[i];
  567. }
  568. avg_width /= 2.0;
  569. avg_length /= 2.0;
  570. // std::cout << "avg width: " << avg_width << ", avg length: " << avg_length << std::endl;
  571. // 以投影方式计算轮宽
  572. Eigen::Vector2d car_angle_vec(cos(-car_angle), sin(-car_angle));
  573. double left_min=INT_MAX, left_max=-INT_MAX, right_min=INT_MAX, right_max=-INT_MAX;
  574. if(m_left_rear_cloud.size()==0 || m_right_rear_cloud.size()==0)
  575. {
  576. ratio = 1.0f;
  577. return false;
  578. }
  579. for (size_t i = 0; i < m_left_rear_cloud.size(); i++)
  580. {
  581. Eigen::Vector2d point_vec(m_left_rear_cloud[i].x, m_left_rear_cloud[i].y);
  582. double res = sqrt(point_vec.squaredNorm() - pow(car_angle_vec.dot(point_vec),2));
  583. // std::cout<<"lres: "<<res<<std::endl;
  584. if(res<left_min)
  585. left_min=res;
  586. if(res>left_max)
  587. left_max=res;
  588. }
  589. for (size_t i = 0; i < m_right_rear_cloud.size(); i++)
  590. {
  591. Eigen::Vector2d point_vec(m_right_rear_cloud[i].x, m_right_rear_cloud[i].y);
  592. double res = sqrt(point_vec.squaredNorm() - pow(car_angle_vec.dot(point_vec),2));
  593. // std::cout<<"rres: "<<res<<std::endl;
  594. if(res<right_min)
  595. right_min=res;
  596. if(res>right_max)
  597. right_max=res;
  598. }
  599. double new_wheel_width = (left_max+right_max-left_min-right_min)/2.0;
  600. // std::cout << "avg width: " << avg_width << ", new width: " << new_wheel_width << std::endl;
  601. wheel_width = new_wheel_width;
  602. wheel_length = avg_length;
  603. // ratio = 1.0f;
  604. // 轮宽范围,实际0.185-0.3,通常会少0.03-0.04,(新方法不会少),因此设定范围0.175-0.275
  605. // 比例以半径0.64为模板,范围0.6-0.7
  606. if(wheel_width<0.18||wheel_width>0.3)
  607. {
  608. ratio = 1.0f;
  609. }else{
  610. float t_model_ratio = float((0.6 + ((wheel_width - 0.175) * 0.1 / 0.1)) / 0.64);
  611. t_model_ratio = std::max(0.6f/0.64f, t_model_ratio);
  612. t_model_ratio = std::min(0.7f/0.64f, t_model_ratio);
  613. ratio = 1.0f / t_model_ratio;
  614. }
  615. return true;
  616. }
  617. // 使用外接矩形,车轮越大,多条线照到车轮的概率与车轮半径都越大,导致外接矩形向内侧收拢的趋势更明显,轴距偏小得越厉害
  618. bool detect_wheel_ceres3d::wheebase_estimate(double &wheelbase, double &wheel_width, double &wheel_length)
  619. {
  620. // 分别对四轮寻找外接矩形
  621. int rect_res = 0;
  622. cv::RotatedRect rects[4]; // t_left_front_rect, t_right_front_rect, t_left_rear_rect, t_right_rear_rect;
  623. double rot_angles[4], lengths[4], widths[4];
  624. rect_res += get_wheel_rect(m_left_front_cloud, rects[0], rot_angles[0], lengths[0], widths[0]) ? 0 : 1;
  625. rect_res += get_wheel_rect(m_right_front_cloud, rects[1], rot_angles[1], lengths[1], widths[1]) ? 0 : 1;
  626. rect_res += get_wheel_rect(m_left_rear_cloud, rects[2], rot_angles[2], lengths[2], widths[2]) ? 0 : 1;
  627. rect_res += get_wheel_rect(m_right_rear_cloud, rects[3], rot_angles[3], lengths[3], widths[3]) ? 0 : 1;
  628. // 只允许一个异常轮胎
  629. if(rect_res > 1)
  630. {
  631. // std::cout << "异常轮胎过多 " << rect_res << std::endl;
  632. return false;
  633. }
  634. // 计算轮宽
  635. double avg_width = 0.0;
  636. double avg_length = 0.0;
  637. for (size_t i = 2; i < 4; i++)
  638. {
  639. avg_width += widths[i];
  640. avg_length += lengths[i];
  641. }
  642. avg_width /= 2.0;
  643. avg_length /= 2.0;
  644. // std::cout << "avg width: " << avg_width << ", avg length: " << avg_length << std::endl;
  645. wheel_width = avg_width;
  646. wheel_length = avg_length;
  647. // 检查角度,后轮不可超过5度,前轮不可超过30度
  648. int rear_limit_count = 0, front_limit_count = 0;
  649. int rear_abnormal_index = -1, front_abnormal_index = -1;
  650. for (size_t i = 2; i < 4; i++)
  651. {
  652. if (90-rot_angles[i] > 5)
  653. {
  654. // std::cout << "后轮角度 " << rot_angles[i] << std::endl;
  655. rear_limit_count++;
  656. rear_abnormal_index = i;
  657. }
  658. // else
  659. // {
  660. // // 后轮记录
  661. // rear_index = i;
  662. // }
  663. }
  664. for (size_t i = 0; i < 2; i++)
  665. {
  666. if (90-rot_angles[i] > 30)
  667. {
  668. // std::cout << "前轮角度 " << rot_angles[i] << std::endl;
  669. front_limit_count++;
  670. front_abnormal_index = i;
  671. }
  672. // else
  673. // {
  674. // // 前轮记录
  675. // front_index = i;
  676. // }
  677. }
  678. // 异常矩形超过一个
  679. if (rear_limit_count + front_limit_count > 1)
  680. {
  681. // std::cout << "异常矩形过多 " << rear_limit_count<<", "<<front_limit_count << std::endl;
  682. return false;
  683. }
  684. // 剔除可能异常数据,计算轴距
  685. Eigen::Vector2d wb_vector;
  686. if (rear_abnormal_index != 2 && front_abnormal_index != 0)
  687. {
  688. wb_vector << rects[0].center.x - rects[2].center.x, rects[0].center.y - rects[2].center.y;
  689. }else if(rear_abnormal_index != 3 && front_abnormal_index != 1){
  690. wb_vector << rects[1].center.x - rects[3].center.x, rects[1].center.y - rects[3].center.y;
  691. }else{
  692. return false;
  693. }
  694. wheelbase = wb_vector.norm();
  695. double alpha = 0.2;
  696. wheelbase = wheelbase + alpha * (wheelbase - 2.55);
  697. return true;
  698. }
  699. bool detect_wheel_ceres3d::get_wheel_rect(pcl::PointCloud<pcl::PointXYZ> cloud, cv::RotatedRect &rect, double &theta, double &length, double &width)
  700. {
  701. std::vector<cv::Point2f> t_point_vec;
  702. for (size_t i = 0; i < cloud.size(); i++)
  703. {
  704. t_point_vec.push_back(cv::Point2f(cloud[i].x, cloud[i].y));
  705. }
  706. if(t_point_vec.size()<=0)
  707. return false;
  708. rect = cv::minAreaRect(t_point_vec);
  709. length = std::max(rect.size.width, rect.size.height);
  710. width = std::min(rect.size.width, rect.size.height);
  711. // 车轮范围,轮胎直径600-800,宽度165-245
  712. if (length < 0.3 || length >0.9 || width < 0.1 || width > 0.3)
  713. {
  714. // std::cout << "车轮范围越界 0.3-0.9, 0.1-0.3: "<<length<<", "<<width << std::endl;
  715. return false;
  716. }
  717. // 获得真实旋转角,前轮y更大
  718. cv::Point2f corners[4];
  719. rect.points(corners);
  720. for (size_t i = 0; i < 4; i++)
  721. {
  722. for (size_t j = 0; j < 3-i; j++)
  723. {
  724. if(corners[j].y > corners[j+1].y)
  725. {
  726. std::swap(corners[j], corners[j + 1]);
  727. }
  728. }
  729. }
  730. Eigen::Vector2d rear2front;
  731. rear2front << corners[2].x + corners[3].x - corners[0].x - corners[1].x, corners[2].y + corners[3].y - corners[0].y - corners[1].y;
  732. rear2front /= 2;
  733. theta = std::atan2(rear2front.y(), rear2front.x()) * 180.0 / M_PI;
  734. return true;
  735. }
  736. bool detect_wheel_ceres3d::Solve(Detect_result &detect_result, Loss_result &loss_result, std::string &error_info)
  737. {
  738. // 20220118 added by yct. 计算比例传入模型
  739. float model_ratio = 1.0f;
  740. // bool ws_res = wheel_size_estimate(detect_result.single_wheel_width, detect_result.single_wheel_length, detect_result.theta, model_ratio);
  741. // std::cout << "change cloud with ratio: " << model_ratio << std::endl;
  742. double cx=detect_result.cx;
  743. double cy=detect_result.cy;
  744. double init_theta=detect_result.theta;
  745. double init_wheel_base=2.7;
  746. if(detect_result.wheel_base>2.55 && detect_result.wheel_base<3.2)
  747. init_wheel_base=detect_result.wheel_base;
  748. double init_width=1.85;
  749. double init_theta_front=0*M_PI/180.0;
  750. double variable[] = {cx, cy, init_theta, init_wheel_base, init_width, init_theta_front};
  751. // printf("init solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  752. // variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);
  753. // 第二部分:构建寻优问题
  754. ceres::Problem problem;
  755. CostFunctor3d *cost_func = new CostFunctor3d(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,
  756. *mp_left_grid,*mp_right_grid, model_ratio);
  757. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  758. ceres::CostFunction* cost_function =new
  759. ceres::AutoDiffCostFunction<CostFunctor3d, ceres::DYNAMIC, 6>(
  760. cost_func,
  761. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  762. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  763. //第三部分: 配置并运行求解器
  764. ceres::Solver::Options options;
  765. // options.use_nonmonotonic_steps=false;
  766. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  767. //options.logging_type = ceres::LoggingType::SILENT;
  768. options.max_num_iterations=500;
  769. options.num_threads=1;
  770. options.minimizer_progress_to_stdout = false;//输出到cout
  771. ceres::Solver::Summary summary;//优化信息
  772. ceres::Solve(options, &problem, &summary);//求解!!!
  773. // printf("after solve x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",
  774. // variable[0], variable[1], variable[3], variable[4], variable[2], variable[5]);
  775. 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());
  776. detect_result.cx=variable[0];
  777. detect_result.cy=variable[1];
  778. detect_result.theta=(-variable[2])*180.0/M_PI;
  779. detect_result.wheel_base=variable[3];
  780. detect_result.width=variable[4];
  781. detect_result.front_theta=-(variable[5]*180.0/M_PI);
  782. if(detect_result.theta>180.0)
  783. detect_result.theta=detect_result.theta-180.0;
  784. if(detect_result.theta<0)
  785. detect_result.theta+=180.0;
  786. if(summary.iterations.size()<=1){
  787. error_info.append(std::string("仅迭代一轮,优化异常"));
  788. return false;
  789. }
  790. if(summary.iterations[summary.iterations.size()-1].iteration<=1){
  791. error_info.append(std::string("最终仅迭代一轮,优化异常"));
  792. return false;
  793. }
  794. /*printf("it : %d ,summary loss: %.5f \n",
  795. summary.iterations.size(),loss);*/
  796. if (detect_result.width < 1.25 || detect_result.width > 2.000 || detect_result.wheel_base > 3.15 || detect_result.wheel_base < 2.200)
  797. {
  798. error_info.append(std::string("宽度(1.25, 2.00) 轴距(2.20, 3.15): ").append(
  799. std::to_string(detect_result.width).append(", ").append(
  800. std::to_string(detect_result.wheel_base)).append("\t")));
  801. return false;
  802. }
  803. if(detect_result.theta > 120 || detect_result.theta < 60)
  804. {
  805. error_info.append("车身角度错误 ").append(std::to_string(detect_result.theta)).append("\t");
  806. // LOG(WARNING) <<"总角度错误 "<<detect_result.theta;
  807. return false;
  808. }
  809. if(fabs(detect_result.front_theta)>35)
  810. {
  811. error_info.append("前轮角度错误 ").append(std::to_string(detect_result.front_theta)).append("\t");
  812. return false;
  813. }
  814. // 将loss传出
  815. if(cost_func!=nullptr)
  816. {
  817. double costs_lf, costs_rf, costs_lr, costs_rr;
  818. get_costs(variable,costs_lf, costs_rf, costs_lr, costs_rr);
  819. loss_result.lf_loss = costs_lf/float(m_left_front_cloud.size()+1e-6);
  820. loss_result.rf_loss = costs_rf/float(m_right_front_cloud.size()+1e-6);
  821. loss_result.lb_loss = costs_lr/float(m_left_rear_cloud.size()+1e-6);
  822. loss_result.rb_loss = costs_rr/float(m_right_rear_cloud.size()+1e-6);
  823. loss_result.total_avg_loss = loss;
  824. detect_result.loss=loss_result;
  825. if(loss_result.lf_loss>0.4 || loss_result.rf_loss>0.4
  826. ||loss_result.lb_loss>0.4||loss_result.rb_loss>0.4)
  827. {
  828. error_info.append("loss过大 lf").append(std::to_string(loss_result.lf_loss)).append(",rf").append(std::to_string(loss_result.rf_loss)).append(", lr").
  829. append(std::to_string(loss_result.lb_loss)).append(",rb").append(std::to_string(loss_result.rb_loss));
  830. return false;
  831. }
  832. }
  833. else
  834. {
  835. return false;
  836. }
  837. return true;
  838. }