Go to the documentation of this file.00001
00004 #include <iostream>
00005 #include <ros/ros.h>
00006
00007 #include <sensor_msgs/PointCloud2.h>
00008 #include <pcl_conversions/pcl_conversions.h>
00009 #include <pcl/ModelCoefficients.h>
00010 #include <pcl/io/pcd_io.h>
00011 #include <pcl/point_types.h>
00012 #include <pcl/sample_consensus/method_types.h>
00013 #include <pcl/sample_consensus/model_types.h>
00014 #include <pcl/segmentation/sac_segmentation.h>
00015 #include <pcl/filters/voxel_grid.h>
00016 #include <pcl/filters/extract_indices.h>
00017 #include <pcl/visualization/cloud_viewer.h>
00018
00019 ros::Publisher pub;
00020
00021 void
00022 cloud_cb (const pcl::PCLPointCloud2ConstPtr& cloud_blob)
00023 {
00024
00025
00026 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
00027
00028 pcl::PCLPointCloud2::Ptr cloud_filtered_blob (new pcl::PCLPointCloud2);
00029 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZRGB>), cloud_p (new pcl::PointCloud<pcl::PointXYZRGB>), cloud_f (new pcl::PointCloud<pcl::PointXYZRGB>);
00030
00031
00032 pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
00033 sor.setInputCloud (cloud_blob);
00034 sor.setLeafSize (0.2f, 0.2f, 0.2f);
00035 sor.filter (*cloud_filtered_blob);
00036
00037
00038 pcl::fromPCLPointCloud2 (*cloud_filtered_blob, *cloud_filtered);
00039
00040
00041 std::cout << "PointCloud after filtering has: " << cloud_filtered->points.size () << " data points." << std::endl;
00042
00043
00044
00045
00046 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00047 pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00048
00049 pcl::SACSegmentation<pcl::PointXYZRGB> seg;
00050
00051 seg.setOptimizeCoefficients (true);
00052
00053 seg.setModelType (pcl::SACMODEL_PLANE);
00054 seg.setMethodType (pcl::SAC_RANSAC);
00055 seg.setMaxIterations (1000);
00056 seg.setDistanceThreshold (0.2);
00057 seg.setInputCloud (cloud_filtered);
00058
00059 int planeFndCnt = 0, nr_points = (int) cloud_filtered->points.size ();
00060 pcl::IndicesPtr remaining (new std::vector<int>);
00061 remaining->resize (nr_points);
00062 for (size_t i = 0; i < remaining->size (); ++i) { (*remaining)[i] = static_cast<int>(i); }
00063
00064
00065 while (remaining->size () > 0.5 * nr_points)
00066 {
00067
00068 seg.setIndices (remaining);
00069 seg.segment (*inliers, *coefficients);
00070 if (inliers->indices.size () == 0) break;
00071
00072
00073 std::vector<int>::iterator it = remaining->begin();
00074 for (size_t i = 0; i < inliers->indices.size (); ++i)
00075 {
00076 int curr = inliers->indices[i];
00077
00078 while (it != remaining->end() && *it < curr) { ++it; }
00079 if (it == remaining->end()) break;
00080 if (*it == curr) it = remaining->erase(it);
00081 }
00082 planeFndCnt++;
00083 }
00084 std::cout << "Found " << planeFndCnt << " planes." << std::endl;
00085
00086
00087 for (std::vector<int>::iterator it = remaining->begin(); it != remaining->end(); ++it)
00088 {
00089 uint8_t r = 0, g = 255, b = 0;
00090 uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b);
00091 cloud_filtered->at(*it).rgb = *reinterpret_cast<float*>(&rgb);
00092 }
00093
00094 pcl::visualization::CloudViewer viewer ("Simple Cloud Viewer");
00095 viewer.showCloud (cloud_filtered);
00096 while (!viewer.wasStopped ())
00097 {
00098 }
00099
00100 pcl::PCLPointCloud2 outcloud;
00101 pcl::toPCLPointCloud2 (*cloud_filtered, outcloud);
00102 pub.publish (outcloud);
00103 }
00104
00105 int
00106 main (int argc, char** argv)
00107 {
00108
00109 ros::init (argc, argv, "obstacles");
00110 ros::NodeHandle nh;
00111
00112 std::string inputTopic = "input";
00113
00114
00115 std::string heatMapName;
00116 nh.getParam("heat_map", heatMapName);
00117 if (argc > 1)
00118 {
00119 inputTopic = argv[1];
00120 }
00121
00122 ros::Subscriber sub = nh.subscribe (inputTopic, 1, cloud_cb);
00123
00124
00125 pub = nh.advertise<pcl::PCLPointCloud2> ("obstacles", 1);
00126
00127
00128 ros::spin ();
00129 }