car_pose_detector.cpp 21 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484
  1. /*
  2. * @Description:
  3. * @Author: yct
  4. * @Date: 2021-09-16 15:18:34
  5. * @LastEditTime: 2021-11-17 15:37:25
  6. * @LastEditors: yct
  7. */
  8. #include "car_pose_detector.h"
  9. // 变换点云, 反向平移后旋转
  10. void
  11. Car_pose_detector::inv_trans_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double x, double y, double theta) {
  12. for (int i = 0; i < cloud_ptr->size(); i++) {
  13. Eigen::Matrix<double, 2, 1> t_point(double(cloud_ptr->points[i].x) - x, double(cloud_ptr->points[i].y) - y);
  14. Eigen::Rotation2D<double> rotation(theta);
  15. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  16. Eigen::Matrix<double, 2, 1> trans_point = rotation_matrix * t_point;
  17. cloud_ptr->points[i].x = trans_point.x();
  18. cloud_ptr->points[i].y = trans_point.y();
  19. }
  20. }
  21. // 变换点云,旋转后平移
  22. void Car_pose_detector::trans_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double x, double y, double theta) {
  23. for (int i = 0; i < cloud_ptr->size(); i++) {
  24. Eigen::Matrix<double, 2, 1> t_point(double(cloud_ptr->points[i].x), double(cloud_ptr->points[i].y));
  25. Eigen::Rotation2D<double> rotation(theta);
  26. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  27. Eigen::Matrix<double, 2, 1> trans_point = rotation_matrix * t_point;
  28. cloud_ptr->points[i].x = trans_point.x() + x;
  29. cloud_ptr->points[i].y = trans_point.y() + y;
  30. }
  31. }
  32. // 创建两轴具体曲线
  33. void Car_pose_detector::create_curve_cloud(pcl::PointCloud<pcl::PointXYZ>::Ptr &cloud_ptr, double width) {
  34. for (double x = -2.5; x < 2.5; x += 0.02) {
  35. double left_value = 1.0 / (1.0 + exp(30 * (x + width / 2.0)));
  36. double right_value = 1.0 / (1.0 + exp(30 * (-x + width / 2.0)));
  37. double front_value = 1.0 / (1.0 + exp(15 * (x + 2.2)));
  38. double back_value = 1.0 / (1.0 + exp(15 * (-x + 2.2)));
  39. cloud_ptr->push_back(pcl::PointXYZ(x, std::max(left_value, right_value) - 3.0, 0.0));
  40. cloud_ptr->push_back(pcl::PointXYZ(std::max(front_value, back_value) - 2.0, x, 0.0));
  41. }
  42. }
  43. // 代价函数的计算模型
  44. struct Car_pose_cost {
  45. Car_pose_cost(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr) : m_cloud_ptr(cloud_ptr) {}
  46. // 残差的计算
  47. template<typename T>
  48. bool operator()(
  49. const T *const vars, // 模型参数,x y theta w
  50. T *residual) const {
  51. if (m_cloud_ptr == nullptr || m_cloud_ptr->size() <= 0) {
  52. std::cout << "error occured" << std::endl;
  53. return false;
  54. }
  55. const T norm_scale = T(0.002);
  56. //residual[0] = T(0);
  57. // residual[1] = T(0);
  58. // residual[m_cloud_ptr->size()] = T(0.0);
  59. // 点云loss
  60. const T width = T(2.0); //vars[3];
  61. char buf[40960] = {0};
  62. // sprintf(buf, "----");
  63. for (int i = 0; i < m_cloud_ptr->size(); i++) {
  64. Eigen::Matrix<T, 2, 1> t_point(T(m_cloud_ptr->points[i].x) - vars[0],
  65. T(m_cloud_ptr->points[i].y) - vars[1]);
  66. Eigen::Rotation2D<T> rotation(vars[2]);
  67. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  68. Eigen::Matrix<T, 2, 1> t_trans_point = rotation_matrix * t_point;
  69. T left_loss = T(1.0) / (T(1.0) + ceres::exp(T(30.0) * (t_trans_point.x() + width / T(2.0))));
  70. T right_loss = T(1.0) / (T(1.0) + ceres::exp(T(30.0) * (-t_trans_point.x() + width / T(2.0))));
  71. T front_loss = T(1.0) / (T(1.0) + ceres::exp(T(15.0) * (t_trans_point.y() + T(2.2))));
  72. T back_loss = T(1.0) / (T(1.0) + ceres::exp(T(15.0) * (-t_trans_point.y() + T(2.2))));
  73. residual[i] = left_loss + right_loss + front_loss +
  74. back_loss; // + norm_scale * ((left_loss - T(0.5)) + (right_loss - T(0.5)));
  75. // residual[m_cloud_ptr->size()] += (left_loss - T(0.5)) + (right_loss - T(0.5));
  76. // if(left_loss > T(0.01))
  77. // std::cout << "index l r: " << i << ", " << left_loss << ", " << right_loss << ", " << trans_point.x() << std::endl;
  78. // sprintf(buf + strlen(buf), "%.4f ", residual[i]);
  79. // if(i%20==8)
  80. // {
  81. // sprintf(buf + strlen(buf), "\n");
  82. // }
  83. }
  84. // printf(buf);
  85. // // 参数L2正则化loss
  86. // residual[m_cloud_ptr->size()] = T(m_cloud_ptr->size()) * width * norm_scale;
  87. // residual[1] += ceres::pow(vars[1],2) * norm_scale;
  88. // residual[1] += ceres::pow(vars[2],2) * norm_scale;
  89. // residual[1] += ceres::pow((vars[3]-T(1.8)),2) * norm_scale;
  90. // ((i != 3) ? norm_scale : norm_scale * T(m_cloud_ptr->size()));
  91. return true;
  92. }
  93. pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud_ptr; // x,y数据
  94. };
  95. // 公式转图片优化
  96. #include <ceres/cubic_interpolation.h>
  97. constexpr float kMinProbability = 0.01f;
  98. constexpr float kMaxProbability = 1.f - kMinProbability;
  99. constexpr float kMaxCorrespondenceCost = 1.f - kMinProbability;
  100. constexpr int kPadding = INT_MAX / 4;
  101. constexpr float resolutionx = 0.01f;
  102. constexpr float resolutiony = 0.01f;
  103. constexpr float min_x = -2.0f;
  104. constexpr float min_y = -3.0f;
  105. constexpr float max_x = 2.0f;
  106. constexpr float max_y = 3.0f;
  107. cv::Mat Car_pose_detector::m_model = Car_pose_detector::create_mat(min_x, max_x, min_y, max_y, resolutionx,
  108. resolutiony);
  109. class GridArrayAdapter {
  110. public:
  111. enum {
  112. DATA_DIMENSION = 1
  113. };
  114. explicit GridArrayAdapter(const cv::Mat &grid) : grid_(grid) {}
  115. void GetValue(const int row, const int column, double *const value) const {
  116. if (row < kPadding || column < kPadding || row >= NumRows() - kPadding ||
  117. column >= NumCols() - kPadding) {
  118. *value = kMaxCorrespondenceCost;
  119. } else {
  120. *value = static_cast<double>(grid_.at<float>(row - kPadding, column - kPadding));
  121. // if (row - kPadding > 100 && row - kPadding < 300 && column - kPadding > 50 && column - kPadding < 150)
  122. // printf("row:%d, col:%d, val%.3f\n", row-kPadding, column-kPadding, grid_.at<float>(row - kPadding, column - kPadding));
  123. }
  124. }
  125. int NumRows() const {
  126. return grid_.rows + 2 * kPadding;
  127. }
  128. int NumCols() const {
  129. return grid_.cols + 2 * kPadding;
  130. }
  131. private:
  132. const cv::Mat &grid_;
  133. };
  134. // 代价函数的计算模型
  135. struct Trans_mat_cost {
  136. Trans_mat_cost(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr, cv::Mat &mat) : m_cloud_ptr(cloud_ptr), m_mat(mat) {
  137. // cv::namedWindow("img", CV_WINDOW_FREERATIO);
  138. // cv::imshow("img", m_mat);
  139. // cv::waitKey();
  140. // debug_img(cloud_ptr, mat);
  141. }
  142. void debug_img(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr, cv::Mat &mat) {
  143. if (m_cloud_ptr == nullptr || m_cloud_ptr->empty()) {
  144. std::cout << "error occured" << std::endl;
  145. return;
  146. }
  147. cv::Mat img_show = mat.clone();//cv::Mat::zeros(mat.rows * 1, mat.cols * 1, CV_32FC1);
  148. const GridArrayAdapter adapter(mat);
  149. ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
  150. // 点云loss
  151. // char buf[150960]={0};
  152. // sprintf(buf, "----");
  153. for (int i = 0; i < m_cloud_ptr->size(); i++) {
  154. Eigen::Matrix<double, 2, 1> t_point(double(m_cloud_ptr->points[i].x), double(m_cloud_ptr->points[i].y));
  155. Eigen::Rotation2D<double> rotation(0);
  156. Eigen::Matrix<double, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  157. Eigen::Matrix<double, 2, 1> t_trans_point = rotation_matrix * t_point;
  158. int col_index = int((t_trans_point.x() - min_x) / resolutionx);
  159. int row_index = int((t_trans_point.y() - min_y) / resolutiony);
  160. double val = 0.0;
  161. interpolator.Evaluate(row_index + 0.5 + kPadding, col_index + 0.5 + kPadding, &val);
  162. cv::circle(img_show, cv::Point(col_index, row_index), 1, cv::Scalar(0.25), 1);
  163. // sprintf(buf + strlen(buf), "(%.2f,%.2f)---%.3f ", t_trans_point.x(), t_trans_point.y(), val);
  164. // if(i%15==8)
  165. // {
  166. // sprintf(buf + strlen(buf), "\n");
  167. // }
  168. }
  169. // printf(buf);
  170. // for (size_t i = -mat.rows; i < mat.rows*2; i++)
  171. // {
  172. // for (size_t j = -mat.cols; j < mat.cols*2; j++)
  173. // {
  174. // double val;
  175. // // adapter.GetValue(i + kPadding, j + kPadding, &val);
  176. // interpolator.Evaluate(i+kPadding, j+kPadding, &val);
  177. // img_show.at<float>(i, j) = val;
  178. // }
  179. // }
  180. // printf("r:%d c:%d\n", img_show.rows, img_show.cols);
  181. cv::namedWindow("img", cv::WINDOW_FREERATIO);
  182. // cv::imshow("origin", mat);
  183. cv::imshow("img", img_show);
  184. cv::waitKey();
  185. }
  186. // 残差的计算
  187. template<typename T>
  188. bool operator()(
  189. const T *const vars, // 模型参数,x y theta w
  190. T *residual) const {
  191. if (m_cloud_ptr == nullptr || m_cloud_ptr->size() <= 0) {
  192. std::cout << "error occured" << std::endl;
  193. return false;
  194. }
  195. const GridArrayAdapter adapter(m_mat);
  196. ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
  197. // 点云loss
  198. Eigen::Rotation2D<T> rotation(vars[2]);
  199. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  200. for (int i = 0; i < m_cloud_ptr->size(); i++) {
  201. Eigen::Matrix<T, 2, 1> t_point(T(m_cloud_ptr->points[i].x) - vars[0],
  202. T(m_cloud_ptr->points[i].y) - vars[1]);
  203. Eigen::Matrix<T, 2, 1> t_trans_point = rotation_matrix * t_point;
  204. T col_index = (t_trans_point.x() - T(min_x)) / T(resolutionx) + T(0.5 + kPadding);
  205. T row_index = (t_trans_point.y() - T(min_y)) / T(resolutiony) + T(0.5 + kPadding);
  206. interpolator.Evaluate(row_index, col_index, &residual[i]);
  207. }
  208. // // 参数L2正则化loss
  209. // residual[m_cloud_ptr->size()] = T(m_cloud_ptr->size()) * width * norm_scale;
  210. // residual[1] += ceres::pow(vars[1],2) * norm_scale;
  211. // residual[1] += ceres::pow(vars[2],2) * norm_scale;
  212. // residual[1] += ceres::pow((vars[3]-T(1.8)),2) * norm_scale;
  213. // ((i != 3) ? norm_scale : norm_scale * T(m_cloud_ptr->size()));
  214. return true;
  215. }
  216. pcl::PointCloud<pcl::PointXYZ>::Ptr m_cloud_ptr; // x,y数据
  217. cv::Mat m_mat;
  218. };
  219. // 生成优化图像,降低优化耗时
  220. cv::Mat Car_pose_detector::create_mat(double min_x, double max_x, double min_y, double max_y, double resolution_x,
  221. double resolution_y) {
  222. if (max_x < min_x || max_y < min_y || resolution_x <= 0 || resolution_y <= 0) {
  223. return cv::Mat();
  224. }
  225. int cols = (max_x - min_x) / resolution_x + 1;
  226. int rows = (max_y - min_y) / resolution_y + 1;
  227. if (rows <= 1 || cols <= 1) {
  228. return cv::Mat();
  229. }
  230. cv::Mat t_mat(rows, cols, CV_32FC1);
  231. for (size_t i = 0; i < rows; i++) {
  232. for (size_t j = 0; j < cols; j++) {
  233. double x = j * resolution_x + min_x;
  234. double y = i * resolution_y + min_y;
  235. double left_value = 1.0 / (1.0 + exp(30 * (x + 1.0)));
  236. double right_value = 1.0 / (1.0 + exp(30 * (-x + 1.0)));
  237. double front_value = 1.0 / (1.0 + exp(15 * (y + 2.2)));
  238. double back_value = 1.0 / (1.0 + exp(15 * (-y + 2.2)));
  239. t_mat.at<float>(i, j) = float((left_value + right_value + front_value + back_value) / 1.0f);
  240. }
  241. }
  242. // std::cout << "r,c " << t_mat.rows << ", " << t_mat.cols << std::endl;
  243. // cv::imshow("img", t_mat);
  244. // cv::waitKey();
  245. return t_mat;
  246. }
  247. #include "tool/static_tool.hpp"
  248. // 检测底盘z方向值,去中心,使用mat加速
  249. bool Car_pose_detector::detect_pose_mat(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr,
  250. pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud, double &x, double &y,
  251. double &theta, bool debug_cloud) {
  252. //离群点过滤
  253. pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  254. sor.setInputCloud(cloud_ptr);
  255. sor.setMeanK(50); //K近邻搜索点个数
  256. sor.setStddevMulThresh(0.7); //标准差倍数
  257. sor.setNegative(false); //保留未滤波点(内点)
  258. sor.filter(*out_cloud); //保存滤波结果到cloud_filter
  259. pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud_ptr(new pcl::PointCloud<pcl::PointXYZ>);
  260. out_cloud_ptr->operator+=(*out_cloud);
  261. double t_vars[4] = {0, 0, 0, 1.9};
  262. // 去中心化
  263. pcl::PointXYZ t_center(0, 0, 0);
  264. for (size_t i = 0; i < out_cloud_ptr->size(); i++) {
  265. t_center.x += out_cloud_ptr->points[i].x;
  266. t_center.y += out_cloud_ptr->points[i].y;
  267. }
  268. t_center.x /= out_cloud_ptr->size();
  269. t_center.y /= out_cloud_ptr->size();
  270. for (size_t i = 0; i < out_cloud_ptr->size(); i++) {
  271. out_cloud_ptr->points[i].x -= t_center.x;
  272. out_cloud_ptr->points[i].y -= t_center.y;
  273. }
  274. // // write_pointcloud(t_cloud, std::to_string(count)+"_ori_");
  275. // 构建最小二乘问题
  276. ceres::Problem problem;
  277. Trans_mat_cost *tp_trans_mat_cost = new Trans_mat_cost(out_cloud_ptr, m_model);
  278. // tp_trans_mat_cost->debug_img(t_cloud, m_model);
  279. problem.AddResidualBlock( // 向问题中添加误差项
  280. // 使用自动求导,模板参数:误差类型,输出维度,输入维度,维数要与前面struct中一致
  281. new ceres::AutoDiffCostFunction<Trans_mat_cost, ceres::DYNAMIC, 3>(
  282. tp_trans_mat_cost, out_cloud_ptr->size()),
  283. new ceres::HuberLoss(1.0), // 核函数,这里不使用,为空
  284. t_vars // 待估计参数
  285. );
  286. // 配置求解器
  287. ceres::Solver::Options options; // 这里有很多配置项可以填
  288. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  289. options.minimizer_progress_to_stdout = false; // 输出到cout
  290. options.max_num_iterations = 100;
  291. ceres::Solver::Summary summary; // 优化信息
  292. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  293. ceres::Solve(options, &problem, &summary); // 开始优化
  294. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  295. std::chrono::duration<double> time_used = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  296. // std::cout << "solve time cost = " << time_used.count() << " seconds. " << std::endl;
  297. // 输出结果
  298. // std::cout << summary.BriefReport() << std::endl;
  299. // t_vars[3] -= 0.4;
  300. // 保存结果,将去除的中心补上
  301. x = t_vars[0] + t_center.x;
  302. y = t_vars[1] + t_center.y;
  303. theta = t_vars[2];
  304. // printf("x:%.3f y:%.3f th:%.3f\n", x, y, theta);
  305. if (fabs(theta) > 10 * M_PI / 180.0) {
  306. //std::cout << "wrong angle, detect failed" << theta*180.0/M_PI << std::endl;
  307. return false;
  308. }
  309. return true;
  310. }
  311. // 检测底盘z方向值,原始点云去中心,并切除底盘z以上部分
  312. bool Car_pose_detector::detect_pose(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ptr,
  313. pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud_ptr, double &x, double &y,
  314. double &theta, double &width, double &z_value, bool debug_cloud) {
  315. pcl::PointCloud<pcl::PointXYZ>::Ptr t_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(
  316. new pcl::PointCloud<pcl::PointXYZ>);
  317. t_cloud->operator+=(*cloud_ptr);
  318. double t_vars[4] = {0, 0, 0, 1.9};
  319. // 去中心化
  320. pcl::PointXYZ t_center(0, 0, 0);
  321. for (size_t i = 0; i < t_cloud->size(); i++) {
  322. // t_cloud->points[i].x /= 1000.0;
  323. // t_cloud->points[i].y /= 1000.0;
  324. // t_cloud->points[i].z /= 1000.0;
  325. t_center.x += t_cloud->points[i].x;
  326. t_center.y += t_cloud->points[i].y;
  327. // t_center.z += t_cloud->points[i].z;
  328. }
  329. t_center.x /= t_cloud->size();
  330. t_center.y /= t_cloud->size();
  331. // t_center.z /= t_cloud->size();
  332. for (size_t i = 0; i < t_cloud->size(); i++) {
  333. t_cloud->points[i].x -= t_center.x;
  334. t_cloud->points[i].y -= t_center.y;
  335. // t_cloud->points[i].z -= t_center.z;
  336. }
  337. // // write_pointcloud(t_cloud, std::to_string(count)+"_ori_");
  338. // 构建最小二乘问题
  339. ceres::Problem problem;
  340. problem.AddResidualBlock( // 向问题中添加误差项
  341. // 使用自动求导,模板参数:误差类型,输出维度,输入维度,维数要与前面struct中一致
  342. new ceres::AutoDiffCostFunction<Car_pose_cost, ceres::DYNAMIC, 3>(
  343. new Car_pose_cost(t_cloud), t_cloud->size()),
  344. new ceres::HuberLoss(1.0), // 核函数,这里不使用,为空
  345. t_vars // 待估计参数
  346. );
  347. // 配置求解器
  348. ceres::Solver::Options options; // 这里有很多配置项可以填
  349. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  350. options.minimizer_progress_to_stdout = false; // 输出到cout
  351. options.max_num_iterations = 100;
  352. ceres::Solver::Summary summary; // 优化信息
  353. std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now();
  354. ceres::Solve(options, &problem, &summary); // 开始优化
  355. std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now();
  356. std::chrono::duration<double> time_used = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1);
  357. std::cout << "solve time cost = " << time_used.count() << " seconds. " << std::endl;
  358. // 输出结果
  359. // std::cout << summary.BriefReport() << std::endl;
  360. // t_vars[3] -= 0.4;
  361. // 保存结果,将去除的中心补上
  362. x = t_vars[0] + t_center.x;
  363. y = t_vars[1] + t_center.y;
  364. theta = t_vars[2];
  365. // printf("x:%.3f y:%.3f th:%.3f\n", x, y, theta);
  366. if (fabs(theta) > 10 * M_PI / 180.0) {
  367. //std::cout << "wrong angle, detect failed" << theta*180.0/M_PI << std::endl;
  368. return false;
  369. }
  370. inv_trans_cloud(t_cloud, x, y, theta);
  371. // viewer.showCloud(cloud_ptr);
  372. // write_pointcloud(cloud_ptr, "uniform_");
  373. // //离群点过滤
  374. // pcl::StatisticalOutlierRemoval<pcl::PointXYZ> sor;
  375. // sor.setInputCloud(t_cloud);
  376. // sor.setMeanK(15); //K近邻搜索点个数
  377. // sor.setStddevMulThresh(3.0); //标准差倍数
  378. // sor.setNegative(false); //保留未滤波点(内点)
  379. // sor.filter(*t_cloud); //保存滤波结果到cloud_filter
  380. // 判断x方向边界,若不关于中心对称则错误
  381. pcl::PointXYZ total_min_p, total_max_p;
  382. pcl::getMinMax3D(*t_cloud, total_min_p, total_max_p);
  383. double x_diff = fabs(total_max_p.x + total_min_p.x) / 2.0;
  384. if (x_diff > 2.0) {
  385. // std::cout << "left, right not mirroring----"<<x_diff << std::endl;
  386. } else {
  387. // std::cout << "x diff " << x_diff << std::endl;
  388. width = total_max_p.x - total_min_p.x;
  389. // 最大轮宽0.28再加上前轮极限旋转角35度
  390. double wheel_width = 0.28 * (1 + sin(35 * M_PI / 180.0));
  391. // std::cout << "car width: " << width << std::endl;
  392. // 切出底盘点,找最低即为z值
  393. pcl::PointCloud<pcl::PointXYZ>::Ptr inside_cloud = pcl::PointCloud<pcl::PointXYZ>::Ptr(
  394. new pcl::PointCloud<pcl::PointXYZ>);
  395. pcl::PassThrough<pcl::PointXYZ> pass;
  396. pass.setInputCloud(t_cloud);
  397. pass.setFilterFieldName("x");
  398. pass.setFilterLimits(-width / 2.0 + wheel_width, width / 2.0 - wheel_width);
  399. #if PCL_MINOR_VERSION == 10
  400. pass.setFilterLimitsNegative(false); //保留(true就是删除,false就是保留而删除此区间外的)
  401. #endif
  402. pass.filter(*inside_cloud);
  403. // 找最低为z值
  404. pcl::PointXYZ min_p, max_p;
  405. pcl::getMinMax3D(*inside_cloud, min_p, max_p);
  406. z_value = min_p.z - 0.01;
  407. // 根据z值切原始点云
  408. pass.setInputCloud(t_cloud);
  409. pass.setFilterFieldName("z");
  410. pass.setFilterLimits(total_min_p.z, z_value);
  411. #if PCL_MINOR_VERSION == 10
  412. pass.setFilterLimitsNegative(false); //保留(true就是删除,false就是保留而删除此区间外的)
  413. #endif
  414. pass.filter(*t_cloud);
  415. // std::cout << "\n--------------------------- chassis z0: " << min_p.z << std::endl;
  416. if (debug_cloud) {
  417. create_curve_cloud(t_cloud, t_vars[3]);
  418. for (size_t i = 0; i < 60; i++) {
  419. t_cloud->push_back(pcl::PointXYZ(-t_vars[3] / 2.0, -3.0 + i * 0.1, 0.0));
  420. t_cloud->push_back(pcl::PointXYZ(t_vars[3] / 2.0, -3.0 + i * 0.1, 0.0));
  421. t_cloud->push_back(pcl::PointXYZ(-width / 2.0, -3.0 + i * 0.1, 0.0));
  422. t_cloud->push_back(pcl::PointXYZ(width / 2.0, -3.0 + i * 0.1, 0.0));
  423. t_cloud->push_back(pcl::PointXYZ(-width / 2.0 + wheel_width, -3.0 + i * 0.1, 0.0));
  424. t_cloud->push_back(pcl::PointXYZ(width / 2.0 - wheel_width, -3.0 + i * 0.1, 0.0));
  425. }
  426. out_cloud_ptr->clear();
  427. out_cloud_ptr->operator+=(*t_cloud);
  428. } else {
  429. out_cloud_ptr->clear();
  430. out_cloud_ptr->operator+=(*t_cloud);
  431. }
  432. }
  433. // std::cout << "estimated x,y,theta = " << x << ", " << y << ", " << theta*180.0/M_PI << std::endl;
  434. // std::cout << "----------------------------------" << std::endl;
  435. return true;
  436. }