trimesh_fitting.cpp
Go to the documentation of this file.
00001 /****************************************************************************
00002 * VCGLib                                                            o o     *
00003 * Visual and Computer Graphics Library                            o     o   *
00004 *                                                                _   O  _   *
00005 * Copyright(C) 2004-2012                                           \/)\/    *
00006 * Visual Computing Lab                                            /\/|      *
00007 * ISTI - Italian National Research Council                           |      *
00008 *                                                                    \      *
00009 * All rights reserved.                                                      *
00010 *                                                                           *
00011 * This program is free software; you can redistribute it and/or modify      *
00012 * it under the terms of the GNU General Public License as published by      *
00013 * the Free Software Foundation; either version 2 of the License, or         *
00014 * (at your option) any later version.                                       *
00015 *                                                                           *
00016 * This program is distributed in the hope that it will be useful,           *
00017 * but WITHOUT ANY WARRANTY; without even the implied warranty of            *
00018 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the             *
00019 * GNU General Public License (http://www.gnu.org/licenses/gpl.txt)          *
00020 * for more details.                                                         *
00021 *                                                                           *
00022 ****************************************************************************/
00034 #include<vcg/complex/complex.h>
00035 #include<vcg/complex/algorithms/update/topology.h>
00036 #include<vcg/complex/algorithms/update/normal.h>
00037 #include<vcg/complex/algorithms/create/platonic.h>
00038 #include<vcg/complex/algorithms/point_sampling.h>
00039 #include<wrap/io_trimesh/import_off.h>
00040 #include<vcg/space/fitting3.h>
00041 
00042 
00043 class MyEdge;
00044 class MyFace;
00045 class MyVertex;
00046 struct MyUsedTypes : public vcg::UsedTypes<     vcg::Use<MyVertex>   ::AsVertexType,
00047                                         vcg::Use<MyEdge>     ::AsEdgeType,
00048                                         vcg::Use<MyFace>     ::AsFaceType>{};
00049 
00050 class MyVertex  : public vcg::Vertex<MyUsedTypes, vcg::vertex::Coord3f, vcg::vertex::Normal3f, vcg::vertex::BitFlags  >{};
00051 class MyFace    : public vcg::Face< MyUsedTypes, vcg::face::FFAdj,  vcg::face::VertexRef, vcg::face::Normal3f, vcg::face::BitFlags > {};
00052 class MyEdge    : public vcg::Edge<MyUsedTypes>{};
00053 class MyMesh    : public vcg::tri::TriMesh< std::vector<MyVertex>, std::vector<MyFace> , std::vector<MyEdge>  > {};
00054 
00055 float EvalPlane(vcg::Plane3f &pl, std::vector<vcg::Point3f> posVec)
00056 {
00057   float off=0;
00058   for(size_t i=0;i<posVec.size();++i)
00059     off += fabs(vcg::SignedDistancePlanePoint(pl,posVec[i]));
00060 
00061   off/=float(posVec.size());
00062   return off;
00063 }
00064 
00065 
00066 int main( )
00067 {
00068   MyMesh m;
00069   vcg::tri::Icosahedron(m);
00070   vcg::tri::UpdateNormal<MyMesh>::PerVertexNormalizedPerFaceNormalized(m);
00071   vcg::tri::UpdateBounding<MyMesh>::Box(m);
00072 
00073   // As a simple test just run over all the faces of a mesh
00074   // get a few random points over it, perturb them and fit a plane on them.
00075   vcg::Plane3f ple,plf,plw;
00076   int cnt=0;
00077   float scaleFac = m.bbox.Diag()/10.0f;
00078   printf("ScaleFac %f\n\n",scaleFac);
00079   vcg::math::MarsenneTwisterRNG rnd;
00080   for(int i=0;i<m.FN();++i)
00081   {
00082     std::vector<vcg::Point3f> ExactVec;
00083     std::vector<vcg::Point3f> PerturbVec;
00084     std::vector<float> WeightVec;
00085     vcg::Plane3f pl;
00086     pl.Init(vcg::Barycenter(m.face[i]),m.face[i].N());
00087     for(int j=0;j<200;++j)
00088     {
00089       vcg::Point3f p = vcg::tri::SurfaceSampling<MyMesh>::RandomPointInTriangle(m.face[i]);
00090       ExactVec.push_back(p);
00091       vcg::Point3f off = vcg::math::GeneratePointInUnitBallUniform<float>(rnd);
00092       p+=off*scaleFac;
00093       float w =  std::max(0.0f, 1.0f-fabs(vcg::SignedDistancePlanePoint(pl,p))/scaleFac);
00094       PerturbVec.push_back(p);
00095       WeightVec.push_back(w*w); // as weight we use the square of  (1-distance)
00096     }
00097 
00098     vcg::FitPlaneToPointSet(ExactVec,ple);
00099     float err=EvalPlane(ple,ExactVec);
00100 
00101     vcg::FitPlaneToPointSet(PerturbVec,plf);
00102     float err0=EvalPlane(plf,ExactVec);
00103 
00104     vcg::WeightedFitPlaneToPointSet(PerturbVec,WeightVec,plw);
00105     float err1=EvalPlane(plw,ExactVec);
00106     printf("Exact %5.3f Fit to Perturbed %5.3f Weighted fit to perturbed %5.3f\n",err,err0,err1);
00107     if(err0>err1) cnt++;
00108   }
00109 
00110   printf("\nWeighted Fitting was better %i on %i\n",cnt,m.FN());
00111   return 0;
00112 }


shape_reconstruction
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:38:18