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_H_
00035 #define _C_POLYGON_REPRESENTATION_H_
00036
00037
00040
00041 #include <ros/ros.h>
00042
00043 #include <sensor_msgs/PointCloud2.h>
00044
00045
00046
00047 #include <pcl/ros/conversions.h>
00048 #include <pcl/point_cloud.h>
00049 #include <pcl/point_types.h>
00050
00051 #include <signal.h>
00052
00053
00054 #include <stdio.h>
00055 #include <stdlib.h>
00056 #include <string.h>
00057
00058 #include "config.h"
00059 #include "config_util.h"
00060 #include "eventlog.h"
00061 #include "lcmtypes_velodyne_t.h"
00062 #include "lcmtypes_pose_t.h"
00063 #include "small_linalg.h"
00064 #include "velodyne.h"
00065
00066 #include <visualization_msgs/Marker.h>
00067
00068 #include <cmath>
00069
00070 #include <iostream>
00071 #include <pcl/ModelCoefficients.h>
00072 #include <pcl/io/pcd_io.h>
00073 #include <pcl/point_types.h>
00074 #include <pcl/sample_consensus/method_types.h>
00075 #include <pcl/sample_consensus/model_types.h>
00076 #include <pcl/segmentation/sac_segmentation.h>
00077 #include <pcl/features/normal_3d.h>
00078 #include <pcl/ModelCoefficients.h>
00079 #include <pcl/io/pcd_io.h>
00080 #include <pcl/point_types.h>
00081 #include <pcl/features/normal_3d.h>
00082 #include <pcl/filters/extract_indices.h>
00083 #include <pcl/filters/passthrough.h>
00084 #include <pcl/sample_consensus/method_types.h>
00085 #include <pcl/sample_consensus/model_types.h>
00086 #include <pcl/segmentation/sac_segmentation.h>
00087 #include <pcl/filters/project_inliers.h>
00088
00089 #include <pcl/filters/extract_indices.h>
00090 #include <pcl/surface/convex_hull.h>
00091 #include <pcl/ModelCoefficients.h>
00092 #include <pcl/point_types.h>
00093 #include <pcl/io/pcd_io.h>
00094 #include <pcl/features/normal_3d.h>
00095 #include <pcl/filters/extract_indices.h>
00096 #include <pcl/filters/voxel_grid.h>
00097 #include <pcl/kdtree/kdtree.h>
00098 #include <pcl/sample_consensus/method_types.h>
00099 #include <pcl/sample_consensus/model_types.h>
00100 #include <pcl/segmentation/sac_segmentation.h>
00101 #include <pcl/segmentation/extract_clusters.h>
00102
00103 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00104
00105
00106 #include "pcl_ros/segmentation/extract_polygonal_prism_data.h"
00107
00108 typedef pcl::PointXYZ PointT;
00109 #define _NUM_POLYGONS_ 5
00110 #define _NUM_CLUSTERS_ 5
00111
00112
00113
00114 typedef struct tag_t_polygon_point_cloud
00115 {
00116 pcl::PointCloud<PointT>::Ptr cloud;
00117 ros::Publisher publisher;
00118 char advertising_name[1024];
00119 }t_polygon_point_cloud;
00120
00121
00122
00123 class c_polygon_representation
00124 {
00125 public:
00126
00128 c_polygon_representation(const char* name, ros::NodeHandle *node);
00129
00131 ~c_polygon_representation();
00132
00133 void publish_raw_cloud(void){publish_polygon_point_cloud(&raw);};
00134 void publish_projected_cloud(void){publish_polygon_point_cloud(&projected);};
00135 void publish_convex_hull_cloud(void){publish_polygon_point_cloud(&convex_hull);};
00136 void publish_additional_cloud(void){publish_polygon_point_cloud(&additional);};
00137
00138 void publish_polygon_point_cloud(t_polygon_point_cloud *ppc)
00139 {
00141 ppc->cloud->header.frame_id = "/sensor_frame";
00142 ppc->cloud->height = 1;
00143 ppc->cloud->is_dense=0;
00144 ppc->cloud->width = ppc->cloud->size();
00145
00146 pcl::toROSMsg(*ppc->cloud, cloud_msg);
00147 ppc->publisher.publish(cloud_msg);
00148 }
00149
00150
00151
00152
00153
00154 int indices_extraction(pcl::PointIndices::Ptr ind,
00155 pcl::PointCloud<PointT> *input_cloud,
00156 pcl::PointCloud<PointT> *remove_cloud,
00157 pcl::PointCloud<PointT>::Ptr copy_cloud,
00158 pcl::PointCloud<pcl::Normal> *input_normals,
00159 pcl::PointCloud<pcl::Normal> *remove_normals)
00160 {
00161 if (input_cloud!=NULL)
00162 {
00163 pcl::ExtractIndices<PointT> extract;
00164 extract.setInputCloud(input_cloud->makeShared());
00165 extract.setIndices(ind);
00166
00167
00168 if(copy_cloud!=NULL)
00169 {
00170 extract.setNegative(false);
00171 extract.filter(*copy_cloud);
00172 }
00173
00174
00175 if(remove_cloud!=NULL)
00176 {
00177 extract.setNegative(true);
00178 extract.filter(*remove_cloud);
00179 }
00180 }
00181
00182 if (input_normals!=NULL)
00183 {
00184 pcl::ExtractIndices<pcl::Normal> extract_normals;
00185 extract_normals.setInputCloud(input_normals->makeShared());
00186 extract_normals.setIndices(ind);
00187
00188 if (remove_normals!=NULL)
00189 {
00190 extract_normals.setNegative(true);
00191 extract_normals.filter(*remove_normals);
00192 }
00193 }
00194
00195
00196
00197 return 1;}
00198
00199
00200 void compute_plane_candidate_from_pc(pcl::PointCloud<PointT> *input_cloud,
00201 pcl::PointCloud<pcl::Normal> *input_normals,
00202 double DistanceThreshold = 0.5,
00203 double NormalDistanceWeight = 0.5,
00204 int MaxIterations = 1000
00205 );
00206
00207 void project_raw_cloud_to_plane(void)
00208 {
00209 project_cloud_to_plane(raw.cloud->makeShared());
00210 }
00211
00212 void project_cloud_to_plane(pcl::PointCloud<PointT>::Ptr input_cloud)
00213 {
00214
00215 pcl::ProjectInliers<pcl::PointXYZ> projection;
00216
00217 projection.setModelType(pcl::SACMODEL_NORMAL_PLANE);
00218 projection.setInputCloud(raw.cloud->makeShared());
00219 projection.setModelCoefficients(coefficients);
00220 projection.filter(*projected.cloud);
00221
00222 }
00223
00224 void compute_convex_hull(void)
00225 {
00226
00227 pcl::ConvexHull<pcl::PointXYZ> chull;
00228 chull.setInputCloud(projected.cloud->makeShared());
00229 chull.reconstruct(*convex_hull.cloud);
00230 }
00231
00232
00233 void segment_plane_from_point_cloud(
00234 pcl::PointCloud<PointT> *input_cloud,
00235 double DistanceThreshold,
00236 int MaxIterations);
00237
00238
00239 void compute_convex_hull_inliers(pcl::PointCloud<PointT> *input_cloud, pcl::PointCloud<pcl::Normal> *input_normals)
00240 {
00241
00242 pcl::ExtractPolygonalPrismData<PointT> epp;
00243 pcl::PointCloud<PointT>::ConstPtr input_cloud_constptr;
00244 input_cloud_constptr.reset (new pcl::PointCloud<PointT> (*input_cloud));
00245 pcl::PointCloud<PointT>::ConstPtr convex_hull_constptr;
00246 convex_hull_constptr.reset (new pcl::PointCloud<PointT> (*convex_hull.cloud));
00247 pcl::PointIndices::Ptr ind = pcl::PointIndices::Ptr(new pcl::PointIndices);
00248 pcl::ExtractIndices<PointT> extract;
00249
00250
00251 ROS_INFO("Extracting Convex Hull inliers");
00252 ROS_INFO("Input cloud has %d points",(int)input_cloud->size());
00253
00254
00255
00256 epp.setInputCloud(input_cloud_constptr);
00257 epp.setInputPlanarHull(convex_hull_constptr);
00258 epp.setHeightLimits(-0.2, 0.2);
00259 epp.setViewPoint(0,0,0);
00260
00261
00262 epp.segment(*ind);
00263
00264
00265 indices_extraction(ind,
00266 input_cloud,
00267 input_cloud,
00268 additional.cloud,
00269 input_normals,
00270 input_normals);
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00289
00290
00291
00292 (*raw.cloud) += (*additional.cloud);
00293
00294
00295
00296
00297 pcl::SACSegmentation<PointT> segmentation;
00298
00299 segmentation.setOptimizeCoefficients(true);
00300 segmentation.setModelType(pcl::SACMODEL_PLANE);
00301 segmentation.setMethodType (pcl::SAC_RANSAC);
00302 segmentation.setMaxIterations (100);
00303 segmentation.setDistanceThreshold(333);
00304
00305 ROS_INFO("Indices before %d ...",(int)raw.cloud->size());
00306
00307
00308 segmentation.setInputCloud(input_cloud->makeShared());
00309 segmentation.segment(*indices, *coefficients);
00310
00311 if (indices->indices.size () == 0)
00312 {
00313 ROS_ERROR("Could not estimate a planar model for the given dataset."); return;
00314 }
00315
00316 ROS_INFO("Found %d inliers of polygon",(int)additional.cloud->size());
00317 ROS_INFO("Removed %d points from input_cloud. Now has %d points",(int)additional.cloud->size(),(int)input_cloud->size());
00318
00319
00320 ROS_INFO("Extracting Convex Hull inliers done ...");
00321 }
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336 pcl::ModelCoefficients::Ptr coefficients;
00337 pcl::PointIndices::Ptr indices;
00338 t_polygon_point_cloud raw, projected, convex_hull, additional;
00339
00340
00341 private:
00342
00343
00344
00345
00346 ros::NodeHandle *rosnode;
00347 char polygon_name[1024];
00348 sensor_msgs::PointCloud2 cloud_msg;
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00360 void set_names(const char* s)
00361 {
00362 sprintf(polygon_name,"%s",s);
00363 sprintf(raw.advertising_name,"%s/raw",s);
00364 sprintf(additional.advertising_name,"%s/additional",s);
00365 sprintf(projected.advertising_name,"%s/projected",s);
00366 sprintf(convex_hull.advertising_name,"%s/convex_hull",s);
00367 }
00368
00369
00371 void allocate_space(void);
00372
00373
00374
00375 };
00376 #endif
00377
00380