c_polygon_representation.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
34 #ifndef _C_POLYGON_REPRESENTATION_CPP_
35 #define _C_POLYGON_REPRESENTATION_CPP_
36 
37 
39 
40 c_polygon_representation::c_polygon_representation(const char* name, ros::NodeHandle *node)
41 {
43  set_names(name);
44  rosnode = node;
45  raw.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(raw.advertising_name, 1);
46  additional.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(additional.advertising_name, 1);
47  projected.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(projected.advertising_name, 1);
48  convex_hull.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(convex_hull.advertising_name, 1);
49  ROS_INFO("__________________________________");
50  ROS_INFO("Starting a new polygon class named %s",polygon_name);
51 };
52 
54 {
55  delete &coefficients;
56  delete &indices;
57 };
58 
60 {
61  raw.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
62  additional.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
63  projected.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
64  convex_hull.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
65  coefficients = pcl::ModelCoefficients::Ptr(new pcl::ModelCoefficients);
66  indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
67 }
68 
70  pcl::PointCloud<PointT> *input_cloud,
71  pcl::PointCloud<pcl::Normal> *input_normals,
72  double DistanceThreshold,
73  double NormalDistanceWeight,
74  int MaxIterations)
75 {
76 int num_original_pts = (int)input_cloud->size();
77 
78 // Create the segmentation object
79 pcl::SACSegmentationFromNormals<PointT, pcl::Normal> segmentation;
80 
81 //Setup segmentation parameters
82 segmentation.setOptimizeCoefficients(true);
83 segmentation.setModelType(pcl::SACMODEL_NORMAL_PLANE);
84 segmentation.setMethodType (pcl::SAC_RANSAC);
85 segmentation.setMaxIterations (MaxIterations);
86 segmentation.setNormalDistanceWeight (NormalDistanceWeight);
87 segmentation.setDistanceThreshold(DistanceThreshold);
88 
89 //Compute a plane candidate from the point cloud
90 segmentation.setInputCloud(input_cloud->makeShared());
91 segmentation.setInputNormals(input_normals->makeShared());
92 segmentation.segment(*indices, *coefficients);
93 
94 if (indices->indices.size () == 0)
95 {
96  ROS_ERROR("Could not estimate a planar model for the given dataset."); return;
97 }
98 
100  input_cloud,
101  input_cloud,
102  raw.cloud,
103  input_normals,
104  input_normals);
105 
106 
107 ROS_INFO("COMPUTING A PLANE CANDIDATE: candidate with %d points from an input pc with %d points",(int)raw.cloud->size(), num_original_pts);
108 
109 }
110 
112  pcl::PointCloud<PointT> *input_cloud,
113  double DistanceThreshold,
114  int MaxIterations)
115  {
116 
117  //Setup segmentation parameters
118  pcl::SACSegmentation<PointT> segmentation; // Create the segmentation object
119 
120  segmentation.setOptimizeCoefficients(true);
121  segmentation.setModelType(pcl::SACMODEL_PLANE);
122  segmentation.setMethodType (pcl::SAC_RANSAC);
123  segmentation.setMaxIterations (MaxIterations);
124  segmentation.setDistanceThreshold(DistanceThreshold);
125 
126  ROS_INFO("Indices before %d ...",(int)raw.cloud->size());
127 
128  //Compute a plane candidate from the point cloud
129  segmentation.setInputCloud(input_cloud->makeShared());
130  segmentation.segment(*indices, *coefficients);
131 
132  if (indices->indices.size () == 0)
133  {
134  ROS_ERROR("Could not estimate a planar model for the given dataset."); return;
135  }
136 
137 
138 
139  }
140 
141 #endif
142 
t_polygon_point_cloud additional
pcl::PointCloud< PointT >::Ptr cloud
void compute_plane_candidate_from_pc(pcl::PointCloud< PointT > *input_cloud, pcl::PointCloud< pcl::Normal > *input_normals, double DistanceThreshold=0.5, double NormalDistanceWeight=0.5, int MaxIterations=1000)
int indices_extraction(pcl::PointIndices::Ptr ind, pcl::PointCloud< PointT > *input_cloud, pcl::PointCloud< PointT > *remove_cloud, pcl::PointCloud< PointT >::Ptr copy_cloud, pcl::PointCloud< pcl::Normal > *input_normals, pcl::PointCloud< pcl::Normal > *remove_normals)
pcl::PointIndices::Ptr indices
header for polygon representation. Defines how a polygon is stored in memory
~c_polygon_representation()
Destructor. free space of Ptr objecs.
pcl::ModelCoefficients::Ptr coefficients
t_polygon_point_cloud convex_hull
c_polygon_representation(const char *name, ros::NodeHandle *node)
Constructor. Allocate space for Ptr objecs.
void segment_plane_from_point_cloud(pcl::PointCloud< PointT > *input_cloud, double DistanceThreshold, int MaxIterations)
void set_names(const char *s)
set names


polygon_primitives_extraction
Author(s): Miguel Oliveira
autogenerated on Mon Mar 2 2015 01:32:41