quad_regression_algo.h
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2011
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_vision
00012  * ROS package name: dynamic_tutorials
00013  * Description:
00014  *
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *
00017  * Author: josh
00018  *
00019  * Date of creation: Oct 26, 2011
00020  * ToDo:
00021  *
00022  *
00023  *
00024  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00025  *
00026  * Redistribution and use in source and binary forms, with or without
00027  * modification, are permitted provided that the following conditions are met:
00028  *
00029  *     * Redistributions of source code must retain the above copyright
00030  *       notice, this list of conditions and the following disclaimer.
00031  *     * Redistributions in binary form must reproduce the above copyright
00032  *       notice, this list of conditions and the following disclaimer in the
00033  *       documentation and/or other materials provided with the distribution.
00034  *     * Neither the name of the Fraunhofer Institute for Manufacturing
00035  *       Engineering and Automation (IPA) nor the names of its
00036  *       contributors may be used to endorse or promote products derived from
00037  *       this software without specific prior written permission.
00038  *
00039  * This program is free software: you can redistribute it and/or modify
00040  * it under the terms of the GNU Lesser General Public License LGPL as
00041  * published by the Free Software Foundation, either version 3 of the
00042  * License, or (at your option) any later version.
00043  *
00044  * This program is distributed in the hope that it will be useful,
00045  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00046  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00047  * GNU Lesser General Public License LGPL for more details.
00048  *
00049  * You should have received a copy of the GNU Lesser General Public
00050  * License LGPL along with this program.
00051  * If not, see <http://www.gnu.org/licenses/>.
00052  *
00053  ****************************************************************/
00054 
00055 #ifndef QUAD_REGRESSION_ALGO_H_
00056 #define QUAD_REGRESSION_ALGO_H_
00057 
00058 #include <pcl/kdtree/kdtree_flann.h>
00059 #include "../general_segmentation.h"
00060 
00061 #define USE_MIN_MAX_RECHECK_
00062 #define STOP_TIME
00063 //#define BACK_CHECK_REPEAT
00064 #define DO_NOT_DOWNSAMPLE_
00065 //#define SIMULATION_
00066 //#define MIN_EIGEN_VECTOR
00067 //#define EVALUATE
00068 //#define USE_BOOST_POLYGONS_
00069 
00070 #include "polygon.h"
00071 
00072 namespace Segmentation
00073 {
00074 
00075   namespace QPPF
00076   {
00077 
00084     template<typename Point>
00085     class CameraModel_Kinect {
00086     public:
00087       float f,dx,dy;
00088 
00089       CameraModel_Kinect(): f(0.f) {}
00090 
00092       void getParams(const pcl::PointCloud<Point> &pc);
00093 
00094       inline static float std(const float dist) {return 0.0075f+0.001425f*dist*dist;}   //after "Accuracy analysis of kinect depth data"
00095 
00097       template<typename APoint>
00098       friend std::ostream &operator<<(ostream &os, const CameraModel_Kinect<APoint> &cmk);
00099     };
00100 
00107     template<typename Point>
00108     class CameraModel_SR4500 {
00109     public:
00110       float f,dx,dy;
00111 
00112       CameraModel_SR4500(): f(0.f) {}
00113 
00115       void getParams(const pcl::PointCloud<Point> &pc);
00116 
00117       inline static float std(const float dist) {return 0.00015f+0.00015f*dist;}   //after "Accuracy analysis of kinect depth data"
00118 
00120       template<typename APoint>
00121       friend std::ostream &operator<<(ostream &os, const CameraModel_Kinect<APoint> &cmk);
00122     };
00123 
00124     template<typename Point>
00125     std::ostream &operator<<(ostream &os, const CameraModel_Kinect<Point> &cmk) {
00126       os<<"Kinect Camera\n";
00127       os<<"f = "<<cmk.f<<std::endl;
00128       os<<"dx = "<<cmk.dx<<std::endl;
00129       os<<"dy = "<<cmk.dy<<std::endl;
00130       return os;
00131     }
00132 
00136     template <int Degree, typename Point, typename CameraModel>
00137     class QuadRegression
00138     {
00139     protected:
00140 
00142       inline int getInd(const int i, const int x, const int y) const {
00143         return (x)+(y)*levels_[i].w;
00144       }
00145 
00147       inline int getIndPC(const int w, const int x, const int y) const {
00148         return (x)+(y)*w;
00149       }
00150 
00152       inline int isOccupied(const int i, const int x, const int y) const {
00153         if(i>=(int)levels_.size())
00154           return -1;
00155         if(levels_[i].data[getInd(i,x,y)].occopied>=0)
00156           return levels_[i].data[getInd(i,x,y)].occopied;
00157         return isOccupied(i+1,x/2,y/2);
00158       }
00159 
00160       //------------MEMBERS---------------
00161       boost::shared_ptr<const pcl::PointCloud<Point> > input_;          
00162       std::vector<SubStructure::ParamC<Degree> > levels_;               
00163       std::vector<Segmentation::S_POLYGON<Degree> > polygons_;          
00164 
00165 #ifdef STOP_TIME
00166       // evaluation variables
00167       double execution_time_quadtree_, execution_time_growing_, execution_time_polyextraction_;
00168 #endif
00169 
00170       enum {DEGREE=Degree};             // constant for degree (1=linear)
00171 
00172     private:
00173       //-----------CONSTANTS-------------
00174       const unsigned int MIN_LOD;       
00175       const unsigned int FINAL_LOD;     
00176       const unsigned int GO_DOWN_TO_LVL;
00177 
00178       //------------MEMBERS---------------
00179       CameraModel camera_;              
00180 
00181       int *ch_; 
00182 
00183       bool *outline_check_;             
00184       size_t outline_check_size_;       
00185       float filter_;                    
00186       bool only_planes_;                
00187 
00188       void grow(SubStructure::Model<Degree> &model, const int i, const int x, const int y);
00189       void grow(SubStructure::VISITED_LIST<SubStructure::SVALUE> &list, SubStructure::Model<Degree> &model, const int i, const int mark, bool first_lvl);
00190 
00191       inline bool filterOccupied(const int i, const int x, const int y, const int mark) const {
00192         if(i>=(int)levels_.size())
00193           return false;
00194         if(levels_[i].data[getInd(i,x,y)].occopied==mark)
00195           return true;
00196         return filterOccupied(i+1,x/2,y/2,mark);
00197       }
00198 
00199       inline int otherOccupied(const int i, const int x, const int y, const int mark) const {
00200         if(i>=(int)levels_.size() || x<0 || y<0 || x>=(int)levels_[i].w || y>=(int)levels_[i].h)
00201           return -1;
00202         if(levels_[i].data[getInd(x,y)].occopied>=0 && levels_[i].data[getInd(x,y)].occopied!=mark)
00203           return levels_[i].data[getInd(x,y)].occopied;
00204         return otherOccupied(i+1,x/2,y/2,mark);
00205       }
00206 
00207       /*inline bool criternion(const SubStructure::Model<Degree> &model, const SubStructure::Param<Degree> &data, const int i) const {
00208         f
00209       }*/
00210 
00211       /*inline bool checkModelAt(const SubStructure::Model<Degree> &model, const int i, const int x, const int y, const float thr) const {
00212         if(i==0)
00213           return model.check_tangent(levels_[i].data[getInd(i,x,y)], thr);
00214 
00215         return //model.check(levels_[i].data[getInd(x,y)], thr) &&
00216             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x,2*y)], thr) &&
00217             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x,2*y+1)], thr) &&
00218             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x+1,2*y)], thr) &&
00219             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x+1,2*y+1)], thr);
00220       }*/
00221 
00222       inline bool checkModelAt(const SubStructure::Model<Degree> &model, const int i, const int x, const int y) const {
00223         if(i==0)
00224           return model.check_tangent(levels_[0].data[getInd(0,x,y)], 1.5f*camera_.std(levels_[0].data[getInd(0,x,y)].z_(0)/levels_[0].data[getInd(0,x,y)].model_(0,0)));
00225 
00226         return //model.check(levels_[i].data[getInd(x,y)], thr) &&
00227             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x,2*y)], 1.5f*camera_.std(levels_[i-1].data[getInd(i-1,2*x,2*y)].z_(0)/levels_[i-1].data[getInd(i-1,2*x,2*y)].model_(0,0))) &&
00228             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x,2*y+1)], 1.5f*camera_.std(levels_[i-1].data[getInd(i-1,2*x,2*y+1)].z_(0)/levels_[i-1].data[getInd(i-1,2*x,2*y+1)].model_(0,0))) &&
00229             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x+1,2*y)], 1.5f*camera_.std(levels_[i-1].data[getInd(i-1,2*x+1,2*y)].z_(0)/levels_[i-1].data[getInd(i-1,2*x+1,2*y)].model_(0,0))) &&
00230             model.check_tangent(levels_[i-1].data[getInd(i-1,2*x+1,2*y+1)], 1.5f*camera_.std(levels_[i-1].data[getInd(i-1,2*x+1,2*y+1)].z_(0)/levels_[i-1].data[getInd(i-1,2*x+1,2*y+1)].model_(0,0)));
00231       }
00232 
00233       inline void addPoint(const int i, const int x, const int y, const int mark, S_POLYGON<Degree> &poly, const SubStructure::Model<Degree> &model, const float v=0.f) {
00234 
00235 #if 0
00236         for(int xx=-1; xx<2; xx++)
00237           for(int yy=-1; yy<2; yy++)
00238             if(x+xx>=0 && y+yy>=0 && x+xx<(int)levels_[i].w && y+yy<(int)levels_[i].h
00239                 && filterOccupied(i,x+xx,y+yy,mark) //&& (levels_[i].data[getInd(x+xx,y+yy)].occopied==mark||levels_[i+1].data[getInd3((x+xx)/2,(y+yy)/2)].occopied==mark)
00240         //&& poly.model_.check_tangent(levels_[i].data[getInd(x+xx,y+yy)],0.02f)
00241             ){
00242               Eigen::Vector3f p;
00243               p(0) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,1)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00244               p(1) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,3)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00245               p(2) = levels_[i].data[getInd(x+xx,y+yy)].z_(0)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00246 
00247 
00248               //            Eigen::Vector3f p = poly.project2plane(levels_[i].data[getInd(x+xx,y+yy)].model_(0,1)/levels_[i].data[getInd(x+xx,y+yy)].z_(0),
00249               //                                                   levels_[i].data[getInd(x+xx,y+yy)].model_(0,3)/levels_[i].data[getInd(x+xx,y+yy)].z_(0),
00250               //                                                   model,v);
00251 
00252               p.head<2>() = poly.nextPoint(p);
00253               /*
00254 Eigen::Vector2f vv;
00255       vv(0) = (p-poly.param_.col(0)).dot(poly.proj2plane_.col(0))/poly.proj2plane_.col(0).squaredNorm();
00256       vv(1) = (p-poly.param_.col(0)).dot(poly.proj2plane_.col(1))/poly.proj2plane_.col(1).squaredNorm();
00257             p.head<2>() = vv;*/
00258 
00259               if(!pcl_isfinite(p.sum())) continue;
00260               p(2) = v;
00261               poly.segments_.back().push_back(p);
00262               return;
00263             }
00264         for(int xx=-1; xx<2; xx++)
00265           for(int yy=-1; yy<2; yy++)
00266             if(x+xx>=0 && y+yy>=0 && x+xx<(int)levels_[i].w && y+yy<(int)levels_[i].h
00267                 && poly.model_.check_tangent(levels_[i].data[getInd(x+xx,y+yy)],0.02f)){
00268               Eigen::Vector3f p;
00269               p(0) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,1)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00270               p(1) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,3)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00271               p(2) = levels_[i].data[getInd(x+xx,y+yy)].z_(0)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00272               /*            p.head<2>() = poly.nextPoint(p);
00273 
00274 Eigen::Vector2f vv;
00275       vv(0) = (p-poly.param_.col(0)).dot(poly.proj2plane_.col(0))/poly.proj2plane_.col(0).squaredNorm();
00276       vv(1) = (p-poly.param_.col(0)).dot(poly.proj2plane_.col(1))/poly.proj2plane_.col(1).squaredNorm();
00277             p.head<2>() = vv;
00278                */
00279               if(!pcl_isfinite(p.sum())) continue;
00280               p(2) = v;
00281               poly.segments_.back().push_back(p);
00282               return;
00283             }
00284 
00285         //      for(int xx=-2; xx<3; xx++)
00286         //        for(int yy=-2; yy<3; yy++)
00287         //          if(x+xx>=0 && y+yy>=0 && x+xx<levels_[i].w && y+yy<levels_[i].h && levels_[i].data[getInd(x+xx,y+yy)].occopied==mark){
00288         //            Eigen::Vector3f p;
00289         //            p(0) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,1)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00290         //            p(1) = levels_[i].data[getInd(x+xx,y+yy)].model_(0,3)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00291         //            p(2) = levels_[i].data[getInd(x+xx,y+yy)].z_(0)/levels_[i].data[getInd(x+xx,y+yy)].model_(0,0);
00292         //            //p.head<2>() = poly.nextPoint(p);
00293         //
00294         //            p.head<2>() -= poly.getCenter();
00295         //            p(0)/=poly.proj2plane_(0,0);
00296         //            p(1)/=poly.proj2plane_(1,1);
00297         //
00298         //            if(!pcl_isfinite(p.sum())) continue;
00299         //            p(2) = v;
00300         //            poly.segments_.back().push_back(p);
00301         //            return;
00302         //          }
00303 #endif
00304 
00305 #ifdef DO_NOT_DOWNSAMPLE_
00306         const int fact=1;
00307 #else
00308         const int fact=2;
00309 #endif
00310 
00311         /*{
00312         Eigen::Vector3f p = poly.project2plane(((x<<(i+fact-1))-kinect_params_.dx)/kinect_params_.f,
00313                                                ((y<<(i+fact-1))-kinect_params_.dy)/kinect_params_.f,
00314                                                model,v);
00315       poly.segments_.back().push_back(p);
00316 #ifdef USE_BOOST_POLYGONS_
00317 poly.segments2d_.back().push_back(BoostPoint(x,y));
00318 #elif defined(BACK_CHECK_REPEAT)
00319 Eigen::Vector2i p2;
00320 p2(0) = x;
00321 p2(1) = y;
00322 poly.segments2d_.back().push_back(p2);
00323 #endif
00324       }
00325       return;*/
00326 
00327         Eigen::Vector3f p = poly.project2plane(((x<<(i+fact-1))-camera_.dx)/camera_.f,
00328                                                ((y<<(i+fact-1))-camera_.dy)/camera_.f,
00329                                                model,v);
00330 #if 1
00331         bool found = false;
00332         const float thr = 9*camera_.std(p(2))*camera_.std(p(2));
00333         Eigen::Vector3f vp = poly.project2world(p.head<2>());
00334 
00335         static const int rel_motion_pattern[][2] = { {0,0}, {-1,-1}, {-1,0}, {-1,1}, {0,-1}, {0,1}, {1,-1}, {1,0}, {1,1}
00336         , {-2,-2}, {-2,-1}, {-2,0}, {-2,1}, {-2,2}, {-1,-2}, {-1,2}, {0,-2}, {0,2}, {1,-2}, {1,2}, {2,-2}, {2,-1}, {2,0}, {2,1}, {2,2}
00337         //, {-3,-3}, {-3,-2}, {-3,-1}, {-3,0}, {-3,1}, {-3,2}, {-3,3}, {-2,-3}, {-2,3}, {-1,-3}, {-1,3}, {0,-3}, {0,3}, {1,-3}, {1,3}, {2,-3}, {2,3}, {3,-3}, {3,-2}, {3,-1}, {3,0}, {3,1}, {3,2}, {3,3}, {-4,-4}, {-4,-3}, {-4,-2}, {-4,-1}, {-4,0}, {-4,1}, {-4,2}, {-4,3}, {-4,4}, {-3,-4}, {-3,4}, {-2,-4}, {-2,4}, {-1,-4}, {-1,4}, {0,-4}, {0,4}, {1,-4}, {1,4}, {2,-4}, {2,4}, {3,-4}, {3,4}, {4,-4}, {4,-3}, {4,-2}, {4,-1}, {4,0}, {4,1}, {4,2}, {4,3}, {4,4}
00338         };
00339 
00340         const pcl::PointCloud<Point> &pc = *input_;
00341         for(size_t j=0; j<sizeof(rel_motion_pattern)/sizeof(rel_motion_pattern[0]); j++) {
00342           int xx=rel_motion_pattern[j][0];
00343           int yy=rel_motion_pattern[j][1];
00344 
00345           if(x+xx>=0 && y+yy>=0 && x+xx<(int)pc.width && y+yy<(int)pc.height) {
00346 
00347             if( (vp-pc(x+xx,y+yy).getVector3fMap()).squaredNorm() < thr )
00348             {
00349               found = true;
00350               break;
00351             }
00352           }
00353         }
00354 
00355 
00356         if(found)
00357         {
00358           poly.segments_.back().push_back(p);
00359 #ifdef USE_BOOST_POLYGONS_
00360           poly.segments2d_.back().push_back(BoostPoint(x,y));
00361 #else
00362           Eigen::Vector2i p2;
00363           p2(0) = x;
00364           p2(1) = y;
00365           poly.segments2d_.back().push_back(p2);
00366 #endif
00367         }
00368 
00369 
00370 #else
00371 #ifndef EVALUATE
00372 
00373 #if 0
00374         poly.segments_.back().push_back(p);
00375 #ifdef USE_BOOST_POLYGONS_
00376         poly.segments2d_.back().push_back(BoostPoint(x,y));
00377 #elif defined(BACK_CHECK_REPEAT)
00378         Eigen::Vector2i p2;
00379         p2(0) = x;
00380         p2(1) = y;
00381         poly.segments2d_.back().push_back(p2);
00382 #endif
00383 
00384         return;
00385 #endif
00386 
00387         Eigen::Vector3f vp = poly.project2world(p.head<2>());
00388 
00389         float d = poly.middle_(2);
00390         d*=d;
00391 
00392         static const int rel_motion_pattern[][2] = { {0,0}, {-1,-1}, {-1,0}, {-1,1}, {0,-1}, {0,1}, {1,-1}, {1,0}, {1,1}
00393         //, {-2,-2}, {-2,-1}, {-2,0}, {-2,1}, {-2,2}, {-1,-2}, {-1,2}, {0,-2}, {0,2}, {1,-2}, {1,2}, {2,-2}, {2,-1}, {2,0}, {2,1}, {2,2}
00394         //, {-3,-3}, {-3,-2}, {-3,-1}, {-3,0}, {-3,1}, {-3,2}, {-3,3}, {-2,-3}, {-2,3}, {-1,-3}, {-1,3}, {0,-3}, {0,3}, {1,-3}, {1,3}, {2,-3}, {2,3}, {3,-3}, {3,-2}, {3,-1}, {3,0}, {3,1}, {3,2}, {3,3}, {-4,-4}, {-4,-3}, {-4,-2}, {-4,-1}, {-4,0}, {-4,1}, {-4,2}, {-4,3}, {-4,4}, {-3,-4}, {-3,4}, {-2,-4}, {-2,4}, {-1,-4}, {-1,4}, {0,-4}, {0,4}, {1,-4}, {1,4}, {2,-4}, {2,4}, {3,-4}, {3,4}, {4,-4}, {4,-3}, {4,-2}, {4,-1}, {4,0}, {4,1}, {4,2}, {4,3}, {4,4}
00395         };
00396 
00397 
00398         const pcl::PointCloud<Point> &pc = *input_;
00399         //      for(int xx=-4; xx<5; xx++)
00400         //        for(int yy=-4; yy<5; yy++)
00401         for(size_t j=0; j<sizeof(rel_motion_pattern)/sizeof(rel_motion_pattern[0]); j++) {
00402           int xx=rel_motion_pattern[j][0];
00403           int yy=rel_motion_pattern[j][1];
00404 
00405           if(fact*x+xx>=0 && fact*y+yy>=0 && fact*x+xx<(int)pc.width && fact*y+yy<(int)pc.height) {
00406             Eigen::Vector3f p = poly.project2plane((((fact*x+xx)<<(i))-camera_.dx)/camera_.f,
00407                                                    (((fact*y+yy)<<(i))-camera_.dy)/camera_.f,
00408                                                    model,v);
00409 
00410             if( (poly.project2world(p.head<2>())-pc[getIndPC(pc.width, fact*x+xx,fact*y+yy)].getVector3fMap()).squaredNorm()<std::max(0.0005f,0.0005f*d)
00411             && (poly.project2world(p.head<2>())-vp).squaredNorm()<0.02f)
00412             {
00413               poly.segments_.back().push_back(p);/*
00414           Eigen::Vector2f p = poly.nextPoint(pc[getIndPC(fact*x+xx,fact*y+yy)].getVector3fMap());
00415 
00416           if( (poly.project2world(p)-pc[getIndPC(fact*x+xx,fact*y+yy)].getVector3fMap()).squaredNorm()<std::max(0.0005f,0.0005f*d)
00417           && (poly.project2world(p)-vp).squaredNorm()<0.02f
00418           )
00419           {
00420             Eigen::Vector3f p3;
00421             p3.head<2>()=p;
00422             poly.segments_.back().push_back(p3);*/
00423 
00424               //            std::cout<<"P\n"<<poly.project2world(p.head<2>())<<"\n";
00425               //            std::cout<<"C\n"<<pc[getIndPC(2*x+xx,2*y+yy)].getVector3fMap()<<"\n";
00426 
00427 #ifdef USE_BOOST_POLYGONS_
00428               poly.segments2d_.back().push_back(BoostPoint(x,y));
00429 #else
00430               Eigen::Vector2i p2;
00431               p2(0) = x+xx/fact;
00432               p2(1) = y+yy/fact;
00433               poly.segments2d_.back().push_back(p2);
00434 #endif
00435 
00436               return;
00437             }
00438           }
00439 
00440         }
00441 #if 0
00442         for(int xx=-8; xx<9; xx++)
00443           for(int yy=-8; yy<9; yy++)
00444             if(fact*x+xx>=0 && fact*y+yy>=0 && fact*x+xx<(int)pc.width && fact*y+yy<(int)pc.height) {
00445               Eigen::Vector3f p = poly.project2plane((((fact*x+xx)<<(i))-kinect_params_.dx)/kinect_params_.f,
00446                                                      (((fact*y+yy)<<(i))-kinect_params_.dy)/kinect_params_.f,
00447                                                      model,v);
00448 
00449               if( (poly.project2world(p.head<2>())-pc[getIndPC(fact*x+xx,fact*y+yy)].getVector3fMap()).squaredNorm()<std::max(0.0005f,0.0005f*d)
00450               && (poly.project2world(p.head<2>())-vp).squaredNorm()<0.02f)
00451               {
00452                 poly.segments_.back().push_back(p);
00453 
00454                 //            std::cout<<"P\n"<<poly.project2world(p.head<2>())<<"\n";
00455                 //            std::cout<<"C\n"<<pc[getIndPC(2*x+xx,2*y+yy)].getVector3fMap()<<"\n";
00456 
00457                 //            std::cout<<"P\n"<<poly.project2world(p.head<2>())<<"\n";
00458                 //            std::cout<<"C\n"<<pc[getIndPC(2*x+xx,2*y+yy)].getVector3fMap()<<"\n";
00459 
00460 #ifdef USE_BOOST_POLYGONS_
00461                 poly.segments2d_.back().push_back(BoostPoint(x,y));
00462 #elif defined(BACK_CHECK_REPEAT)
00463                 Eigen::Vector2i p2;
00464                 p2(0) = x+xx/fact;
00465                 p2(1) = y+yy/fact;
00466                 poly.segments2d_.back().push_back(p2);
00467 #endif
00468 
00469                 return;
00470               }
00471             }
00472 #endif
00473 #endif
00474 
00475 const float zzz=poly.project2world(p.head<2>())(2);
00476 if(zzz>0.4f && zzz<8.f)
00477         if(poly.normalAt(p.head<2>())(2)>0.35f)
00478         {
00479           poly.segments_.back().push_back(p);
00480 #ifdef USE_BOOST_POLYGONS_
00481           poly.segments2d_.back().push_back(BoostPoint(x,y));
00482 #else
00483           Eigen::Vector2i p2;
00484           p2(0) = x;
00485           p2(1) = y;
00486           poly.segments2d_.back().push_back(p2);
00487 #endif
00488         }
00489 #endif
00490       }
00491 
00492       int getPos(int *ch, const int xx, const int yy, const int w, const int h);
00493 
00494       void outline(int *ch, const int w, const int h, std::vector<SubStructure::SXY> &out, const int i, S_POLYGON<Degree> &poly, const SubStructure::Model<Degree> &model, const int mark);
00495 
00496     public:
00498       QuadRegression();
00499 
00501       virtual ~QuadRegression() {
00502         delete [] ch_;
00503         delete [] outline_check_;
00504       }
00505 
00507       virtual void setInputCloud (const boost::shared_ptr<const pcl::PointCloud<Point> > &cloud)
00508       {
00509         input_ = cloud;
00510         if(levels_.size()==0)
00511           prepare(*cloud);
00512         camera_.getParams(*cloud);
00513       }
00514 
00515       virtual bool compute();
00516 
00518       const std::vector<Segmentation::S_POLYGON<Degree> > &getPolygons() const {return polygons_;}
00519 
00520       void setFilter(const float f) {filter_=f;}                
00521       void setOnlyPlanes(const bool b) {only_planes_=b;}        
00522 
00523       bool getFilter() const {return filter_;}                  
00524       bool getOnlyPlanes() const {return only_planes_;}         
00525 
00526       virtual void prepare(const pcl::PointCloud<Point> &pc);   
00527       virtual void buildTree(const pcl::PointCloud<Point> &pc); 
00528       void calc();                                              
00529       void back_check_repeat();                                 
00530 
00531 #ifdef STOP_TIME
00532       // for evaluation purposes
00533       void getExecutionTimes(double &quadtree, double &growing, double &extraction)
00534       {
00535         quadtree = execution_time_quadtree_;
00536         extraction = execution_time_polyextraction_;
00537         growing = execution_time_growing_ - extraction;
00538       }
00539 #endif
00540     };
00541 
00542 
00546     template <int Degree, typename Point, typename CameraModel>
00547     class QuadRegression_Downsampled : public QuadRegression<Degree, Point, CameraModel>
00548     {
00549       virtual void prepare(const pcl::PointCloud<Point> &pc);   
00550       virtual void buildTree(const pcl::PointCloud<Point> &pc); 
00551     };
00552 
00553 #include "impl/quad_regression_algo.hpp"
00554 
00555   }     //namespace QPPF
00556 }       //namespace Segmentation
00557 
00558 
00559 #endif /* QUAD_REGRESSION_ALGO_H_ */


cob_3d_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:03:03