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
00036 #ifndef _polygon_primitive_H_
00037 #define _polygon_primitive_H_
00038
00042 #define PFLN {printf("DEBUG PRINT FILE %s LINE %d\n",__FILE__,__LINE__);}
00043
00044
00047
00049 #include <ros/ros.h>
00050 #include <sensor_msgs/PointCloud2.h>
00051 #include <sensor_msgs/PointCloud.h>
00052 #include <visualization_msgs/Marker.h>
00053 #include <visualization_msgs/MarkerArray.h>
00054 #include <tf/transform_broadcaster.h>
00055
00057 #include "pcl_ros/impl/transforms.hpp"
00058 #include <pcl/ros/conversions.h>
00059 #include <pcl/point_cloud.h>
00060 #include <pcl/point_types.h>
00061 #include <pcl_ros/point_cloud.h>
00062 #include <pcl/io/pcd_io.h>
00063 #include <pcl/point_types.h>
00064 #include <pcl/sample_consensus/method_types.h>
00065 #include <pcl/sample_consensus/model_types.h>
00066 #include <pcl/segmentation/sac_segmentation.h>
00067 #include <pcl/features/normal_3d.h>
00068 #include <pcl/ModelCoefficients.h>
00069 #include <pcl/filters/extract_indices.h>
00070 #include <pcl/segmentation/sac_segmentation.h>
00071 #include <pcl/filters/project_inliers.h>
00072 #include <pcl/filters/extract_indices.h>
00073 #include <pcl/surface/convex_hull.h>
00074 #include <pcl/surface/concave_hull.h>
00075 #include <pcl/ModelCoefficients.h>
00076 #include <pcl/features/normal_3d.h>
00077 #include <pcl/filters/extract_indices.h>
00078 #include <pcl/filters/voxel_grid.h>
00079 #include <pcl/kdtree/kdtree.h>
00080 #include <pcl/sample_consensus/method_types.h>
00081 #include <pcl/sample_consensus/model_types.h>
00082 #include <pcl/segmentation/sac_segmentation.h>
00083 #include <pcl-1.6/pcl/segmentation/extract_clusters.h>
00084
00085 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00086
00087
00089 #include <opencv2/core/core.hpp>
00090
00092 #include <polygon_primitive_msg/polygon_primitive.h>
00093
00094
00098 template <class PointT>
00099 class polygon_3d:public pcl::PointCloud<PointT>{};
00100
00101
00102 typedef struct {double x,y,z;}t_vector3d;
00103 typedef struct
00104 {
00105 t_vector3d origin;
00106 t_vector3d arrow_x;
00107 t_vector3d arrow_y;
00108 t_vector3d arrow_z;
00109 tf::Transform transform;
00110 }t_reference_frame;
00111
00112 typedef struct
00113 {
00114 struct
00115 {
00119 struct
00120 {
00121 unsigned char r,g,b;
00122 }color;
00123
00124 char name[1024];
00125 bool ground_search;
00126
00127 }misc;
00128
00132 struct
00133 {
00137 struct
00138 {
00139 polygon_3d<pcl::PointXYZ>::Ptr polygon, extended_polygon;
00140 double area;
00141 double solidity;
00142 }convex;
00143
00147 struct
00148 {
00149 polygon_3d<pcl::PointXYZ>::Ptr polygon, extended_polygon;
00150 double area;
00151 double solidity;
00152 }concave;
00153 }hulls;
00154
00158 struct
00159 {
00160 pcl::ModelCoefficients::Ptr current;
00161 pcl::ModelCoefficients::Ptr previous;
00162 }planes;
00163
00167 struct
00168 {
00169 std::string local_name;
00170 std::string global_name;
00171 t_reference_frame current;
00172 t_reference_frame previous;
00173 }frames;
00174
00175 }t_polygon_primitive_data;
00176
00177
00178
00182 class c_polygon_primitive
00183 {
00184
00185
00186
00187 public:
00188
00189
00193 struct {
00194 pcl::PointCloud<pcl::PointXYZ>::Ptr
00195 all,
00196 projected,
00197 additional,
00198 growed,
00199 tmp;
00200 }pointclouds;
00201
00202 ros::NodeHandle *rosnode;
00203 t_polygon_primitive_data data;
00204
00205 private:
00206 tf::TransformBroadcaster br;
00207 sensor_msgs::PointCloud2 cloud_msg;
00208 unsigned int grow_number;
00209
00210
00211
00212 public:
00213
00214
00215
00216
00217 c_polygon_primitive(ros::NodeHandle *node, const char* name="unamed", unsigned char r=0, unsigned char g=0, unsigned char b=0);
00218 ~c_polygon_primitive();
00219
00220
00221
00222
00223 int export_to_polygon_primitive_msg(polygon_primitive_msg::polygon_primitive* msg);
00224 int import_from_polygon_primitive_msg(polygon_primitive_msg::polygon_primitive* msg);
00225 int create_vizualization_msgs(visualization_msgs::MarkerArray* marker_vec, unsigned int id_start=0);
00226 visualization_msgs::Marker create_visualization_marker_header(
00227 std::string frame_id, ros::Time stamp, std::string name,
00228 int action, int id, int type,
00229 double px, double py, double pz,
00230 double qx, double qy, double qz, double qw,
00231 double sx, double sy, double sz,
00232 double cr, double cg, double cb, double alpha
00233 );
00234
00235
00236
00237
00238
00239 int print_polygon_information(void);
00240
00241 int compute_supporting_perpendicular_plane_ransac( pcl::PointCloud<pcl::PointXYZ> *pc_in,
00242 pcl::PointCloud<pcl::Normal> *n_in,
00243 double DistanceThreshold,
00244 double NormalDistanceWeight,
00245 int MaxIterations,
00246 pcl::PointIndices::Ptr ind_out,
00247 pcl::ModelCoefficients::Ptr coeff_out
00248 );
00249
00250 int compute_supporting_plane_ransac( pcl::PointCloud<pcl::PointXYZ> *input_cloud,
00251 pcl::PointCloud<pcl::Normal> *input_normals,
00252 double DistanceThreshold,
00253 double NormalDistanceWeight,
00254 int MaxIterations,
00255 pcl::PointIndices::Ptr indices,
00256 pcl::ModelCoefficients::Ptr coefficients
00257 );
00258
00259 int indices_extraction(pcl::PointIndices::Ptr ind,
00260 pcl::PointCloud<pcl::PointXYZ> *input_cloud,
00261 pcl::PointCloud<pcl::PointXYZ> *remove_cloud,
00262 pcl::PointCloud<pcl::PointXYZ>::Ptr copy_cloud,
00263 pcl::PointCloud<pcl::Normal> *input_normals,
00264 pcl::PointCloud<pcl::Normal> *remove_normals,
00265 int compute_normals=1);
00266
00267 void project_pc_to_plane(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout);
00268
00269
00270
00271
00272 int polygon_create(pcl::PointCloud<pcl::PointXYZ> *input_cloud,
00273 pcl::PointCloud<pcl::Normal> *input_normals,
00274 double DistanceThreshold = 0.5,
00275 double NormalDistanceWeight = 0.5,
00276 int MaxIterations = 1000,
00277 int do_spatial_division=0
00278 );
00279
00280 void polygon_split(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ>::Ptr pcdumpster, pcl::ModelCoefficients::Ptr coeff);
00281
00282
00283 int polygon_expansion(pcl::PointCloud<pcl::PointXYZ> *input_cloud,
00284 double longitudinal_offset=0.2,
00285 double perpendicular_offset=0.3,
00286 pcl::PointCloud<pcl::Normal>* input_normals=NULL);
00287
00288
00289
00290
00291
00292 void compute_convex_hull(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout);
00293
00294 void compute_convex_hull_cgal(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, tf::Transform *tr, double &area, double &solidity, bool flg=false);
00295
00296 void compute_convex_hull_cgal(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, tf::Transform *tr);
00297
00298 void compute_concave_hull(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, const pcl::ModelCoefficients::Ptr coeff);
00299
00300
00301
00302
00303 private:
00304
00305
00306
00307
00308 int _polygon_expansion(pcl::PointCloud<pcl::PointXYZ> *input_cloud,
00309 double longitudinal_offset,
00310 double perpendicular_offset,
00311 pcl::PointCloud<pcl::Normal>* input_normals);
00312
00313
00314
00315
00316
00317
00318 void set_names(const char* s);
00319
00320
00321 void allocate_space(void);
00322 double compute_polygon_area(const polygon_3d<pcl::PointXYZ>::Ptr pcin);
00323
00324 void normalize_vector(double *v);
00325
00332 void copy(pcl::ModelCoefficients::Ptr in, pcl::ModelCoefficients::Ptr out)
00333 {
00334 out->values[0] = in->values[0];
00335 out->values[1] = in->values[1];
00336 out->values[2] = in->values[2];
00337 out->values[3] = in->values[3];
00338 }
00339
00346 void copy(const t_reference_frame *in, t_reference_frame *out)
00347 {
00348 out->origin.x = in->origin.x; out->origin.y = in->origin.y; out->origin.z = in->origin.z;
00349 out->arrow_x.x = in->arrow_x.x; out->arrow_x.y = in->arrow_x.y; out->arrow_x.z = in->arrow_x.z;
00350 out->arrow_y.x = in->arrow_y.x; out->arrow_y.y = in->arrow_y.y; out->arrow_y.z = in->arrow_y.z;
00351 out->arrow_z.x = in->arrow_z.x; out->arrow_z.y = in->arrow_z.y; out->arrow_z.z = in->arrow_z.z;
00352 out->transform = in->transform;
00353 }
00354
00355 double fit_plane_to_two_pc_and_ratio(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin1, pcl::PointCloud<pcl::PointXYZ>::Ptr pcin2, double ratio, pcl::ModelCoefficients::Ptr plane);
00356
00357 void project_point_to_plane(const pcl::PointXYZ *ptin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointXYZ *ptout);
00358
00359 bool check_if_point_lies_on_plane(const pcl::ModelCoefficients::Ptr plane, const pcl::PointXYZ *point);
00360
00361 int check_plane_normal_orientation(pcl::ModelCoefficients::Ptr plane, pcl::PointXYZ *ptin, double vx, double vy, double vz);
00362
00363 void compute_arrow_points_from_transform(t_reference_frame *frame);
00364
00365 void create_reference_frame_from_plane_and_two_points(
00366 pcl::ModelCoefficients::Ptr plane,
00367 pcl::PointXYZ *pt1,
00368 pcl::PointXYZ *pt2,
00369 t_reference_frame *frame
00370 );
00371
00372 void set_reference_systems(void);
00373
00374 void refine_plane_coefficients(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::ModelCoefficients::Ptr coeff);
00375
00376
00377
00378
00379
00380 double fit_plane_to_pc(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::ModelCoefficients::Ptr plane);
00381
00382
00383
00384
00385 void publish_local_tf(void);
00386
00387
00388
00389
00390 void offset_polygon(double val, const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, tf::Transform *tr);
00391 };
00392 #endif
00393