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_offsetpolygon_CPP_
00037 #define _polygon_primitive_offsetpolygon_CPP_
00038 
00039 #include "polygon_primitive.h"
00040 
00041 #include<CGAL/basic.h>
00042 #include<CGAL/Cartesian.h>
00043 #include<CGAL/Polygon_2.h>
00044 #include<CGAL/Exact_predicates_inexact_constructions_kernel.h>
00045 #include<CGAL/Straight_skeleton_builder_2.h>
00046 #include<CGAL/Polygon_offset_builder_2.h>
00047 #include<CGAL/compute_outer_frame_margin.h>
00048 #include <CGAL/Cartesian.h>
00049 #include <CGAL/Polygon_2.h>
00050 
00051 
00052 typedef CGAL::Exact_predicates_inexact_constructions_kernel Kernel;
00053 
00054 typedef Kernel::Point_2 Point_2;
00055 typedef CGAL::Polygon_2<Kernel>    Contour;
00056 typedef boost::shared_ptr<Contour> ContourPtr;
00057 typedef std::vector<ContourPtr>    ContourSequence ;
00058 
00059 typedef CGAL::Straight_skeleton_2<Kernel> Ss;
00060 
00061 typedef Ss::Halfedge_iterator Halfedge_iterator;
00062 typedef Ss::Halfedge_handle   Halfedge_handle;
00063 typedef Ss::Vertex_handle     Vertex_handle;
00064 
00065 typedef CGAL::Straight_skeleton_builder_traits_2<Kernel>      SsBuilderTraits;
00066 typedef CGAL::Straight_skeleton_builder_2<SsBuilderTraits,Ss> SsBuilder;
00067 
00068 typedef CGAL::Polygon_offset_builder_traits_2<Kernel>                  OffsetBuilderTraits;
00069 typedef CGAL::Polygon_offset_builder_2<Ss,OffsetBuilderTraits,Contour> OffsetBuilder;
00070 
00071 
00080 void c_polygon_primitive::offset_polygon(double offset, const pcl::PointCloud<pcl::PointXYZ>::Ptr pcin, pcl::PointCloud<pcl::PointXYZ>::Ptr pcout, tf::Transform *tr)
00081         
00082 {
00083         
00084 
00085         pcl::PointCloud<pcl::PointXYZ>::Ptr pc_local = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00086         pcl::PointCloud<pcl::PointXYZ>::Ptr pc_local_extended = pcl::PointCloud<pcl::PointXYZ>::Ptr(new pcl::PointCloud<pcl::PointXYZ>);
00087 
00088         
00089         
00090         
00091         
00092 
00093         
00094         pcl_ros::transformPointCloud(*pcin, *pc_local,  data.frames.current.transform.inverse());
00095 
00096         
00097         for (int i=0; i< (int) pc_local->size(); i++)
00098         {
00099                 if (pc_local->points[i].z>0.01 || pc_local->points[i].z<-0.01)
00100                 {
00101                         
00102                         
00103                         
00104                 }
00105         }
00106 
00107         
00108         Contour mypol;
00109 
00110 
00111         for (int i=0; i< (int) pc_local->size(); i++) 
00112         {
00113                 mypol.push_back(Point_2(pc_local->points[i].x, pc_local->points[i].y));
00114         }
00115 
00116 
00117 
00118 
00119         if(!mypol.is_simple())
00120         {
00121                 int keep_trying=1;
00122 
00123                 while(keep_trying)
00124                 {
00125 
00126                         int tt=0;
00127                         double prev_x=-999999, prev_y=-999999;
00128                         
00129 
00130                         int tttt=0;
00131                         for (Contour::Vertex_const_iterator j = mypol.vertices_begin(); j != mypol.vertices_end(); ++ j )
00132                         {
00133                                 
00134                                 tttt++;
00135                         }
00136 
00137 
00138                         Contour::Vertex_const_iterator begin = mypol.vertices_begin();
00139                         Contour::Vertex_const_iterator end = --mypol.vertices_end();
00140                         if ( begin->x() == end->x() && begin->y() == end->y())
00141                         {
00142                                 
00143                                 mypol.erase(end);       
00144                         }       
00145 
00146 
00147                         for (Contour::Vertex_const_iterator j = mypol.vertices_begin(); j != mypol.vertices_end(); ++ j )
00148                         {
00149                                 if(tt!=0)
00150                                 {
00151                                         if (prev_x==j->x() && prev_y==j->y())
00152                                         {
00153                                                 
00154                                                 mypol.erase(j); 
00155                                                 break;
00156                                         }
00157                                         else
00158                                         {
00159                                                 prev_x = j->x();        
00160                                                 prev_y = j->y();        
00161                                         }
00162 
00163                                 }
00164                                 else
00165                                 {
00166                                         prev_x = j->x();        
00167                                         prev_y = j->y();        
00168                                 }
00169 
00170 
00171                                 
00172                                 tt++;
00173                         }
00174 
00175 
00176                         
00177 
00178                         int ttt=0;
00179                         for (Contour::Vertex_const_iterator j = mypol.vertices_begin(); j != mypol.vertices_end(); ++ j )
00180                         {
00181                                 
00182                                 ttt++;
00183                         }
00184 
00185                         if (mypol.is_simple()) keep_trying=0;
00186 
00187 
00188                 }
00189         }
00190 
00191 
00192         if(!mypol.is_counterclockwise_oriented()) 
00193         {
00194                 
00195                 mypol.reverse_orientation();    
00196                 
00197         }
00198 
00199 
00200         
00201         std::vector<Point_2> star; 
00202 
00203 
00204         int t=0;
00205         for (Contour::Vertex_const_iterator j = mypol.vertices_begin(); j != mypol.vertices_end(); ++ j )
00206         {
00207 
00208                 pc_local->points[t].x =  j->x();
00209                 pc_local->points[t].y =  j->y();
00210                 pc_local->points[t].z = 0; 
00211                 t++;
00212         }
00213 
00214 
00215 
00216 
00217         
00218         for (int i=0; i< (int) pc_local->size(); i++)
00219         {
00220                 star.push_back(Point_2(pc_local->points[i].x, pc_local->points[i].y));
00221         }
00222 
00223 
00224 
00225         
00226         
00227         
00228         
00229         
00230         
00231 
00232         
00233         
00234         boost::optional<double> margin = CGAL::compute_outer_frame_margin(star.begin(),star.end(), offset);
00235 
00236 
00237 
00238         
00239         if ( margin )
00240         {
00241                 
00242                 CGAL::Bbox_2 bbox = CGAL::bbox_2(star.begin(),star.end());
00243 
00244                 
00245                 double fxmin = bbox.xmin() - *margin ;
00246                 double fxmax = bbox.xmax() + *margin ;
00247                 double fymin = bbox.ymin() - *margin ;
00248                 double fymax = bbox.ymax() + *margin ;
00249 
00250                 
00251                 Point_2 frame[4]= { Point_2(fxmin,fymin)
00252                         , Point_2(fxmax,fymin)
00253                                 , Point_2(fxmax,fymax)
00254                                 , Point_2(fxmin,fymax)
00255                 } ;
00256 
00257 
00258 
00259                 
00260                 SsBuilder ssb ;  
00261 
00262 
00263                 
00264                 ssb.enter_contour(frame,frame+4);
00265 
00266 
00267 
00268                 
00269                 ssb.enter_contour(star.rbegin(),star.rend());
00270 
00271 
00272 
00273                 
00274                 boost::shared_ptr<Ss> ss = ssb.construct_skeleton();
00275 
00276 
00277 
00278                 
00279                 if ( ss )
00280                 {
00281                         
00282                         ContourSequence offset_contours ;
00283 
00284 
00285                         
00286                         OffsetBuilder ob(*ss);
00287 
00288 
00289                         
00290                         ob.construct_offset_contours(offset, std::back_inserter(offset_contours));
00291 
00292 
00293                         
00294                         
00295                         
00296                         ContourSequence::iterator f = offset_contours.end();
00297                         double lLargestArea = 0.0 ;  
00298 
00299                         for (ContourSequence::iterator i = offset_contours.begin(); i != offset_contours.end(); ++ i  )
00300                         {
00301 
00302                                 double lArea = CGAL_NTS abs( (*i)->area() ) ; 
00303                                 if ( lArea > lLargestArea )
00304                                 {
00305                                         f = i ;
00306                                         lLargestArea = lArea ;
00307                                 }
00308                         }
00309 
00310 
00311                         
00312                         offset_contours.erase(f);
00313 
00314 
00315                         
00316                         Halfedge_handle null_halfedge ;
00317                         Vertex_handle   null_vertex ;
00318 
00319 
00320 
00321                         
00322                         
00323                         
00324                         
00325                         
00326                         
00327                         
00328                         
00329 
00330                         
00331 
00332                         
00333 
00334 
00335                         for (ContourSequence::const_iterator i = offset_contours.begin(); i != offset_contours.end(); ++ i )
00336                         {
00337                                 
00338                                 
00339                                 pc_local_extended->points.resize((*i)->size());
00340                                 pc_local_extended->height=1;
00341                                 pc_local_extended->width=(*i)->size();
00342                                 int t=0;
00343 
00344                                 for (Contour::Vertex_const_iterator j = (*i)->vertices_begin(); j != (*i)->vertices_end(); ++ j )
00345                                 {
00346                                         
00347                                         pc_local_extended->points[t].x =  j->x();
00348                                         pc_local_extended->points[t].y =  j->y();
00349                                         pc_local_extended->points[t].z = 0; 
00350                                         t++;
00351                                 }
00352 
00353                                 break; 
00354                         }
00355                 }
00356         }
00357 
00358 
00359 
00360         
00361         
00362         pcl_ros::transformPointCloud(*pc_local_extended, *pcout,  data.frames.current.transform);
00363 
00364 
00365         
00366         pc_local.reset();
00367         pc_local_extended.reset();      
00368 
00369 } 
00370 
00371 
00372 
00373 
00374 
00375 #endif
00376 
00379