quad_regression.hpp
Go to the documentation of this file.
00001 
00060 #include <cob_3d_segmentation/eval.h>
00061 #include "../sub_structures/labeling.h"
00062 #include "../sub_structures/debug.h"
00063 #include <pcl/conversions.h>
00064 #include <pcl_conversions/pcl_conversions.h>
00065 
00066 #ifdef DO_NOT_DOWNSAMPLE_
00067 #define SHIFT   0
00068 #else
00069 #define SHIFT   1
00070 #endif
00071 
00072 #define KDTREE pcl::KdTreeFLANN
00073 
00074   template <typename Point, typename PointLabel, typename Parent>
00075   void Segmentation_QuadRegression<Point,PointLabel,Parent>::back_check_repeat() {
00076 #ifdef BACK_CHECK_REPEAT
00077     for(size_t i=0; i<this->polygons_.size(); i++) {
00078       if(this->polygons_[i].segments_.size()<1) continue;
00079 
00080       //ROS_ERROR("start");
00081 
00082       for(size_t j=0; j<this->polygons_[i].segments2d_.size(); j++) {
00083 
00084         for(size_t k=0; k<this->polygons_[i].segments2d_[j].size(); k++)
00085         {
00086 
00087           Eigen::Vector2i start = this->polygons_[i].segments2d_[j][(k-1+this->polygons_[i].segments2d_[j].size())%this->polygons_[i].segments2d_[j].size()],
00088               end = this->polygons_[i].segments2d_[j][k], pos;
00089 
00090           const size_t n = std::max((size_t)1, (size_t)(sqrtf((end-start).squaredNorm())/5) );
00091           float prob = 0.f;
00092 
00093           //ROS_ERROR("n %d",n);
00094           //int m=0;
00095 
00096           for(size_t p=0; p<n; p++) {
00097             //pos
00098             pos = start + (end-start)*(p+1)/(float)(n+1);
00099 
00100             //ROS_ERROR("pos %d %d",pos(0),pos(1));
00101 
00102             if(pos(0)<0 || pos(1)<0 || pos(0)>=(int)levels_[0].w || pos(1)>=(int)levels_[0].h) continue;
00103 
00104             int o;
00105             for(int x=-12; x<=12; x+=3)
00106               for(int y=-12; y<=12; y+=3)
00107                 if( (o = otherOccupied(0, pos(0)+x, pos(1)+y, this->polygons_[i].mark_)) != -1)
00108                   break;
00109 
00110             if(o<0||o==this->polygons_[i].mark_) continue;
00111             //ROS_ERROR("o %d",o);
00112             //++m;
00113 
00114             //get here
00115             Eigen::Vector2f pHere = this->polygons_[i].project2plane(((pos(0)<<(SHIFT))-kinect_params_.dx)/kinect_params_.f,
00116                                                                ((pos(1)<<(SHIFT))-kinect_params_.dy)/kinect_params_.f,
00117                                                                this->polygons_[i].model_,0.f).head(2);
00118             Eigen::Vector3f vHere = this->polygons_[i].project2world(pHere), nHere = this->polygons_[i].normalAt(pHere);
00119 
00120             //get there
00121             Eigen::Vector2f pThere = this->polygons_[o].project2plane(((pos(0)<<(SHIFT))-kinect_params_.dx)/kinect_params_.f,
00122                                                                 ((pos(1)<<(SHIFT))-kinect_params_.dy)/kinect_params_.f,
00123                                                                 this->polygons_[o].model_,0.f).head(2);
00124             Eigen::Vector3f vThere = this->polygons_[o].project2world(pHere), nThere = this->polygons_[o].normalAt(pHere);
00125 
00126             const float d = std::min(vThere(2),vHere(2));
00127 
00128             prob += (
00129                 (vThere(2)-vHere(2))>0.01f*d*d && std::abs(nHere(2))>0.7f) ||
00130                 (std::abs(vThere(2)-vHere(2))<0.1f*d*d && nHere.dot(nThere)<0.8f)
00131                 ? 1.f:0.f;
00132           }
00133 
00134           this->polygons_[i].segments_[j][k](2) = prob/n;
00135           //ROS_ERROR("m %d",m);
00136 
00137         }
00138       }
00139     }
00140 
00141 #endif
00142   }
00143 
00144   template <typename Point, typename PointLabel, typename Parent>
00145   bool Segmentation_QuadRegression<Point,PointLabel,Parent>::compute() {
00146     if(!this->Parent::compute())
00147       return false;
00148 
00149 #ifdef BACK_CHECK_REPEAT
00150   back_check_repeat();
00151 #endif
00152     return true;
00153   }
00154 
00155   template <typename Point, typename PointLabel, typename Parent>
00156   boost::shared_ptr<const pcl::PointCloud<PointLabel> > Segmentation_QuadRegression<Point,PointLabel,Parent>::compute_labeled_pc()
00157   {
00158     typename pcl::PointCloud<PointLabel>::Ptr out(new pcl::PointCloud<PointLabel>);
00159 
00160     ROS_ASSERT(this->levels_.size()>1);
00161 
00162     out->width = this->levels_[0].w;
00163     out->height= this->levels_[0].h;
00164     out->resize(out->width*out->height);
00165 
00166     for(size_t x=0; x<this->levels_[0].w; x++)
00167     {
00168       for(size_t y=0; y<this->levels_[0].h; y++)
00169       {
00170         //position
00171         const int i=0;
00172         (*out)(x,y).x = this->levels_[0].data[this->getInd(i, x,y)].x();
00173         (*out)(x,y).y = this->levels_[0].data[this->getInd(i, x,y)].y();
00174         (*out)(x,y).z = this->levels_[0].data[this->getInd(i, x,y)].z();
00175 
00176         //color/label
00177         int mark = this->isOccupied(0,x,y);
00178         SetLabeledPoint<PointLabel>( (*out)(x,y), mark);
00179 #ifdef SICK
00180         (*out)(x,y).intensity = (*input_)(x,y).intensity;
00181         (*out)(x,y).label = mark;
00182 #endif
00183       }
00184     }
00185 
00186     return out;
00187   }
00188 
00189   template <typename Point, typename PointLabel, typename Parent>
00190   boost::shared_ptr<const pcl::PointCloud<PointLabel> > Segmentation_QuadRegression<Point,PointLabel,Parent>::compute_reconstructed_pc()
00191   {
00192     typename pcl::PointCloud<PointLabel>::Ptr out(new pcl::PointCloud<PointLabel>);
00193 
00194     ROS_ASSERT(this->levels_.size()>0);
00195 
00196     out->width = this->levels_[0].w;
00197     out->height= this->levels_[0].h;
00198     out->resize(out->width*out->height);
00199 
00200     for(size_t x=0; x<this->levels_[0].w; x++)
00201     {
00202       for(size_t y=0; y<this->levels_[0].h; y++)
00203       {
00204         //position
00205         (*out)(x,y).x = this->levels_[0].data[this->getInd(0, x,y)].x();
00206         (*out)(x,y).y = this->levels_[0].data[this->getInd(0, x,y)].y();
00207 
00208         //color/label
00209         int mark = this->isOccupied(0,x,y);
00210         if(mark>=0)
00211           (*out)(x,y).z = this->polygons_[mark].model_.model(
00212               this->levels_[0].data[this->getInd(0, x,y)].x(),
00213               this->levels_[0].data[this->getInd(0, x,y)].y()
00214           );
00215         else
00216           (*out)(x,y).x = (*out)(x,y).y = (*out)(x,y).z = 0;
00217         SetLabeledPoint<PointLabel>( (*out)(x,y), mark);
00218 
00219         /*if(mark>0 && mark<(int)this->polygons_.size())
00220         {
00221           const float z = this->levels_[0].data[this->getInd(i, x,y)].z_(0)/this->levels_[0].data[this->getInd(i, x,y)].model_(0,0);
00222 
00223           Eigen::Vector3f p;
00224           p(0) =
00225               this->levels_[0].data[this->getInd(0, x,y)].x();
00226           p(1) =
00227               this->levels_[0].data[this->getInd(0, x,y)].y();
00228           p(2) = z;
00229 
00230           const float z_model = polygons_[mark].model_.model(
00231               levels_[0].data[getInd(x,y)].model_(0,1)/levels_[0].data[getInd(x,y)].model_(0,0),
00232               levels_[0].data[getInd(x,y)].model_(0,3)/levels_[0].data[getInd(x,y)].model_(0,0)
00233           );
00234           Point ps;
00235           ps.x = (*out)(x,y).x;
00236           ps.y = (*out)(x,y).y;
00237           ps.z = (*out)(x,y).z;
00238           kdtree.nearestKSearch(ps, 1, pointIdxNKNSearch, pointNKNSquaredDistance);
00239           const float d = std::min(pointNKNSquaredDistance[0], std::min(std::abs(z - z_model), (polygons_[i].project2world(polygons_[i].nextPoint(p))-p).norm()));
00240 
00241           if(pcl_isfinite(d)) {
00242             if(d<0.1)
00243               (*out)(x,y).x = (*out)(x,y).y = (*out)(x,y).z = 0;
00244             else {
00245               std::cout<<"meas\n"<<p<<"\n\n";
00246               std::cout<<"z\n"<<z_model<<"\n";
00247               std::cout<<"p\n"<<polygons_[i].project2world(polygons_[i].nextPoint(p))<<"\n\n";
00248             }
00249           }
00250 
00251           //const float d = std::min(std::abs(z - z_model), (polygons_[i].project2world(polygons_[i].nextPoint(p))-p).norm());
00252           //(*out)(x,y).r = (*out)(x,y).g = (*out)(x,y).b = d/0.1f * 255;
00253         }*/
00254 
00255       }
00256     }
00257 
00258     return out;
00259   }
00260 
00261   template <typename Point, typename PointLabel, typename Parent>
00262   void Segmentation_QuadRegression<Point,PointLabel,Parent>::compute_accuracy(float &mean, float &var, float &mean_weighted, float &var_weighted, size_t &used, size_t &mem, size_t &points, float &avg_dist, const boost::shared_ptr<const pcl::PointCloud<PointLabel> > &labeled_pc, double &true_positive, double &false_positive)
00263   {
00264     typename pcl::PointCloud<PointLabel>::Ptr out(new pcl::PointCloud<PointLabel>);
00265 
00266     KDTREE<Point> kdtree;
00267 
00268     std::vector<int> pointIdxNKNSearch(1);
00269     std::vector<float> pointNKNSquaredDistance(1);
00270 
00271     kdtree.setInputCloud (this->input_);
00272 
00273     ROS_ASSERT(this->levels_.size()>0);
00274 
00275     out->width = this->levels_[0].w;
00276     out->height= this->levels_[0].h;
00277     out->resize(out->width*out->height);
00278 
00279     BinaryClassification bc;
00280     RunningStat rstat, rstat_weighted;
00281     points = 0;
00282     avg_dist = 0;
00283 
00284     bc.addPC(labeled_pc);
00285 
00286     for(size_t x=0; x<this->levels_[0].w; x++)
00287     {
00288       for(size_t y=0; y<this->levels_[0].h; y++)
00289       {
00290         //position
00291         const int i=0;
00292 
00293         //color/label
00294         int mark = this->isOccupied(0,x,y);
00295 
00296         if(mark>=0 && mark<(int)this->polygons_.size())
00297         {
00298           const float z_model = this->polygons_[mark].model_.model(
00299               this->levels_[0].data[this->getInd(i, x,y)].x(),
00300               this->levels_[0].data[this->getInd(i, x,y)].y()
00301           );
00302           const float z = this->levels_[0].data[this->getInd(i, x,y)].z_(0)/this->levels_[0].data[this->getInd(i, x,y)].model_(0,0);
00303 
00304           Eigen::Vector3f p;
00305           p(0) =
00306               this->levels_[0].data[this->getInd(i, x,y)].x();
00307           p(1) =
00308               this->levels_[0].data[this->getInd(i, x,y)].y();
00309           p(2) = z;
00310 
00311           Point ps;
00312           ps.x = p(0);
00313           ps.y = p(1);
00314           ps.z = z_model;
00315           if(pcl_isfinite(ps.x) && pcl_isfinite(ps.y) && pcl_isfinite(z)) {
00316           kdtree.nearestKSearch(ps, 1, pointIdxNKNSearch, pointNKNSquaredDistance);
00317           const float d = std::min(std::sqrt(pointNKNSquaredDistance[0]), std::min(std::abs(z - z_model), (this->polygons_[i].project2world(this->polygons_[i].nextPoint(p))-p).norm()));
00318 
00319           if(labeled_pc && pointIdxNKNSearch.size()>0 && pointIdxNKNSearch[0]<(int)labeled_pc->size())
00320             bc.addMark(mark, (*labeled_pc)[pointIdxNKNSearch[0]].label);
00321 
00322           if(pcl_isfinite(d) && pcl_isfinite(z) && d<0.25f)
00323           {
00324             if(d<0.05f) {
00325               rstat.Push(d);
00326               rstat_weighted.Push(d, 1/z_model);
00327             }
00328             avg_dist += z;
00329           }}
00330         }
00331 
00332         if(this->levels_[0].data[this->getInd(i, x,y)].z_(0)/this->levels_[0].data[this->getInd(i, x,y)].model_(0,0)>0 && pcl_isfinite(this->levels_[0].data[this->getInd(i, x,y)].z_(0)/this->levels_[0].data[this->getInd(i, x,y)].model_(0,0)))
00333           points++;
00334 
00335       }
00336     }
00337 
00338     bc.finish().get_rate(true_positive, false_positive);
00339 
00340     //points = this->levels_[0].w*this->levels_[0].h;
00341     used = rstat.NumDataValues();
00342     mem = 0;
00343     for(size_t i=0; i<this->polygons_.size(); i++)
00344       mem+=4*SubStructure::Param<Parent::DEGREE>::NUM + this->polygons_[i].segments_.size()*2*4;
00345 
00346     mean = rstat.Mean();
00347     var = rstat.Variance();
00348     mean_weighted = rstat_weighted.Mean();
00349     var_weighted = rstat_weighted.Variance();
00350     avg_dist /= points;
00351   }
00352 
00353   template <typename Point, typename PointLabel, typename Parent>
00354   Segmentation_QuadRegression<Point,PointLabel,Parent>::operator cob_3d_mapping_msgs::ShapeArray() const {
00355     cob_3d_mapping_msgs::ShapeArray sa;
00356 
00357     cob_3d_mapping_msgs::Shape s;
00358     if(this->getOnlyPlanes())
00359       s.type = cob_3d_mapping_msgs::Shape::POLYGON;
00360     else
00361       s.type = cob_3d_mapping_msgs::Shape::CURVED;
00362 
00363     sa.header.frame_id = s.header.frame_id = "/test";
00364 
00365     for(size_t i=0; i<this->polygons_.size(); i++) {
00366       if(this->polygons_[i].segments_.size()<1) continue;
00367 
00368       Eigen::Vector3f mi, ma;
00369 
00370       s.params.clear();
00371 
00372       if(this->getOnlyPlanes()) {
00373         /*ROS_ASSERT( std::abs(this->polygons_[i].model_.p(2))<0.001f &&
00374                     std::abs(this->polygons_[i].model_.p(4))<0.001f &&
00375                     std::abs(this->polygons_[i].model_.p(5))<0.001f );*/
00376 
00377         Eigen::Vector3f n = this->polygons_[i].model_.getNormal(0,0), v;
00378         v.fill(0);
00379         v(2) = this->polygons_[i].model_.p(0);
00380         for(int i=0; i<3; i++) s.params.push_back(n(i));
00381         s.params.push_back(n.dot(v));
00382       }
00383       else {
00384         for(int k=0; k<SubStructure::Param<Parent::DEGREE>::NUM; k++)
00385           s.params.push_back(this->polygons_[i].model_.p(k));
00386       }
00387 
00388       s.pose.position.x = this->polygons_[i].model_.x();
00389       s.pose.position.y = this->polygons_[i].model_.y();
00390       s.pose.position.z = this->polygons_[i].model_.z(); //perhaps from model?
00391       
00392       Eigen::Quaternionf orientation = this->polygons_[i].get_orientation();
00393       s.pose.orientation.x = orientation.x();
00394       s.pose.orientation.y = orientation.y();
00395       s.pose.orientation.z = orientation.z();
00396       s.pose.orientation.w = orientation.w();
00397       
00398       const Eigen::Affine3f T = (
00399                                 Eigen::Translation3f(s.pose.position.x,s.pose.position.y,s.pose.position.z)*
00400                                 orientation
00401                         ).inverse();
00402 
00403       s.weight = this->polygons_[i].weight_;
00404 
00405       s.color.r=this->polygons_[i].color_[0];
00406       s.color.g=this->polygons_[i].color_[1];
00407       s.color.b=this->polygons_[i].color_[2];
00408       s.color.a=1.f;
00409 
00410       s.id = i;
00411       //s.color.a=std::min(1000.f,this->polygons_[i].weight_)/1000.f;
00412 
00413       s.points.clear();
00414       float backs=0;
00415       for(size_t j=0; j<this->polygons_[i].segments_.size(); j++) {
00416         pcl::PointCloud<pcl::PointXYZ> pc;
00417         pcl::PointXYZ pt;
00418 
00419         for(size_t k=0; k<this->polygons_[i].segments_[j].size(); k++) {
00420                         pt.x=this->polygons_[i].segments_[j][k](0);
00421                         pt.y=this->polygons_[i].segments_[j][k](1);
00422                         
00423                         //compatible to code of goa (e.g. visualization)
00424                         if(this->getOnlyPlanes()) {
00425                           const Eigen::Vector3f p = T*this->polygons_[i].project2world( this->polygons_[i].segments_[j][k].head(2) );
00426                           
00427                           pt.x = p(0);
00428                           pt.y = p(1);
00429                           pt.z = p(2);
00430                           
00431                           if(pcl_isfinite(pt.x) && pcl_isfinite(pt.y))
00432                                 pc.push_back(pt);
00433                         }
00434                         else {
00435                           pt.z=this->polygons_[i].segments_[j][k](2);
00436                           if(j==0) {
00437                                 backs+=this->polygons_[i].segments_[j][k](2);
00438                                 if(k==0)
00439                                   mi = ma = this->polygons_[i].project2world( this->polygons_[i].segments_[j][k].head(2) );
00440                                 else
00441                                 {
00442                                   Eigen::Vector3f t = this->polygons_[i].project2world( this->polygons_[i].segments_[j][k].head(2) );
00443                                   mi(0) = std::min(t(0),mi(0));
00444                                   mi(1) = std::min(t(1),mi(1));
00445                                   mi(2) = std::min(t(2),mi(2));
00446                                   ma(0) = std::max(t(0),ma(0));
00447                                   ma(1) = std::max(t(1),ma(1));
00448                                   ma(2) = std::max(t(2),ma(2));
00449                                 }
00450                           }
00451                           if(pcl_isfinite(pt.x) && pcl_isfinite(pt.y)) {
00452                                 pc.push_back(pt);
00453                           }
00454                   }
00455                   
00456         }
00457 
00458         pcl::PCLPointCloud2 pc2;
00459         pcl::toPCLPointCloud2(pc, pc2);
00460         sensor_msgs::PointCloud2 pc_msg;
00461         pcl_conversions::fromPCL(pc2, pc_msg);   
00462         //pcl::toROSMsg(pc,pc_msg);
00463 
00464         s.points.push_back(pc_msg);
00465         s.holes.push_back(j>0);
00466       }
00467 
00468       //ROS_INFO("density %f",(mi-ma).squaredNorm()/(this->polygons_[i].weight_*this->polygons_[i].weight_));
00469       //if( (mi-ma).squaredNorm()/(this->polygons_[i].weight_*this->polygons_[i].weight_)<0.00002f)
00470       sa.shapes.push_back(s);
00471     }
00472 
00473     return sa;
00474   }
00475 
00476 
00477   template <typename Point, typename PointLabel, typename Parent>
00478   Segmentation_QuadRegression<Point,PointLabel,Parent>::operator visualization_msgs::Marker() const {
00479     visualization_msgs::Marker m;
00480     m.type = visualization_msgs::Marker::LINE_LIST;
00481     m.id = 0;
00482     m.action = visualization_msgs::Marker::ADD;
00483     m.pose.position.x = 0;
00484     m.pose.position.y = 0;
00485     m.pose.position.z = 0;
00486     m.pose.orientation.x = 0.0;
00487     m.pose.orientation.y = 0.0;
00488     m.pose.orientation.z = 0.0;
00489     m.pose.orientation.w = 1.0;
00490     m.scale.x = 0.02;
00491     m.scale.y = 0.1;
00492     m.scale.z = 0.1;
00493     m.color.a = 1.0;
00494     m.color.r = 1.0;
00495     m.color.g = 1.0;
00496     m.color.b = 1.0;
00497 
00498     for(size_t i=0; i<this->polygons_.size(); i++) {
00499 
00500 
00501 //      std::cerr<<"OFF:\n"<<this->polygons_[i].param_.col(0)<<"\n";
00502 //      std::cerr<<"PLANE:\n"<<this->polygons_[i].proj2plane_<<"\n";
00503 //      std::cerr<<"P1:\n"<<this->polygons_[i].param_.col(1)<<"\n";
00504 //      std::cerr<<"P2:\n"<<this->polygons_[i].param_.col(2)<<"\n";
00505 
00506       if(this->polygons_[i].segments_.size()<1) continue;
00507 
00508       for(size_t j=0; j<this->polygons_[i].segments_.size(); j++) {
00509 
00510         for(size_t k=0; k<this->polygons_[i].segments_[j].size(); k++)
00511         {
00512           std_msgs::ColorRGBA c;
00513           geometry_msgs::Point p;
00514           Eigen::Vector3f v1,v2;
00515 
00516           c.r=this->polygons_[i].segments_[j][(k+1)%this->polygons_[i].segments_[j].size()](2);
00517           c.g=0;
00518           c.b=1-c.r;
00519           c.a=1;
00520 
00521           v1 = this->polygons_[i].project2world(this->polygons_[i].segments_[j][k].head(2));
00522           v2 = this->polygons_[i].project2world(this->polygons_[i].segments_[j][(k+1)%this->polygons_[i].segments_[j].size()].head(2));
00523 
00524 
00525 //          std::cerr<<"s\n"<<this->polygons_[i].segments_[j][k].head<2>()<<"\n";
00526 //          std::cerr<<"P\n"<<v1<<"\n";
00527 
00528           if(!pcl_isfinite(v1.sum()) || !pcl_isfinite(v2.sum()))
00529             continue;
00530 
00531           //          std::cout<<"O\n"<<v1<<"\n";
00532 
00533           p.x = v1(0);
00534           p.y = v1(1);
00535           p.z = v1(2);
00536           m.points.push_back(p);
00537           m.colors.push_back(c);
00538 
00539           p.x = v2(0);
00540           p.y = v2(1);
00541           p.z = v2(2);
00542           m.points.push_back(p);
00543           m.colors.push_back(c);
00544         }
00545       }
00546     }
00547 
00548     return m;
00549   }
00550 
00551   template <typename Point, typename PointLabel, typename Parent>
00552   bool Segmentation_QuadRegression<Point,PointLabel,Parent>::extractImages() {
00553 #ifdef USE_COLOR
00554     const pcl::PointCloud<Point> &pc = (*this->input_);
00555 
00556     for(size_t i=0; i<this->polygons_.size(); i++) {
00557       this->polygons_[i].img_.reset(new sensor_msgs::Image);
00558 
00559       if(this->polygons_[i].segments2d_.size()<1 || this->polygons_[i].segments2d_[0].size()<3) continue;
00560 
00561       //2d rect
00562       int mix=this->input_->width, miy=this->input_->height, max=-1, may=-1;
00563       for(size_t j=0; j<this->polygons_[i].segments2d_[0].size(); j++) { //outer hull
00564         mix = std::min(mix, this->polygons_[i].segments2d_[0][j](0));
00565         max = std::max(max, this->polygons_[i].segments2d_[0][j](0));
00566         miy = std::min(miy, this->polygons_[i].segments2d_[0][j](1));
00567         may = std::max(may, this->polygons_[i].segments2d_[0][j](1));
00568       }
00569 #ifndef DO_NOT_DOWNSAMPLE_
00570       mix*=2;
00571       max*=2;
00572       miy*=2;
00573       may*=2;
00574 #endif
00575 
00576       int w=max-mix, h=may-miy;
00577       max-=w/4;
00578       mix+=w/4;
00579       may-=h/4;
00580       miy+=h/4;
00581 
00582       this->polygons_[i].img_->width  = max-mix+1;
00583       this->polygons_[i].img_->height = may-miy+1;
00584       this->polygons_[i].img_->encoding = "rgb8";
00585       this->polygons_[i].img_->step = this->polygons_[i].img_->width*3;
00586       this->polygons_[i].img_->is_bigendian = false;
00587       this->polygons_[i].img_->data.resize( this->polygons_[i].img_->step*this->polygons_[i].img_->height );
00588 
00589       this->polygons_[i].color_[0] = this->polygons_[i].color_[1] = this->polygons_[i].color_[2] = 0.f;
00590       for(int x=mix; x<=max; x++) {
00591         for(int y=miy; y<=may; y++) {
00592           this->polygons_[i].img_->data[(y-miy)*this->polygons_[i].img_->step + 3*(x-mix) + 0] = pc(x,y).r;
00593           this->polygons_[i].img_->data[(y-miy)*this->polygons_[i].img_->step + 3*(x-mix) + 1] = pc(x,y).g;
00594           this->polygons_[i].img_->data[(y-miy)*this->polygons_[i].img_->step + 3*(x-mix) + 2] = pc(x,y).b;
00595 
00596           this->polygons_[i].color_[0] += pc(x,y).r;
00597           this->polygons_[i].color_[1] += pc(x,y).g;
00598           this->polygons_[i].color_[2] += pc(x,y).b;
00599         }
00600       }
00601 
00602       this->polygons_[i].color_[0] /= 255.f*this->polygons_[i].img_->width*this->polygons_[i].img_->height;
00603       this->polygons_[i].color_[1] /= 255.f*this->polygons_[i].img_->width*this->polygons_[i].img_->height;
00604       this->polygons_[i].color_[2] /= 255.f*this->polygons_[i].img_->width*this->polygons_[i].img_->height;
00605     }
00606   return true;
00607 #else
00608   return false;
00609 #endif
00610   }
00611 
00612 
00613   template <typename Point, typename PointLabel, typename Parent>
00614   std::istream &Segmentation_QuadRegression<Point,PointLabel,Parent>::serialize(std::istream &is) {
00615         this->polygons_.clear();
00616 
00617         int degree=0; is.read((char*)&degree, sizeof(degree));
00618         assert(degree==Parent::DEGREE);
00619 
00620         size_t num_polygons=0;
00621         is.read((char*)&num_polygons, sizeof(num_polygons));
00622         this->polygons_.resize(num_polygons);
00623         for(size_t i=0; i<num_polygons; i++) {
00624                 for(int j=0; j<this->polygons_[i].model_.param.NUM; j++) {
00625                         float f=0;
00626                         is.read((char*)&f, sizeof(f));
00627                         this->polygons_[i].model_.p[j] = f;
00628                 }
00629                 size_t num_hulls=0;
00630                 is.read((char*)&num_hulls, sizeof(num_hulls));
00631                 this->polygons_[i].segments_.resize(num_hulls);
00632                 for(size_t j=0; j<num_hulls; j++) {
00633                         size_t num_pts=0;
00634                         is.read((char*)&num_pts, sizeof(num_pts));
00635                         this->polygons_[i].segments_[j].resize(num_pts);
00636                         for(size_t k=0; k<num_pts; k++) {
00637                                 for(int l=0; l<2; l++) {
00638                                         float f=0;
00639                                         is.read((char*)&f, sizeof(f));
00640                                         this->polygons_[i].segments_[j][k](l) = f;
00641                                 }
00642                         }
00643                 }
00644         }
00645 
00646         return is;
00647    }
00648 
00649   template <typename Point, typename PointLabel, typename Parent>
00650   std::ostream &Segmentation_QuadRegression<Point,PointLabel,Parent>::serialize(std::ostream &os) const {
00651         size_t num_polygons=this->polygons_.size();
00652 
00653         int degree=Parent::DEGREE; os.write((const char*)&degree, sizeof(degree));
00654 
00655         os.write((const char*)&num_polygons, sizeof(num_polygons));
00656         for(size_t i=0; i<num_polygons; i++) {
00657                 for(int j=0; j<this->polygons_[i].model_.param.NUM; j++) {
00658                         float f=this->polygons_[i].model_.p[j];
00659                         os.write((const char*)&f, sizeof(f));
00660                 }
00661                 size_t num_hulls=this->polygons_[i].segments_.size();
00662                 os.write((const char*)&num_hulls, sizeof(num_hulls));
00663                 for(size_t j=0; j<num_hulls; j++) {
00664                         size_t num_pts=this->polygons_[i].segments_[j].size();
00665                         os.write((const char*)&num_pts, sizeof(num_pts));
00666                         for(size_t k=0; k<num_pts; k++) {
00667                                 for(int l=0; l<2; l++) {
00668                                         float f=this->polygons_[i].segments_[j][k](l);
00669                                         os.write((const char*)&f, sizeof(f));
00670                                 }
00671                         }
00672                 }
00673         }
00674 
00675         return os;
00676    }


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