detect_circle_3d.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00045 // ROS core
00046 #include <ros/ros.h>
00047 
00048 #include "pcl/io/pcd_io.h"
00049 #include "pcl/point_types.h"
00050 #include "pcl_ros/transforms.h"
00051 
00052 #include <pcl/ModelCoefficients.h>
00053 
00054 #include <pcl/features/normal_3d.h>
00055 
00056 #include <pcl/filters/extract_indices.h>
00057 #include <pcl/filters/passthrough.h>
00058 
00059 #include <pcl/sample_consensus/method_types.h>
00060 #include <pcl/sample_consensus/model_types.h>
00061 #include <pcl/segmentation/sac_segmentation.h>
00062 #include <pcl_ros/point_cloud.h>
00063 using namespace std;
00064 
00065 typedef pcl::PointXYZ Point;
00066 typedef pcl::PointCloud<Point> PointCloud;
00067 typedef PointCloud::Ptr PointCloudPtr;
00068 typedef PointCloud::ConstPtr PointCloudConstPtr;
00069 typedef pcl::KdTree<Point>::Ptr KdTreePtr;
00070 
00071 class DetectCircle
00072 {
00073 protected:
00074   ros::NodeHandle nh_;
00075 
00076 public:
00077   string output_cloud_topic_, input_cloud_topic_;
00078   ros::Subscriber sub_;
00079   ros::Publisher pub_;
00080   pcl::SACSegmentation<Point> seg;
00081   pcl::PointIndices circle_inliers_;
00082   pcl::ModelCoefficients circle_coeff;
00084   DetectCircle  (ros::NodeHandle &n) : nh_(n)
00085   {
00086     // Maximum number of outgoing messages to be queued for delivery to subscribers = 1
00087     nh_.param("input_cloud_topic", input_cloud_topic_, std::string("/camera/depth/points2_throttle"));
00088     nh_.param("output_cloud_topic", output_cloud_topic_, std::string("circle"));
00089    
00090     sub_ = nh_.subscribe (input_cloud_topic_, 1,  &DetectCircle::cloud_cb, this);
00091     ROS_INFO ("[DetectCircle3D:] Listening for incoming data on topic %s", nh_.resolveName (input_cloud_topic_).c_str ());
00092     pub_ = nh_.advertise<sensor_msgs::PointCloud2>(output_cloud_topic_, 1);
00093     ROS_INFO ("[DetectCircle3D:] Will be publishing data on topic %s.", nh_.resolveName (output_cloud_topic_).c_str ());
00094   }
00095 
00097   // cloud_cb (!)
00098   void cloud_cb (const sensor_msgs::PointCloud2ConstPtr& pc)
00099   {
00100     PointCloud cloud_raw;
00101     pcl::fromROSMsg (*pc, cloud_raw);
00102     seg.setOptimizeCoefficients (true);
00103     seg.setModelType (pcl::SACMODEL_CIRCLE2D);
00104     seg.setMethodType (pcl::SAC_RANSAC);
00105     seg.setMaxIterations (10000);
00106     seg.setDistanceThreshold (0.05);
00107     seg.setRadiusLimits (0.05, 0.1);
00108     seg.setInputCloud (boost::make_shared<PointCloud> (cloud_raw));
00109     // Obtain the circle inliers and coefficients
00110     seg.segment (circle_inliers_, circle_coeff);
00111     std::cerr << "Circle inliers " << circle_inliers_.indices.size() << std::endl;
00112     std::cerr << "Circle coefficients: " << circle_coeff << std::endl;
00113 
00114     pcl::ExtractIndices<Point> extract_object_indices;
00115     extract_object_indices.setInputCloud (boost::make_shared<PointCloud> (cloud_raw));
00116     extract_object_indices.setIndices (boost::make_shared<const pcl::PointIndices> (circle_inliers_));
00117     pcl::PointCloud<Point> cloud_object;
00118     extract_object_indices.filter (cloud_object);
00119     pub_.publish(cloud_object);
00120   }
00121 };
00122 
00123 int main (int argc, char** argv)
00124 {
00125   ros::init (argc, argv, "detect_circle_node");
00126   ros::NodeHandle n("~");
00127   DetectCircle dc(n);
00128   ros::spin ();
00129   return (0);
00130 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_cloud_tools
Author(s): Nico Blodow, Zoltan-Csaba Marton, Dejan Pangercic
autogenerated on Sun Oct 6 2013 11:58:07