car_pose_detector.cpp 8.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189
  1. /*
  2. * @Description:
  3. * @Author: yct
  4. * @Date: 2021-09-16 15:18:34
  5. * @LastEditTime: 2021-10-12 17:38:39
  6. * @LastEditors: yct
  7. */
  8. #include "car_pose_detector.h"
  9. // 变换点云, 反向平移后旋转
  10. void Car_pose_detector::inv_trans_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double x, double y, double theta)
  11. {
  12. for (int i = 0; i < cloud_ptr->size(); i++)
  13. {
  14. Eigen::Matrix<double, 2, 1> t_point(double(cloud_ptr->points[i].x) - x, double(cloud_ptr->points[i].y) - y);
  15. Eigen::Rotation2D<double> rotation(theta);
  16. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  17. Eigen::Matrix<double, 2, 1> trans_point = rotation_matrix * t_point;
  18. cloud_ptr->points[i].x = trans_point.x();
  19. cloud_ptr->points[i].y = trans_point.y();
  20. }
  21. }
  22. // 变换点云,旋转后平移
  23. void Car_pose_detector::trans_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double x, double y, double theta)
  24. {
  25. for (int i = 0; i < cloud_ptr->size(); i++)
  26. {
  27. Eigen::Matrix<double, 2, 1> t_point(double(cloud_ptr->points[i].x), double(cloud_ptr->points[i].y));
  28. Eigen::Rotation2D<double> rotation(theta);
  29. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  30. Eigen::Matrix<double, 2, 1> trans_point = rotation_matrix * t_point;
  31. cloud_ptr->points[i].x = trans_point.x()+x;
  32. cloud_ptr->points[i].y = trans_point.y()+y;
  33. }
  34. }
  35. // 创建两轴具体曲线
  36. void Car_pose_detector::create_curve_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double width)
  37. {
  38. for (double x = -2.5; x < 2.5; x += 0.02)
  39. {
  40. double left_value = 1.0 / (1.0 + exp(30 * (x + width / 2.0)));
  41. double right_value = 1.0 / (1.0 + exp(30 * (-x + width / 2.0)));
  42. double front_value = 1.0 / (1.0 + exp(15 * (x + 2.2)));
  43. double back_value = 1.0 / (1.0 + exp(15 * (-x + 2.2)));
  44. cloud_ptr->push_back(pcl::PointXYZ(x, std::max(left_value, right_value) - 3.0, 0.0));
  45. cloud_ptr->push_back(pcl::PointXYZ(std::max(front_value, back_value) - 2.0, x, 0.0));
  46. }
  47. }
  48. // 检测底盘z方向值,原始点云去中心,并切除底盘z以上部分
  49. bool Car_pose_detector::detect_pose(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr, pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud_ptr, double &x, double &y, double &theta, double &width, double &z_value, bool debug_cloud)
  50. {
  51. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  52. t_cloud->operator+=(*cloud_ptr);
  53. double t_vars[4] = {0, 0, 0, 1.9};
  54. // 去中心化
  55. pcl::PointXYZ t_center(0, 0, 0);
  56. for (size_t i = 0; i < t_cloud->size(); i++)
  57. {
  58. // t_cloud->points[i].x /= 1000.0;
  59. // t_cloud->points[i].y /= 1000.0;
  60. // t_cloud->points[i].z /= 1000.0;
  61. t_center.x += t_cloud->points[i].x;
  62. t_center.y += t_cloud->points[i].y;
  63. // t_center.z += t_cloud->points[i].z;
  64. }
  65. t_center.x /= t_cloud->size();
  66. t_center.y /= t_cloud->size();
  67. // t_center.z /= t_cloud->size();
  68. for (size_t i = 0; i < t_cloud->size(); i++)
  69. {
  70. t_cloud->points[i].x -= t_center.x;
  71. t_cloud->points[i].y -= t_center.y;
  72. // t_cloud->points[i].z -= t_center.z;
  73. }
  74. // // write_pointcloud(t_cloud, std::to_string(count)+"_ori_");
  75. // 构建最小二乘问题
  76. ceres::Problem problem;
  77. problem.AddResidualBlock( // 向问题中添加误差项
  78. // 使用自动求导,模板参数:误差类型,输出维度,输入维度,维数要与前面struct中一致
  79. new ceres::AutoDiffCostFunction<Car_pose_cost, ceres::DYNAMIC, 3>(
  80. new Car_pose_cost(t_cloud), t_cloud->size()),
  81. nullptr, // 核函数,这里不使用,为空
  82. t_vars // 待估计参数
  83. );
  84. // 配置求解器
  85. ceres::Solver::Options options; // 这里有很多配置项可以填
  86. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  87. options.minimizer_progress_to_stdout = false; // 输出到cout
  88. options.max_num_iterations = 100;
  89. ceres::Solver::Summary summary; // 优化信息
  90. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  91. ceres::Solve(options, &problem, &summary); // 开始优化
  92. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  93. std::chrono::duration<double> time_used = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  94. // std::cout << "solve time cost = " << time_used.count() << " seconds. " << std::endl;
  95. // 输出结果
  96. // std::cout << summary.BriefReport() << std::endl;
  97. // t_vars[3] -= 0.4;
  98. x = t_vars[0];
  99. y = t_vars[1];
  100. theta = t_vars[2];
  101. if(fabs(theta)>30*M_PI/180.0)
  102. {
  103. //std::cout << "wrong angle, detect failed" << theta*180.0/M_PI << std::endl;
  104. return false;
  105. }
  106. inv_trans_cloud(t_cloud, x, y, theta);
  107. // viewer.showCloud(cloud_ptr);
  108. // write_pointcloud(cloud_ptr, "uniform_");
  109. // //离群点过滤
  110. // pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  111. // sor.setInputCloud(t_cloud);
  112. // sor.setMeanK(15); //K近邻搜索点个数
  113. // sor.setStddevMulThresh(3.0); //标准差倍数
  114. // sor.setNegative(false); //保留未滤波点(内点)
  115. // sor.filter(*t_cloud); //保存滤波结果到cloud_filter
  116. // 判断x方向边界,若不关于中心对称则错误
  117. pcl::PointXYZ total_min_p, total_max_p;
  118. pcl::getMinMax3D(*t_cloud, total_min_p, total_max_p);
  119. double x_diff = fabs(total_max_p.x + total_min_p.x) / 2.0;
  120. if (x_diff > 2.0)
  121. {
  122. // std::cout << "left, right not mirroring----"<<x_diff << std::endl;
  123. }
  124. else
  125. {
  126. // std::cout << "x diff " << x_diff << std::endl;
  127. width = total_max_p.x - total_min_p.x;
  128. // 最大轮宽0.28再加上前轮极限旋转角35度
  129. double wheel_width = 0.28 * (1 + sin(35 * M_PI / 180.0));
  130. // std::cout << "car width: " << width << std::endl;
  131. // 切出底盘点,找最低即为z值
  132. pcl::PointCloud<pcl::PointXYZ>::Ptr inside_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
  133. pcl::PassThrough<pcl::PointXYZ> pass;
  134. pass.setInputCloud(t_cloud);
  135. pass.setFilterFieldName("x");
  136. pass.setFilterLimits(-width / 2.0 + wheel_width, width / 2.0 - wheel_width);
  137. pass.setFilterLimitsNegative(false);
  138. pass.filter(*inside_cloud);
  139. // 找最低为z值
  140. pcl::PointXYZ min_p, max_p;
  141. pcl::getMinMax3D(*inside_cloud, min_p, max_p);
  142. z_value = min_p.z-0.01;
  143. // 根据z值切原始点云
  144. pass.setInputCloud(t_cloud);
  145. pass.setFilterFieldName("z");
  146. pass.setFilterLimits(total_min_p.z, z_value);
  147. pass.setFilterLimitsNegative(false);
  148. pass.filter(*t_cloud);
  149. // std::cout << "\n--------------------------- chassis z0: " << min_p.z << std::endl;
  150. if (debug_cloud)
  151. {
  152. create_curve_cloud(t_cloud, t_vars[3]);
  153. for (size_t i = 0; i < 60; i++)
  154. {
  155. t_cloud->push_back(pcl::PointXYZ(-t_vars[3] / 2.0, -3.0 + i * 0.1, 0.0));
  156. t_cloud->push_back(pcl::PointXYZ(t_vars[3] / 2.0, -3.0 + i * 0.1, 0.0));
  157. t_cloud->push_back(pcl::PointXYZ(-width / 2.0, -3.0 + i * 0.1, 0.0));
  158. t_cloud->push_back(pcl::PointXYZ(width / 2.0, -3.0 + i * 0.1, 0.0));
  159. t_cloud->push_back(pcl::PointXYZ(-width / 2.0 + wheel_width, -3.0 + i * 0.1, 0.0));
  160. t_cloud->push_back(pcl::PointXYZ(width / 2.0 - wheel_width, -3.0 + i * 0.1, 0.0));
  161. }
  162. out_cloud_ptr->clear();
  163. out_cloud_ptr->operator+=(*t_cloud);
  164. }else
  165. {
  166. out_cloud_ptr->clear();
  167. out_cloud_ptr->operator+=(*t_cloud);
  168. }
  169. }
  170. x += t_center.x;
  171. y += t_center.y;
  172. // std::cout << "estimated x,y,theta = " << x << ", " << y << ", " << theta*180.0/M_PI << std::endl;
  173. // std::cout << "----------------------------------" << std::endl;
  174. return true;
  175. }