car_pose_detector.cpp 20 KB

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