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
00034 #ifndef _C_POLYGON_REPRESENTATION_CPP_
00035 #define _C_POLYGON_REPRESENTATION_CPP_
00036
00037
00038 #include "c_polygon_representation.h"
00039
00040 c_polygon_representation::c_polygon_representation(const char* name, ros::NodeHandle *node)
00041 {
00042 allocate_space();
00043 set_names(name);
00044 rosnode = node;
00045 raw.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(raw.advertising_name, 1);
00046 additional.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(additional.advertising_name, 1);
00047 projected.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(projected.advertising_name, 1);
00048 convex_hull.publisher = rosnode->advertise<sensor_msgs::PointCloud2>(convex_hull.advertising_name, 1);
00049 ROS_INFO("__________________________________");
00050 ROS_INFO("Starting a new polygon class named %s",polygon_name);
00051 };
00052
00053 c_polygon_representation::~c_polygon_representation()
00054 {
00055 delete &coefficients;
00056 delete &indices;
00057 };
00058
00059 void c_polygon_representation::allocate_space(void)
00060 {
00061 raw.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
00062 additional.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
00063 projected.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
00064 convex_hull.cloud = pcl::PointCloud<PointT>::Ptr(new pcl::PointCloud<PointT>);
00065 coefficients = pcl::ModelCoefficients::Ptr(new pcl::ModelCoefficients);
00066 indices = pcl::PointIndices::Ptr(new pcl::PointIndices);
00067 }
00068
00069 void c_polygon_representation::compute_plane_candidate_from_pc(
00070 pcl::PointCloud<PointT> *input_cloud,
00071 pcl::PointCloud<pcl::Normal> *input_normals,
00072 double DistanceThreshold,
00073 double NormalDistanceWeight,
00074 int MaxIterations)
00075 {
00076 int num_original_pts = (int)input_cloud->size();
00077
00078
00079 pcl::SACSegmentationFromNormals<PointT, pcl::Normal> segmentation;
00080
00081
00082 segmentation.setOptimizeCoefficients(true);
00083 segmentation.setModelType(pcl::SACMODEL_NORMAL_PLANE);
00084 segmentation.setMethodType (pcl::SAC_RANSAC);
00085 segmentation.setMaxIterations (MaxIterations);
00086 segmentation.setNormalDistanceWeight (NormalDistanceWeight);
00087 segmentation.setDistanceThreshold(DistanceThreshold);
00088
00089
00090 segmentation.setInputCloud(input_cloud->makeShared());
00091 segmentation.setInputNormals(input_normals->makeShared());
00092 segmentation.segment(*indices, *coefficients);
00093
00094 if (indices->indices.size () == 0)
00095 {
00096 ROS_ERROR("Could not estimate a planar model for the given dataset."); return;
00097 }
00098
00099 indices_extraction(indices,
00100 input_cloud,
00101 input_cloud,
00102 raw.cloud,
00103 input_normals,
00104 input_normals);
00105
00106
00107 ROS_INFO("COMPUTING A PLANE CANDIDATE: candidate with %d points from an input pc with %d points",(int)raw.cloud->size(), num_original_pts);
00108
00109 }
00110
00111 void c_polygon_representation::segment_plane_from_point_cloud(
00112 pcl::PointCloud<PointT> *input_cloud,
00113 double DistanceThreshold,
00114 int MaxIterations)
00115 {
00116
00117
00118 pcl::SACSegmentation<PointT> segmentation;
00119
00120 segmentation.setOptimizeCoefficients(true);
00121 segmentation.setModelType(pcl::SACMODEL_PLANE);
00122 segmentation.setMethodType (pcl::SAC_RANSAC);
00123 segmentation.setMaxIterations (MaxIterations);
00124 segmentation.setDistanceThreshold(DistanceThreshold);
00125
00126 ROS_INFO("Indices before %d ...",(int)raw.cloud->size());
00127
00128
00129 segmentation.setInputCloud(input_cloud->makeShared());
00130 segmentation.segment(*indices, *coefficients);
00131
00132 if (indices->indices.size () == 0)
00133 {
00134 ROS_ERROR("Could not estimate a planar model for the given dataset."); return;
00135 }
00136
00137
00138
00139 }
00140
00141 #endif
00142