7 #include <sensor_msgs/PointCloud2.h> 9 #include <pcl/ModelCoefficients.h> 10 #include <pcl/io/pcd_io.h> 11 #include <pcl/point_types.h> 12 #include <pcl/sample_consensus/method_types.h> 13 #include <pcl/sample_consensus/model_types.h> 14 #include <pcl/segmentation/sac_segmentation.h> 15 #include <pcl/filters/voxel_grid.h> 16 #include <pcl/filters/extract_indices.h> 17 #include <pcl/visualization/cloud_viewer.h> 22 cloud_cb (
const pcl::PCLPointCloud2ConstPtr& cloud_blob)
26 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud;
28 pcl::PCLPointCloud2::Ptr cloud_filtered_blob (
new pcl::PCLPointCloud2);
29 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>);
32 pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
33 sor.setInputCloud (cloud_blob);
34 sor.setLeafSize (0.2
f, 0.2
f, 0.2
f);
35 sor.filter (*cloud_filtered_blob);
38 pcl::fromPCLPointCloud2 (*cloud_filtered_blob, *cloud_filtered);
41 std::cout <<
"PointCloud after filtering has: " << cloud_filtered->points.size () <<
" data points." << std::endl;
46 pcl::ModelCoefficients::Ptr coefficients (
new pcl::ModelCoefficients ());
47 pcl::PointIndices::Ptr inliers (
new pcl::PointIndices ());
49 pcl::SACSegmentation<pcl::PointXYZRGB> seg;
51 seg.setOptimizeCoefficients (
true);
53 seg.setModelType (pcl::SACMODEL_PLANE);
54 seg.setMethodType (pcl::SAC_RANSAC);
55 seg.setMaxIterations (1000);
56 seg.setDistanceThreshold (0.2);
57 seg.setInputCloud (cloud_filtered);
59 int planeFndCnt = 0, nr_points = (int) cloud_filtered->points.size ();
60 pcl::IndicesPtr remaining (
new std::vector<int>);
61 remaining->resize (nr_points);
62 for (
size_t i = 0; i < remaining->size (); ++i) { (*remaining)[i] =
static_cast<int>(i); }
65 while (remaining->size () > 0.5 * nr_points)
68 seg.setIndices (remaining);
69 seg.segment (*inliers, *coefficients);
70 if (inliers->indices.size () == 0)
break;
73 std::vector<int>::iterator it = remaining->begin();
74 for (
size_t i = 0; i < inliers->indices.size (); ++i)
76 int curr = inliers->indices[i];
78 while (it != remaining->end() && *it < curr) { ++it; }
79 if (it == remaining->end())
break;
80 if (*it == curr) it = remaining->erase(it);
84 std::cout <<
"Found " << planeFndCnt <<
" planes." << std::endl;
87 for (std::vector<int>::iterator it = remaining->begin(); it != remaining->end(); ++it)
89 uint8_t r = 0, g = 255, b = 0;
90 uint32_t rgb = ((uint32_t)r << 16 | (uint32_t)g << 8 | (uint32_t)b);
91 cloud_filtered->at(*it).rgb = *reinterpret_cast<float*>(&rgb);
94 pcl::visualization::CloudViewer viewer (
"Simple Cloud Viewer");
95 viewer.showCloud (cloud_filtered);
96 while (!viewer.wasStopped ())
100 pcl::PCLPointCloud2 outcloud;
101 pcl::toPCLPointCloud2 (*cloud_filtered, outcloud);
112 std::string inputTopic =
"input";
115 std::string heatMapName;
116 nh.
getParam(
"heat_map", heatMapName);
119 inputTopic = argv[1];
125 pub = nh.
advertise<pcl::PCLPointCloud2> (
"obstacles", 1);
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
void cloud_cb(const pcl::PCLPointCloud2ConstPtr &cloud_blob)