floor_detection_nodelet.cpp 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269
  1. // SPDX-License-Identifier: BSD-2-Clause
  2. #include <memory>
  3. #include <iostream>
  4. #include <boost/optional.hpp>
  5. #include <ros/ros.h>
  6. #include <ros/time.h>
  7. #include <pcl_ros/point_cloud.h>
  8. #include <std_msgs/Time.h>
  9. #include <sensor_msgs/PointCloud2.h>
  10. #include <hdl_graph_slam/FloorCoeffs.h>
  11. #include <nodelet/nodelet.h>
  12. #include <pluginlib/class_list_macros.h>
  13. #include <pcl/common/transforms.h>
  14. #include <pcl/features/normal_3d.h>
  15. #include <pcl/search/impl/search.hpp>
  16. #include <pcl/filters/impl/plane_clipper3D.hpp>
  17. #include <pcl/filters/extract_indices.h>
  18. #include <pcl/sample_consensus/ransac.h>
  19. #include <pcl/sample_consensus/sac_model_plane.h>
  20. namespace hdl_graph_slam {
  21. class FloorDetectionNodelet : public nodelet::Nodelet {
  22. public:
  23. typedef pcl::PointXYZI PointT;
  24. EIGEN_MAKE_ALIGNED_OPERATOR_NEW
  25. FloorDetectionNodelet() {}
  26. virtual ~FloorDetectionNodelet() {}
  27. virtual void onInit() {
  28. NODELET_DEBUG("initializing floor_detection_nodelet...");
  29. nh = getNodeHandle();
  30. private_nh = getPrivateNodeHandle();
  31. initialize_params();
  32. points_sub = nh.subscribe("/filtered_points", 256, &FloorDetectionNodelet::cloud_callback, this);
  33. floor_pub = nh.advertise<hdl_graph_slam::FloorCoeffs>("/floor_detection/floor_coeffs", 32);
  34. read_until_pub = nh.advertise<std_msgs::Header>("/floor_detection/read_until", 32);
  35. floor_filtered_pub = nh.advertise<sensor_msgs::PointCloud2>("/floor_detection/floor_filtered_points", 32);
  36. floor_points_pub = nh.advertise<sensor_msgs::PointCloud2>("/floor_detection/floor_points", 32);
  37. }
  38. private:
  39. /**
  40. * @brief initialize parameters
  41. */
  42. void initialize_params() {
  43. tilt_deg = private_nh.param<double>("tilt_deg", 0.0); // approximate sensor tilt angle [deg]
  44. sensor_height = private_nh.param<double>("sensor_height", 2.0); // approximate sensor height [m]
  45. height_clip_range = private_nh.param<double>("height_clip_range", 1.0); // points with heights in [sensor_height - height_clip_range, sensor_height + height_clip_range] will be used for floor detection
  46. floor_pts_thresh = private_nh.param<int>("floor_pts_thresh", 512); // minimum number of support points of RANSAC to accept a detected floor plane
  47. floor_normal_thresh = private_nh.param<double>("floor_normal_thresh", 10.0); // verticality check thresold for the detected floor plane [deg]
  48. use_normal_filtering = private_nh.param<bool>("use_normal_filtering", true); // if true, points with "non-"vertical normals will be filtered before RANSAC
  49. normal_filter_thresh = private_nh.param<double>("normal_filter_thresh", 20.0); // "non-"verticality check threshold [deg]
  50. points_topic = private_nh.param<std::string>("points_topic", "/velodyne_points");
  51. }
  52. /**
  53. * @brief callback for point clouds
  54. * @param cloud_msg point cloud msg
  55. */
  56. void cloud_callback(const sensor_msgs::PointCloud2ConstPtr& cloud_msg) { // 处理点云数据的回调函数
  57. pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
  58. pcl::fromROSMsg(*cloud_msg, *cloud);
  59. if(cloud->empty()) {
  60. return;
  61. }
  62. // floor detection
  63. boost::optional<Eigen::Vector4f> floor = detect(cloud);
  64. // publish the detected floor coefficients
  65. hdl_graph_slam::FloorCoeffs coeffs;
  66. coeffs.header = cloud_msg->header;
  67. if(floor) {
  68. coeffs.coeffs.resize(4);
  69. for(int i = 0; i < 4; i++) {
  70. coeffs.coeffs[i] = (*floor)[i];
  71. }
  72. }
  73. floor_pub.publish(coeffs);
  74. // for offline estimation
  75. std_msgs::HeaderPtr read_until(new std_msgs::Header());
  76. read_until->frame_id = points_topic;
  77. read_until->stamp = cloud_msg->header.stamp + ros::Duration(1, 0);
  78. read_until_pub.publish(read_until);
  79. read_until->frame_id = "/filtered_points";
  80. read_until_pub.publish(read_until);
  81. }
  82. /**
  83. * @brief detect the floor plane from a point cloud
  84. * @param cloud input cloud
  85. * @return detected floor plane coefficients
  86. */
  87. boost::optional<Eigen::Vector4f> detect(const pcl::PointCloud<PointT>::Ptr& cloud) const { // 主要的检测函数,用 RANSAC 算法你和一个平面,并进行垂直性检查
  88. // compensate the tilt rotation
  89. Eigen::Matrix4f tilt_matrix = Eigen::Matrix4f::Identity();
  90. tilt_matrix.topLeftCorner(3, 3) = Eigen::AngleAxisf(tilt_deg * M_PI / 180.0f, Eigen::Vector3f::UnitY()).toRotationMatrix();
  91. // filtering before RANSAC (height and normal filtering)
  92. pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>);
  93. pcl::transformPointCloud(*cloud, *filtered, tilt_matrix);
  94. filtered = plane_clip(filtered, Eigen::Vector4f(0.0f, 0.0f, 1.0f, sensor_height + height_clip_range), false);
  95. filtered = plane_clip(filtered, Eigen::Vector4f(0.0f, 0.0f, 1.0f, sensor_height - height_clip_range), true);
  96. if(use_normal_filtering) {
  97. filtered = normal_filtering(filtered);
  98. }
  99. pcl::transformPointCloud(*filtered, *filtered, static_cast<Eigen::Matrix4f>(tilt_matrix.inverse()));
  100. if(floor_filtered_pub.getNumSubscribers()) {
  101. filtered->header = cloud->header;
  102. floor_filtered_pub.publish(*filtered);
  103. }
  104. // too few points for RANSAC
  105. if(filtered->size() < floor_pts_thresh) {
  106. return boost::none;
  107. }
  108. // RANSAC
  109. pcl::SampleConsensusModelPlane<PointT>::Ptr model_p(new pcl::SampleConsensusModelPlane<PointT>(filtered));
  110. pcl::RandomSampleConsensus<PointT> ransac(model_p);
  111. ransac.setDistanceThreshold(0.1);
  112. ransac.computeModel();
  113. pcl::PointIndices::Ptr inliers(new pcl::PointIndices);
  114. ransac.getInliers(inliers->indices);
  115. // too few inliers
  116. if(inliers->indices.size() < floor_pts_thresh) {
  117. return boost::none;
  118. }
  119. // verticality check of the detected floor's normal
  120. Eigen::Vector4f reference = tilt_matrix.inverse() * Eigen::Vector4f::UnitZ();
  121. Eigen::VectorXf coeffs;
  122. ransac.getModelCoefficients(coeffs);
  123. double dot = coeffs.head<3>().dot(reference.head<3>());
  124. if(std::abs(dot) < std::cos(floor_normal_thresh * M_PI / 180.0)) {
  125. // the normal is not vertical
  126. return boost::none;
  127. }
  128. // make the normal upward
  129. if(coeffs.head<3>().dot(Eigen::Vector3f::UnitZ()) < 0.0f) {
  130. coeffs *= -1.0f;
  131. }
  132. if(floor_points_pub.getNumSubscribers()) {
  133. pcl::PointCloud<PointT>::Ptr inlier_cloud(new pcl::PointCloud<PointT>);
  134. pcl::ExtractIndices<PointT> extract;
  135. extract.setInputCloud(filtered);
  136. extract.setIndices(inliers);
  137. extract.filter(*inlier_cloud);
  138. inlier_cloud->header = cloud->header;
  139. floor_points_pub.publish(*inlier_cloud);
  140. }
  141. return Eigen::Vector4f(coeffs);
  142. }
  143. /**
  144. * @brief plane_clip
  145. * @param src_cloud
  146. * @param plane
  147. * @param negative
  148. * @return
  149. */
  150. pcl::PointCloud<PointT>::Ptr plane_clip(const pcl::PointCloud<PointT>::Ptr& src_cloud, const Eigen::Vector4f& plane, bool negative) const {
  151. pcl::PlaneClipper3D<PointT> clipper(plane);
  152. pcl::PointIndices::Ptr indices(new pcl::PointIndices);
  153. clipper.clipPointCloud3D(*src_cloud, indices->indices);
  154. pcl::PointCloud<PointT>::Ptr dst_cloud(new pcl::PointCloud<PointT>);
  155. pcl::ExtractIndices<PointT> extract;
  156. extract.setInputCloud(src_cloud);
  157. extract.setIndices(indices);
  158. extract.setNegative(negative);
  159. extract.filter(*dst_cloud);
  160. return dst_cloud;
  161. }
  162. /**
  163. * @brief filter points with non-vertical normals
  164. * @param cloud input cloud
  165. * @return filtered cloud
  166. */
  167. pcl::PointCloud<PointT>::Ptr normal_filtering(const pcl::PointCloud<PointT>::Ptr& cloud) const {
  168. pcl::NormalEstimation<PointT, pcl::Normal> ne;
  169. ne.setInputCloud(cloud);
  170. pcl::search::KdTree<PointT>::Ptr tree(new pcl::search::KdTree<PointT>);
  171. ne.setSearchMethod(tree);
  172. pcl::PointCloud<pcl::Normal>::Ptr normals(new pcl::PointCloud<pcl::Normal>);
  173. ne.setKSearch(10);
  174. ne.setViewPoint(0.0f, 0.0f, sensor_height);
  175. ne.compute(*normals);
  176. pcl::PointCloud<PointT>::Ptr filtered(new pcl::PointCloud<PointT>);
  177. filtered->reserve(cloud->size());
  178. for(int i = 0; i < cloud->size(); i++) {
  179. float dot = normals->at(i).getNormalVector3fMap().normalized().dot(Eigen::Vector3f::UnitZ());
  180. if(std::abs(dot) > std::cos(normal_filter_thresh * M_PI / 180.0)) {
  181. filtered->push_back(cloud->at(i));
  182. }
  183. }
  184. filtered->width = filtered->size();
  185. filtered->height = 1;
  186. filtered->is_dense = false;
  187. return filtered;
  188. }
  189. private:
  190. ros::NodeHandle nh;
  191. ros::NodeHandle private_nh;
  192. // ROS topics
  193. ros::Subscriber points_sub;
  194. ros::Publisher floor_pub;
  195. ros::Publisher floor_points_pub;
  196. ros::Publisher floor_filtered_pub;
  197. std::string points_topic;
  198. ros::Publisher read_until_pub;
  199. // floor detection parameters
  200. // see initialize_params() for the details
  201. double tilt_deg;
  202. double sensor_height;
  203. double height_clip_range;
  204. int floor_pts_thresh;
  205. double floor_normal_thresh;
  206. bool use_normal_filtering;
  207. double normal_filter_thresh;
  208. };
  209. } // namespace hdl_graph_slam
  210. PLUGINLIB_EXPORT_CLASS(hdl_graph_slam::FloorDetectionNodelet, nodelet::Nodelet)