00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #define BOOST_PARAMETER_MAX_ARITY 7
00035 #include "jsk_pcl_ros/hinted_plane_detector.h"
00036 #include "pcl_ros/transforms.h"
00037 #include <visualization_msgs/Marker.h>
00038 #include <pcl/surface/concave_hull.h>
00039 #include <pcl/sample_consensus/method_types.h>
00040 #include <pcl/sample_consensus/model_types.h>
00041 #include <pcl/segmentation/sac_segmentation.h>
00042 #include <pcl/filters/project_inliers.h>
00043 #include <pcl/filters/extract_indices.h>
00044 #include <pcl/ModelCoefficients.h>
00045 #include <pcl/kdtree/kdtree.h>
00046 #include <pcl/segmentation/extract_clusters.h>
00047 #include <pcl/common/centroid.h>
00048 #include <pluginlib/class_list_macros.h>
00049
00050 namespace jsk_pcl_ros {
00051
00052 void HintedPlaneDetector::onInit() {
00053 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
00054 DiagnosticNodelet::onInit();
00055 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00056 typename dynamic_reconfigure::Server<Config>::CallbackType f =
00057 boost::bind (&HintedPlaneDetector::configCallback, this, _1, _2);
00058 srv_->setCallback (f);
00059
00060 pub_hint_polygon_ = advertise<geometry_msgs::PolygonStamped>(
00061 *pnh_, "output/hint/polygon", 1);
00062 pub_hint_polygon_array_ = advertise<jsk_recognition_msgs::PolygonArray>(
00063 *pnh_, "output/hint/polygon_array", 1);
00064 pub_hint_inliers_ = advertise<PCLIndicesMsg>(
00065 *pnh_, "output/hint/inliers", 1);
00066 pub_hint_coefficients_ = advertise<PCLModelCoefficientMsg>(
00067 *pnh_, "output/hint/coefficients", 1);
00068 pub_polygon_ = advertise<geometry_msgs::PolygonStamped>(
00069 *pnh_, "output/polygon", 1);
00070 pub_polygon_array_ = advertise<jsk_recognition_msgs::PolygonArray>(
00071 *pnh_, "output/polygon_array", 1);
00072 pub_hint_filtered_indices_ = advertise<PCLIndicesMsg>(
00073 *pnh_, "output/hint_filtered_indices", 1);
00074 pub_plane_filtered_indices_ = advertise<PCLIndicesMsg>(
00075 *pnh_, "output/plane_filtered_indices", 1);
00076 pub_density_filtered_indices_ = advertise<PCLIndicesMsg>(
00077 *pnh_, "output/density_filtered_indices", 1);
00078 pub_euclidean_filtered_indices_ = advertise<PCLIndicesMsg>(
00079 *pnh_, "output/euclidean_filtered_indices", 1);
00080 pub_inliers_ = advertise<PCLIndicesMsg>(
00081 *pnh_, "output/inliers", 1);
00082 pub_coefficients_ = advertise<PCLModelCoefficientMsg>(
00083 *pnh_, "output/coefficients", 1);
00084 }
00085
00086 void HintedPlaneDetector::subscribe()
00087 {
00088 sub_cloud_.subscribe(*pnh_, "input", 1);
00089 sub_hint_cloud_.subscribe(*pnh_, "input/hint/cloud", 1);
00090 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00091 sync_->connectInput(sub_cloud_, sub_hint_cloud_);
00092 sync_->registerCallback(boost::bind(&HintedPlaneDetector::detect,
00093 this, _1, _2));
00094 }
00095
00096 void HintedPlaneDetector::unsubscribe()
00097 {
00098 sub_cloud_.unsubscribe();
00099 sub_hint_cloud_.unsubscribe();
00100 }
00101
00102 void HintedPlaneDetector::configCallback(
00103 Config &config, uint32_t level)
00104 {
00105 boost::mutex::scoped_lock lock(mutex_);
00106 hint_outlier_threashold_ = config.hint_outlier_threashold;
00107 hint_max_iteration_ = config.hint_max_iteration;
00108 hint_min_size_ = config.hint_min_size;
00109 outlier_threashold_ = config.outlier_threashold;
00110 max_iteration_ = config.max_iteration;
00111 min_size_ = config.min_size;
00112 eps_angle_ = config.eps_angle;
00113 normal_filter_eps_angle_ = config.normal_filter_eps_angle;
00114 euclidean_clustering_filter_tolerance_ = config.euclidean_clustering_filter_tolerance;
00115 euclidean_clustering_filter_min_size_ = config.euclidean_clustering_filter_min_size;
00116 density_radius_ = config.density_radius;
00117 density_num_ = config.density_num;
00118 enable_euclidean_filtering_ = config.enable_euclidean_filtering;
00119 enable_normal_filtering_ = config.enable_normal_filtering;
00120 enable_distance_filtering_ = config.enable_distance_filtering;
00121 enable_density_filtering_ = config.enable_density_filtering;
00122 }
00123
00124 void HintedPlaneDetector::detect(
00125 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00126 const sensor_msgs::PointCloud2::ConstPtr& hint_cloud_msg)
00127 {
00128 vital_checker_->poke();
00129 boost::mutex::scoped_lock lock(mutex_);
00130 pcl::PointCloud<pcl::PointNormal>::Ptr
00131 input_cloud (new pcl::PointCloud<pcl::PointNormal>);
00132 pcl::PointCloud<pcl::PointXYZ>::Ptr
00133 hint_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00134 pcl::fromROSMsg(*cloud_msg, *input_cloud);
00135 pcl::fromROSMsg(*hint_cloud_msg, *hint_cloud);
00136
00137
00138
00139 ConvexPolygon::Ptr convex;
00140
00141 if (detectHintPlane(hint_cloud, convex) && convex) {
00142 if (detectLargerPlane(input_cloud, convex)) {
00143 JSK_NODELET_INFO("success to detect!");
00144 }
00145 else {
00146 JSK_NODELET_ERROR("failed to detect larger plane");
00147 }
00148 }
00149 }
00150
00151 pcl::PointIndices::Ptr HintedPlaneDetector::getBestCluster(
00152 pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
00153 const std::vector<pcl::PointIndices>& cluster_indices,
00154 const ConvexPolygon::Ptr hint_convex)
00155 {
00156 Eigen::Vector3f center = hint_convex->centroid();
00157 double min_dist = DBL_MAX;
00158 size_t min_index = 0;
00159 for (size_t i = 0; i < cluster_indices.size(); i++) {
00160 Eigen::Vector4f center_cluster4;
00161 pcl::compute3DCentroid<pcl::PointNormal>(*input_cloud,
00162 cluster_indices[i].indices,
00163 center_cluster4);
00164 Eigen::Vector3f center_cluster3(center_cluster4[0], center_cluster4[1], center_cluster4[2]);
00165 double dist = (center - center_cluster3).norm();
00166 if (dist < min_dist) {
00167 min_dist = dist;
00168 min_index = i;
00169 }
00170 }
00171 pcl::PointIndices::Ptr ret (new pcl::PointIndices);
00172 ret->indices = cluster_indices[min_index].indices;
00173 return ret;
00174 }
00175
00176 void HintedPlaneDetector::densityFilter(
00177 const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00178 const pcl::PointIndices::Ptr indices,
00179 pcl::PointIndices& output)
00180 {
00181 if (enable_density_filtering_) {
00182 pcl::KdTreeFLANN<pcl::PointNormal> kdtree;
00183 pcl::KdTreeFLANN<pcl::PointNormal>::IndicesPtr indices_ptr
00184 (new std::vector<int>);
00185 *indices_ptr = indices->indices;
00186 kdtree.setInputCloud(cloud, indices_ptr);
00187 for (size_t i = 0; i < indices->indices.size(); i++) {
00188 int point_index = indices->indices[i];
00189 std::vector<int> result_indices;
00190 std::vector<float> result_distances;
00191 kdtree.radiusSearch(i, density_radius_,
00192 result_indices, result_distances);
00193 if (result_distances.size() >= density_num_) {
00194 output.indices.push_back(point_index);
00195 }
00196 }
00197 }
00198 else {
00199 output = *indices;
00200 }
00201 output.header = cloud->header;
00202 PCLIndicesMsg ros_indices;
00203 pcl_conversions::fromPCL(output, ros_indices);
00204 pub_density_filtered_indices_.publish(ros_indices);
00205 }
00206
00207 void HintedPlaneDetector::euclideanFilter(
00208 const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00209 const pcl::PointIndices::Ptr indices,
00210 const ConvexPolygon::Ptr hint_convex,
00211 pcl::PointIndices& output)
00212 {
00213 if (enable_density_filtering_) {
00214 pcl::EuclideanClusterExtraction<pcl::PointNormal> ec;
00215 ec.setClusterTolerance(euclidean_clustering_filter_tolerance_);
00216 pcl::search::KdTree<pcl::PointNormal>::Ptr tree
00217 (new pcl::search::KdTree<pcl::PointNormal>);
00218 tree->setInputCloud(cloud);
00219 ec.setSearchMethod(tree);
00220 ec.setIndices(indices);
00221 ec.setInputCloud(cloud);
00222
00223 std::vector<pcl::PointIndices> cluster_indices;
00224 ec.extract(cluster_indices);
00225 if (cluster_indices.size() == 0) {
00226 return;
00227 }
00228 JSK_NODELET_INFO("%lu clusters", cluster_indices.size());
00229 pcl::PointIndices::Ptr filtered_indices
00230 = getBestCluster(cloud, cluster_indices, hint_convex);
00231 output = *filtered_indices;
00232 }
00233 else {
00234 output = *indices;
00235 }
00236 output.header = cloud->header;
00237 PCLIndicesMsg ros_indices;
00238 pcl_conversions::fromPCL(output, ros_indices);
00239 pub_euclidean_filtered_indices_.publish(ros_indices);
00240 }
00241
00242 void HintedPlaneDetector::hintFilter(
00243 const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00244 const ConvexPolygon::Ptr hint_convex,
00245 pcl::PointIndices& output)
00246 {
00247 for (size_t i = 0; i < cloud->points.size(); i++) {
00248 pcl::PointNormal p = cloud->points[i];
00249 if (!isnan(p.x) && !isnan(p.y) && !isnan(p.y)) {
00250 Eigen::Vector4f v = p.getVector4fMap();
00251 if (!enable_distance_filtering_ || hint_convex->distanceToPoint(v) < outlier_threashold_) {
00252 Eigen::Vector3f n(p.normal_x, p.normal_y, p.normal_z);
00253 if (!enable_normal_filtering_ || hint_convex->angle(n) < normal_filter_eps_angle_) {
00254 output.indices.push_back(i);
00255 }
00256 }
00257 }
00258 }
00259 output.header = cloud->header;
00260 PCLIndicesMsg ros_candidate_inliers;
00261 pcl_conversions::fromPCL(output, ros_candidate_inliers);
00262 pub_hint_filtered_indices_.publish(ros_candidate_inliers);
00263 }
00264
00265 void HintedPlaneDetector::planeFilter(
00266 const pcl::PointCloud<pcl::PointNormal>::Ptr cloud,
00267 const pcl::PointIndices::Ptr indices,
00268 const Eigen::Vector3f& normal,
00269 pcl::PointIndices& output,
00270 pcl::ModelCoefficients& coefficients)
00271 {
00272 pcl::SACSegmentation<pcl::PointNormal> seg;
00273 seg.setOptimizeCoefficients (true);
00274 seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
00275 seg.setMethodType (pcl::SAC_RANSAC);
00276 seg.setDistanceThreshold (outlier_threashold_);
00277 seg.setMaxIterations (max_iteration_);
00278 seg.setEpsAngle(eps_angle_);
00279 seg.setAxis(normal);
00280 seg.setInputCloud(cloud);
00281 seg.setIndices(indices);
00282 seg.segment(output, coefficients);
00283 coefficients.header = cloud->header;
00284 output.header = cloud->header;
00285 PCLIndicesMsg ros_indices;
00286 pcl_conversions::fromPCL(output, ros_indices);
00287 pub_plane_filtered_indices_.publish(ros_indices);
00288 }
00289
00290 bool HintedPlaneDetector::detectLargerPlane(
00291 pcl::PointCloud<pcl::PointNormal>::Ptr input_cloud,
00292 ConvexPolygon::Ptr hint_convex)
00293 {
00294 pcl::PointIndices::Ptr candidate_inliers (new pcl::PointIndices);
00295 hintFilter(input_cloud, hint_convex, *candidate_inliers);
00296
00297
00298 pcl::PointIndices::Ptr plane_inliers (new pcl::PointIndices);
00299 pcl::ModelCoefficients::Ptr plane_coefficients(new pcl::ModelCoefficients);
00300 planeFilter(input_cloud, candidate_inliers,
00301 hint_convex->getNormal(),
00302 *plane_inliers, *plane_coefficients);
00303 if (plane_inliers->indices.size() < min_size_) {
00304 JSK_NODELET_ERROR("failed to detect by plane fitting filtering");
00305 return false;
00306 }
00307
00308 Eigen::Vector3f plane_normal(plane_coefficients->values[0], plane_coefficients->values[1], plane_coefficients->values[2]);
00309 if (plane_normal.dot(Eigen::Vector3f::UnitZ()) > 0) {
00310
00311 plane_coefficients->values[0] = -plane_coefficients->values[0];
00312 plane_coefficients->values[1] = -plane_coefficients->values[1];
00313 plane_coefficients->values[2] = -plane_coefficients->values[2];
00314 plane_coefficients->values[3] = -plane_coefficients->values[3];
00315 }
00316
00317 pcl::PointIndices::Ptr euclidean_filtered_indices(new pcl::PointIndices);
00318 euclideanFilter(input_cloud, plane_inliers, hint_convex,
00319 *euclidean_filtered_indices);
00320 if (euclidean_filtered_indices->indices.size() < min_size_) {
00321 JSK_NODELET_ERROR("failed to detect by euclidean filtering");
00322 return false;
00323 }
00324 pcl::PointIndices::Ptr density_filtered_indices (new pcl::PointIndices);
00325 densityFilter(
00326 input_cloud, euclidean_filtered_indices, *density_filtered_indices);
00327
00328 if (density_filtered_indices->indices.size() < min_size_) {
00329 JSK_NODELET_ERROR("failed to detect by density filtering");
00330 return false;
00331 }
00332 ConvexPolygon::Ptr convex
00333 = convexFromCoefficientsAndInliers<pcl::PointNormal>(
00334 input_cloud, density_filtered_indices, plane_coefficients);
00335
00336 publishPolygon(convex, pub_polygon_, pub_polygon_array_,
00337 input_cloud->header);
00338 PCLIndicesMsg ros_inliers;
00339 pcl_conversions::fromPCL(*density_filtered_indices, ros_inliers);
00340 pub_inliers_.publish(ros_inliers);
00341 PCLModelCoefficientMsg ros_coefficients;
00342 pcl_conversions::fromPCL(*plane_coefficients, ros_coefficients);
00343 pub_coefficients_.publish(ros_coefficients);
00344 return true;
00345 }
00346
00347 void HintedPlaneDetector::publishPolygon(
00348 const ConvexPolygon::Ptr convex,
00349 ros::Publisher& pub_polygon,
00350 ros::Publisher& pub_polygon_array,
00351 const pcl::PCLHeader& header)
00352 {
00353 geometry_msgs::PolygonStamped ros_polygon;
00354 ros_polygon.polygon = convex->toROSMsg();
00355 pcl_conversions::fromPCL(header, ros_polygon.header);
00356 jsk_recognition_msgs::PolygonArray ros_polygon_array;
00357 pcl_conversions::fromPCL(header, ros_polygon_array.header);
00358 ros_polygon_array.polygons.push_back(
00359 ros_polygon);
00360 pub_polygon_array.publish(ros_polygon_array);
00361 pub_polygon.publish(ros_polygon);
00362 }
00363
00364 bool HintedPlaneDetector::detectHintPlane(
00365 pcl::PointCloud<pcl::PointXYZ>::Ptr hint_cloud,
00366 ConvexPolygon::Ptr& convex)
00367 {
00368 pcl::PointIndices::Ptr hint_inliers (new pcl::PointIndices);
00369 pcl::ModelCoefficients::Ptr hint_coefficients(new pcl::ModelCoefficients);
00370 pcl::SACSegmentation<pcl::PointXYZ> seg;
00371 seg.setOptimizeCoefficients (true);
00372 seg.setModelType (pcl::SACMODEL_PLANE);
00373 seg.setMethodType (pcl::SAC_RANSAC);
00374 seg.setDistanceThreshold (hint_outlier_threashold_);
00375 seg.setMaxIterations (hint_max_iteration_);
00376 seg.setInputCloud(hint_cloud);
00377 seg.segment(*hint_inliers, *hint_coefficients);
00378 if (hint_inliers->indices.size() > hint_min_size_) {
00379 convex = convexFromCoefficientsAndInliers<pcl::PointXYZ>(
00380 hint_cloud, hint_inliers, hint_coefficients);
00381
00382 publishPolygon(convex,
00383 pub_hint_polygon_, pub_hint_polygon_array_,
00384 hint_cloud->header);
00385 PCLIndicesMsg ros_indices;
00386 PCLModelCoefficientMsg ros_coefficients;
00387 pcl_conversions::fromPCL(*hint_inliers, ros_indices);
00388 pub_hint_inliers_.publish(ros_indices);
00389 pcl_conversions::fromPCL(*hint_coefficients, ros_coefficients);
00390 pub_hint_coefficients_.publish(ros_coefficients);
00391 return true;
00392 }
00393 else {
00394 JSK_NODELET_ERROR("Failed to find hint plane");
00395 return false;
00396 }
00397 }
00398
00399 }
00400
00401 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HintedPlaneDetector, nodelet::Nodelet);