detect_wheel_ceres3d.cpp 38 KB

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