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_2dhulls_CPP_
00037 #define _polygon_primitive_2dhulls_CPP_
00038
00039
00040 #include "polygon_primitive.h"
00041
00042 #include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
00043 #include <CGAL/convex_hull_2.h>
00044 #include<CGAL/Polygon_2.h>
00045
00053 void c_polygon_primitive::compute_convex_hull(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, const pcl::ModelCoefficients::Ptr coeff, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout)
00054 {
00055
00056
00057
00058
00059 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_projected = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00060
00061
00062 project_pc_to_plane(pcin, coeff, pc_projected);
00063
00064
00065 pcl::ConvexHull<pcl::PointXYZ> chull;
00066 chull.setInputCloud(pc_projected);
00067 chull.reconstruct(*pcout);
00068 pcout->width = pcin->width;
00069 pcout->height = pcin->height;
00070 pcout->header.frame_id = pcin->header.frame_id;
00071
00072 pc_projected.reset();
00073 }
00074
00085 void c_polygon_primitive::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)
00086 {
00087 double area,solidity;
00088 compute_convex_hull_cgal(pcin, coeff, pcout, tr, area, solidity);
00089 }
00090
00091
00092 void c_polygon_primitive::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)
00093 {
00094
00095
00096
00097
00098 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_projected = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00099 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_local = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00100 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_ch_local = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00101
00102
00103 project_pc_to_plane(pcin, coeff, pc_projected);
00104
00105 if(flg)
00106 {
00107 pointclouds.projected = pc_projected;
00108 }
00109
00110
00111
00112
00113 pcl_ros::transformPointCloud(*pc_projected, *pc_local, data.frames.current.transform.inverse());
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130 std::vector<CGAL::Exact_predicates_inexact_constructions_kernel::Point_2> pts;
00131
00132
00133 for (int i=0; i< (int) pc_local->size(); i++)
00134 {
00135 pts.push_back(CGAL::Exact_predicates_inexact_constructions_kernel::Point_2(pc_local->points[i].x, pc_local->points[i].y));
00136 }
00137
00138
00139 std::vector<CGAL::Exact_predicates_inexact_constructions_kernel::Point_2> pts_ch;
00140
00141
00142 area = compute_polygon_area(pc_ch_local);
00143 data.hulls.convex.solidity = (double)(pcin->points.size())/area;
00144
00145
00146
00147 CGAL::convex_hull_2( pts.begin(), pts.end(),std::back_inserter(pts_ch));
00148
00149
00150
00151 for (int t = 0; t<(int)pts_ch.size(); t++ )
00152 {
00153 pc_ch_local->points.push_back(pcl::PointXYZ(pts_ch[t].x(), pts_ch[t].y(),0.0));
00154 }
00155
00156
00157 data.hulls.convex.area = compute_polygon_area(pc_ch_local);
00158 data.hulls.convex.solidity = (double)(pointclouds.all->points.size())/data.hulls.convex.area;
00159
00160
00161
00162
00163 pcl_ros::transformPointCloud(*pc_ch_local, *pcout, data.frames.current.transform);
00164
00165 pc_projected.reset();
00166 pc_local.reset();
00167 pc_ch_local.reset();
00168 }
00169
00177 double c_polygon_primitive::compute_polygon_area(const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin)
00178 {
00179
00180 CGAL::Polygon_2<CGAL::Exact_predicates_inexact_constructions_kernel> star;
00181
00182
00183
00184 for (int i=0; i< (int) pcin->size(); i++)
00185 {
00186 star.push_back(CGAL::Exact_predicates_inexact_constructions_kernel::Point_2(
00187 pcin->points[i].x,
00188 pcin->points[i].y));
00189 }
00190
00191 return fabs(star.area());
00192
00193 }
00194
00201 void c_polygon_primitive::compute_concave_hull(pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, const pcl::ModelCoefficients::Ptr coeff)
00202 {
00203
00204 pcl::PointCloud<pcl::PointXYZ>::Ptr pctmp (new pcl::PointCloud<pcl::PointXYZ>);
00205 pcl::PointCloud<pcl::PointXYZ>::Ptr voronoi_centers (new pcl::PointCloud<pcl::PointXYZ>);
00206
00207 pcl::PointCloud<pcl::PointXYZ>::Ptr pc_projected = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00208
00209
00210 project_pc_to_plane(pcin, coeff, pc_projected);
00211
00212
00213 std::vector< pcl::Vertices > V;
00214 pcl::ConcaveHull<pcl::PointXYZ> chull;
00215 chull.setInputCloud(pc_projected);
00216 chull.setAlpha(6.9);
00217
00218
00219
00220 chull.reconstruct(*pctmp, V);
00221 pctmp->width = pcin->width;
00222 pctmp->header.frame_id = pcin->header.frame_id;
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233 pcout->points.erase(pcout->points.begin(), pcout->points.end());
00234
00235 int i=0;
00236 int v=0;
00237 for (std::vector<pcl::Vertices>::iterator vit=V.begin(); vit != V.end(); vit++)
00238 {
00239 i=0;
00240 for (std::vector<uint32_t>::iterator it=V[v].vertices.begin(); it != V[v].vertices.end(); it++)
00241 {
00242 pcl::PointXYZ p;
00243 p.x = pctmp->points[V[v].vertices[i]].x;
00244 p.y = pctmp->points[V[v].vertices[i]].y;
00245 p.z = pctmp->points[V[v].vertices[i]].z;
00246
00247 pcout->points.push_back(p);
00248 i++;
00249 }
00250 v++;
00251 }
00252
00253
00254 pcout->header.frame_id = pctmp->header.frame_id;
00255 pcout->width = pcout->points.size();
00256 pcout->height = 1;
00257
00258
00259 }
00260 #endif
00261