hinted_stick_finder_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/hinted_stick_finder.h"
00037 #include "jsk_pcl_ros/pcl_conversion_util.h"
00038 #include <pcl/sample_consensus/method_types.h>
00039 #include <pcl/sample_consensus/model_types.h>
00040 #include <pcl/segmentation/sac_segmentation.h>
00041 #include <pcl/filters/project_inliers.h>
00042 #include <pcl/filters/extract_indices.h>
00043 #include <pcl/features/normal_3d_omp.h>
00044 #include <visualization_msgs/Marker.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 
00047 namespace jsk_pcl_ros
00048 {
00049   void HintedStickFinder::onInit()
00050   {
00051     DiagnosticNodelet::onInit();
00052     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00053     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00054       boost::bind (&HintedStickFinder::configCallback, this, _1, _2);
00055     srv_->setCallback (f);
00056     pnh_->param("use_normal", use_normal_, false);
00057     pnh_->param("not_synchronize", not_synchronize_, false);
00058     
00059     pub_line_filtered_indices_ = advertise<PCLIndicesMsg>(
00060       *pnh_, "debug/line_filtered_indices", 1);
00061     pub_line_filtered_normal_ = advertise<sensor_msgs::PointCloud2>(
00062       *pnh_, "debug/line_filtered_normal", 1);
00063     pub_cylinder_marker_ = advertise<visualization_msgs::Marker>(
00064       *pnh_, "debug/cylinder_marker", 1);
00065     pub_cylinder_pose_ = advertise<geometry_msgs::PoseStamped>(
00066       *pnh_, "output/cylinder_pose", 1);
00067     pub_inliers_ = advertise<PCLIndicesMsg>(
00068       *pnh_, "output/inliers", 1);
00069     pub_coefficients_ = advertise<PCLModelCoefficientMsg>(
00070       *pnh_, "output/coefficients", 1);
00071   }
00072 
00073   void HintedStickFinder::subscribe()
00074   {
00075     if (!not_synchronize_) {
00076       sub_polygon_.subscribe(*pnh_, "input/hint/line", 1);
00077       sub_info_.subscribe(*pnh_, "input/camera_info", 1);
00078       sub_cloud_.subscribe(*pnh_, "input", 1);
00079       sync_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(100);
00080       sync_->connectInput(sub_polygon_, sub_info_, sub_cloud_);
00081       sync_->registerCallback(boost::bind(&HintedStickFinder::detect, this,
00082                                           _1, _2, _3));
00083     }
00084     else {
00085       sub_no_sync_cloud_ = pnh_->subscribe(
00086         "input", 1, &HintedStickFinder::cloudCallback, this);
00087       sub_no_sync_camera_info_ = pnh_->subscribe(
00088         "input/camera_info", 1, &HintedStickFinder::infoCallback, this);
00089       sub_no_sync_polygon_ = pnh_->subscribe(
00090         "input/hint/line", 1, &HintedStickFinder::hintCallback, this);
00091     }
00092   }
00093 
00094 
00095   void HintedStickFinder::cloudCallback(
00096       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00097   {
00098     {
00099       boost::mutex::scoped_lock lock(mutex_);
00100       if (!latest_hint_ || !latest_camera_info_) {
00101         // not yet ready
00102         NODELET_WARN_THROTTLE(1, "~input/hint/lline or ~input/camera_info is not ready");
00103         return;
00104       }
00105     }
00106     detect(latest_hint_, latest_camera_info_, cloud_msg);
00107   }
00108 
00109 
00110   void HintedStickFinder::hintCallback(
00111     const geometry_msgs::PolygonStamped::ConstPtr& hint_msg)
00112   {
00113     boost::mutex::scoped_lock lock(mutex_);
00114     latest_hint_ = hint_msg;
00115   }
00116 
00117   void HintedStickFinder::infoCallback(
00118     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00119   {
00120     boost::mutex::scoped_lock lock(mutex_);
00121     latest_camera_info_ = info_msg;
00122   }
00123   
00124   
00125   void HintedStickFinder::unsubscribe()
00126   {
00127     if (!not_synchronize_) {
00128       sub_polygon_.unsubscribe();
00129       sub_info_.unsubscribe();
00130       sub_cloud_.unsubscribe();
00131     }
00132     else {
00133       sub_no_sync_cloud_.shutdown();
00134       sub_no_sync_camera_info_.shutdown();
00135       sub_no_sync_polygon_.shutdown();
00136     }
00137   }
00138 
00139   void HintedStickFinder::detect(
00140     const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
00141     const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg,
00142     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00143   {
00144     boost::mutex::scoped_lock lock(mutex_);
00145     JSK_NODELET_WARN("starting detection");
00146     ros::Time start_time = ros::Time::now();
00147     image_geometry::PinholeCameraModel model;
00148     model.fromCameraInfo(camera_info_msg);
00149     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud
00150       (new pcl::PointCloud<pcl::PointXYZ>);
00151     pcl::fromROSMsg(*cloud_msg, *cloud);
00152     // convert 2-D point into 3-D ray
00153     Eigen::Vector3f a, b;
00154     ConvexPolygon::Ptr polygon = polygonFromLine(polygon_msg, model, a, b);
00155     pcl::PointIndices::Ptr candidate_indices
00156       (new pcl::PointIndices);
00157     
00158     filterPointCloud(cloud, polygon, *candidate_indices);
00159     pcl::PointCloud<pcl::Normal>::Ptr normals
00160       (new pcl::PointCloud<pcl::Normal>);
00161     pcl::PointCloud<pcl::PointXYZ>::Ptr normals_cloud
00162       (new pcl::PointCloud<pcl::PointXYZ>);
00163     if (!use_normal_) {
00164       normalEstimate(cloud, candidate_indices, *normals, *normals_cloud);
00165     }
00166     else {
00167       // we don't need to compute normal
00168       pcl::PointCloud<pcl::Normal>::Ptr all_normals
00169         (new pcl::PointCloud<pcl::Normal>);
00170       pcl::fromROSMsg(*cloud_msg, *all_normals);
00171       pcl::ExtractIndices<pcl::PointXYZ> xyz_extract;
00172       xyz_extract.setInputCloud(cloud);
00173       xyz_extract.setIndices(candidate_indices);
00174       xyz_extract.filter(*normals_cloud);
00175       
00176       pcl::ExtractIndices<pcl::Normal> normal_extract;
00177       normal_extract.setInputCloud(all_normals);
00178       normal_extract.setIndices(candidate_indices);
00179       normal_extract.filter(*normals);
00180     }
00181     fittingCylinder(normals_cloud, normals, a, b);
00182     ros::Time end_time = ros::Time::now();
00183     JSK_NODELET_WARN("detection time: %f", (end_time - start_time).toSec());
00184   }
00185 
00186   void HintedStickFinder::normalEstimate(
00187     const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
00188     const pcl::PointIndices::Ptr indices,
00189     pcl::PointCloud<pcl::Normal>& normals,
00190     pcl::PointCloud<pcl::PointXYZ>& normals_cloud)
00191   {
00192     pcl::NormalEstimationOMP<pcl::PointXYZ, pcl::Normal> ne;
00193     ne.setInputCloud(cloud);
00194     ne.setIndices(indices);
00195     pcl::search::KdTree<pcl::PointXYZ>::Ptr tree
00196       (new pcl::search::KdTree<pcl::PointXYZ> ());
00197     ne.setSearchMethod(tree);
00198     ne.setRadiusSearch (0.03);
00199     ne.compute (normals);
00200     pcl::ExtractIndices<pcl::PointXYZ> ex;
00201     ex.setInputCloud(cloud);
00202     ex.setIndices(indices);
00203     ex.filter(normals_cloud);
00204   }
00205 
00206   bool HintedStickFinder::rejected2DHint(
00207     const Cylinder::Ptr& cylinder,
00208     const Eigen::Vector3f& a,
00209     const Eigen::Vector3f& b)
00210   {
00211     Eigen::Vector3f hint_dir((b - a));
00212     hint_dir[2] = 0;
00213     hint_dir.normalize();
00214     Eigen::Vector3f cylinder_dir(cylinder->getDirection());
00215     cylinder_dir[2] = 0;
00216     cylinder_dir.normalize();
00217     double ang = acos(cylinder_dir.dot(hint_dir));
00218     JSK_NODELET_INFO("angle: %f", ang);
00219     return !(ang < eps_2d_angle_ || (M_PI - ang) < eps_2d_angle_);
00220   }
00221   
00222   void HintedStickFinder::fittingCylinder(
00223     const pcl::PointCloud<pcl::PointXYZ>::Ptr& filtered_cloud,
00224     const pcl::PointCloud<pcl::Normal>::Ptr& cloud_normals,
00225     const Eigen::Vector3f& a,
00226     const Eigen::Vector3f& b)
00227   {
00228     pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal> seg;
00229     pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00230     pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
00231     Eigen::Vector3f normal = (a - b).normalized();
00232     seg.setOptimizeCoefficients (true);
00233     seg.setModelType (pcl::SACMODEL_CYLINDER);
00234     seg.setMethodType (pcl::SAC_RANSAC);
00235     seg.setDistanceThreshold (outlier_threshold_);
00236     seg.setMaxIterations (max_iteration_);
00237     seg.setNormalDistanceWeight (0.1);
00238     seg.setRadiusLimits(min_radius_, max_radius_);
00239     // seg.setEpsAngle(eps_angle_);
00240     // seg.setAxis(normal);
00241     seg.setProbability(min_probability_);
00242     seg.setInputCloud(filtered_cloud);
00243     seg.setInputNormals(cloud_normals);
00244     for (size_t i = 0; i < cylinder_fitting_trial_; i++) {
00245       seg.segment(*inliers, *coefficients);
00246       if (inliers->indices.size() > min_inliers_) {
00247         Eigen::Vector3f dir(coefficients->values[3],
00248                             coefficients->values[4],
00249                             coefficients->values[5]);
00250         if (dir.dot(Eigen::Vector3f(0, -1, 0)) < 0) {
00251           dir = -dir;
00252         }
00253         Cylinder::Ptr cylinder(new Cylinder(Eigen::Vector3f(
00254                                               coefficients->values[0],
00255                                               coefficients->values[1],
00256                                               coefficients->values[2]),
00257                                             dir,
00258                                             coefficients->values[6]));
00259         pcl::PointIndices::Ptr cylinder_indices
00260           (new pcl::PointIndices);
00261         cylinder->filterPointCloud(*filtered_cloud,
00262                                    outlier_threshold_,
00263                                    *cylinder_indices);
00264         double height = 0;
00265         Eigen::Vector3f center;
00266         cylinder->estimateCenterAndHeight(
00267           *filtered_cloud, *cylinder_indices,
00268           center, height);
00269         if (!rejected2DHint(cylinder, a, b)) {
00270           Eigen::Vector3f uz = Eigen::Vector3f(
00271             dir).normalized();
00272           // build maker
00273           visualization_msgs::Marker marker;
00274           cylinder->toMarker(marker, center, uz, height);
00275           pcl_conversions::fromPCL(filtered_cloud->header, marker.header);
00276           pub_cylinder_marker_.publish(marker);
00277           geometry_msgs::PoseStamped pose;
00278           pose.header = marker.header;
00279           pose.pose = marker.pose;
00280           pub_cylinder_pose_.publish(pose);
00281           
00282           PCLIndicesMsg ros_inliers;
00283           pcl_conversions::fromPCL(*inliers, ros_inliers);
00284           pub_inliers_.publish(ros_inliers);
00285           PCLModelCoefficientMsg ros_coefficients;
00286           ros_coefficients.header = pcl_conversions::fromPCL(coefficients->header);
00287           ros_coefficients.values.push_back(center[0]);
00288           ros_coefficients.values.push_back(center[1]);
00289           ros_coefficients.values.push_back(center[2]);
00290           ros_coefficients.values.push_back(dir[0]);
00291           ros_coefficients.values.push_back(dir[1]);
00292           ros_coefficients.values.push_back(dir[2]);
00293           ros_coefficients.values.push_back(coefficients->values[6]);
00294           ros_coefficients.values.push_back(height);
00295           pub_coefficients_.publish(ros_coefficients);
00296         return;
00297         }
00298       }
00299       JSK_NODELET_WARN("failed to detect cylinder [%lu/%d]", i, cylinder_fitting_trial_);
00300     }
00301   }
00302   
00303   void HintedStickFinder::filterPointCloud(
00304     const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud,
00305     const ConvexPolygon::Ptr polygon,
00306     pcl::PointIndices& output_indices)
00307   {
00308     output_indices.indices.clear();
00309     for (size_t i = 0; i < cloud->points.size(); i++) {
00310       pcl::PointXYZ p = cloud->points[i];
00311       if (!isnan(p.x) && !isnan(p.y) && !isnan(p.z)) {
00312         if (polygon->isProjectableInside(p.getVector3fMap())) {
00313           if (polygon->distanceSmallerThan(p.getVector3fMap(), filter_distance_)) {
00314             output_indices.indices.push_back(i);
00315           }
00316         }
00317       }
00318     }
00319     output_indices.header = cloud->header;
00320     PCLIndicesMsg ros_indices;
00321     pcl_conversions::fromPCL(output_indices, ros_indices);
00322     pub_line_filtered_indices_.publish(ros_indices);
00323   }
00324 
00325 
00326   ConvexPolygon::Ptr HintedStickFinder::polygonFromLine(
00327     const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg,
00328     const image_geometry::PinholeCameraModel& model,
00329     Eigen::Vector3f& a,
00330     Eigen::Vector3f& b)
00331   {
00332     cv::Point2d point_a(polygon_msg->polygon.points[0].x,
00333                         polygon_msg->polygon.points[0].y);
00334     cv::Point2d point_b(polygon_msg->polygon.points[1].x,
00335                         polygon_msg->polygon.points[1].y);
00336     cv::Point3d ray_a = model.projectPixelTo3dRay(point_a);
00337     cv::Point3d ray_b = model.projectPixelTo3dRay(point_b);
00338     a = Eigen::Vector3f(ray_a.x, ray_a.y, ray_a.z);
00339     b = Eigen::Vector3f(ray_b.x, ray_b.y, ray_b.z);
00340     // 20m is far enough??
00341     Eigen::Vector3f far_a = 20.0 * a;
00342     Eigen::Vector3f far_b = 20.0 * b;
00343     Eigen::Vector3f O(0, 0, 0);
00344     Vertices vertices;
00345     vertices.push_back(O);
00346     vertices.push_back(far_a);
00347     vertices.push_back(far_b);
00348     ConvexPolygon::Ptr polygon (new ConvexPolygon(vertices));
00349     return polygon;
00350   }
00351 
00352   void HintedStickFinder::configCallback(Config &config, uint32_t level)
00353   {
00354     boost::mutex::scoped_lock lock(mutex_);
00355     min_radius_ = config.min_radius;
00356     max_radius_ = config.max_radius;
00357     filter_distance_ = config.filter_distance;
00358     outlier_threshold_ = config.outlier_threshold;
00359     max_iteration_ = config.max_iteration;
00360     eps_angle_ = config.eps_angle;
00361     min_probability_ = config.min_probability;
00362     cylinder_fitting_trial_ = config.cylinder_fitting_trial;
00363     min_inliers_ = config.min_inliers;
00364     eps_2d_angle_ = config.eps_2d_angle;
00365   }
00366 }
00367 
00368 #include <pluginlib/class_list_macros.h>
00369 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::HintedStickFinder, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47