Go to the documentation of this file.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
00035
00036
00045
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
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
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
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 }