00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024 #ifndef OVERLAP_ESTIMATION_H
00025 #define OVERLAP_ESTIMATION_H
00026
00027 #include <vcg/math/gen_normal.h>
00028 #include <vcg/math/random_generator.h>
00029 #include <vcg/space/index/grid_static_ptr.h>
00030 #include <vcg/complex/trimesh/closest.h>
00031 #include <vcg/complex/trimesh/point_sampling.h>
00032
00033 #include <qdatetime.h>
00034
00035 using namespace std;
00036 using namespace vcg;
00037
00048 template<class MESH_TYPE> class OverlapEstimation
00049 {
00050 public:
00051
00052 typedef MESH_TYPE MeshType;
00053 typedef typename MeshType::ScalarType ScalarType;
00054 typedef typename MeshType::CoordType CoordType;
00055 typedef typename MeshType::VertexType VertexType;
00056 typedef typename MeshType::FaceType FaceType;
00057 typedef typename MeshType::VertexPointer VertexPointer;
00058 typedef typename MeshType::VertexIterator VertexIterator;
00059 typedef typename vector<VertexPointer>::iterator VertexPointerIterator;
00060 typedef GridStaticPtr<VertexType, ScalarType > MeshGrid;
00061 typedef tri::VertTmark<MeshType> MarkerVertex;
00062
00063 private:
00065 class VertexPointerSampler
00066 {
00067 public:
00068
00069 MeshType* m;
00070
00071 VertexPointerSampler(){ m = new MeshType(); m->Tr.SetIdentity(); m->sfn=0; }
00072 ~VertexPointerSampler(){ if(m) delete m; }
00073 vector<VertexType*> sampleVec;
00074
00075 void AddVert(VertexType &p){ sampleVec.push_back(&p); }
00076 void AddFace(const FaceType &f, const CoordType &p){}
00077 void AddTextureSample(const FaceType &, const CoordType &, const Point2i &){}
00078 };
00079
00080 public:
00084 class Parameters
00085 {
00086 public:
00087 int samples;
00088 int bestScore;
00089 float consensusDist;
00090 float consensusNormalsAngle;
00091 float threshold;
00092 bool normalEqualization;
00093 bool paint;
00094 void (*log)(int level, const char * f, ... );
00095
00097 Parameters()
00098 {
00099 samples = 2500;
00100 bestScore = 0;
00101 consensusDist = 2.0f;
00102 consensusNormalsAngle = 0.965f;
00103 threshold = 0.0f;
00104 normalEqualization = true;
00105 paint = false;
00106 log = NULL;
00107 }
00108 };
00109
00110 private:
00111 MeshType* mFix;
00112 MeshType* mMov;
00113 vector<vector<int> >* normBuckets;
00114 MeshGrid* gridFix;
00115 MarkerVertex markerFunctorFix;
00116
00117 public:
00119 OverlapEstimation() : normBuckets(NULL), gridFix(NULL){}
00121 ~OverlapEstimation(){
00122 if(normBuckets) delete normBuckets;
00123 if(gridFix) delete gridFix;
00124 }
00126 void SetFix(MeshType& m){ mFix = &m; }
00128 void SetMove(MeshType& m){ mMov = &m; }
00129
00134 void Paint()
00135 {
00136 for(VertexIterator vi=mMov->vert.begin(); vi!=mMov->vert.end(); vi++){
00137 if(!(*vi).IsD()){
00138 if((*vi).Q()==0.0) (*vi).C() = Color4b::Red;
00139 if((*vi).Q()==1.0) (*vi).C() = Color4b::Yellow;
00140 if((*vi).Q()==2.0) (*vi).C() = Color4b::Blue;
00141 }
00142 }
00143 }
00144
00149 bool Init(Parameters& param){
00150
00151 gridFix = new MeshGrid();
00152 SetupGrid();
00153
00154
00155
00156 if(normBuckets) {normBuckets->clear(); delete normBuckets; }
00157 if(param.normalEqualization){
00158 normBuckets = BucketVertexNormal(mMov->vert, 30);
00159 assert(normBuckets);
00160 }
00161 return true;
00162 }
00163
00168 float Compute(Parameters& param)
00169 {
00170 return Check(param)/float(param.samples);
00171 }
00172
00177
00178 int Check(Parameters& param)
00179 {
00180
00181 vertex::PointDistanceFunctor<ScalarType> PDistFunct;
00182
00183
00184
00185 vector<VertexPointer> queryVert;
00186 if(param.normalEqualization){
00187 assert(normBuckets);
00188 for(unsigned int i=0; i<mMov->vert.size(); i++) queryVert.push_back(&(mMov->vert[i]));
00189 SampleVertNormalEqualized(queryVert, param.samples);
00190 }
00191 else{
00192 SampleVertUniform(*mMov, queryVert, param.samples);
00193 }
00194 assert(queryVert.size()!=0);
00195
00196
00197 float consDist = param.consensusDist*(mMov->bbox.Diag()/100.0f);
00198 int cons_succ = int(param.threshold*(param.samples/100.0f));
00199 int consensus = 0;
00200 float dist;
00201 VertexType* closestVertex = NULL;
00202 Point3<ScalarType> queryNrm;
00203 CoordType queryPnt;
00204 CoordType closestPnt;
00205 Matrix33<ScalarType> inv33_matMov(mMov->Tr,3);
00206 Matrix33<ScalarType> inv33_matFix(Inverse(mFix->Tr),3);
00207
00208
00209 VertexPointerIterator vi; int i;
00210 for(i=0, vi=queryVert.begin(); vi!=queryVert.end(); vi++, i++)
00211 {
00212 dist = -1.0f;
00213
00214 queryPnt = Inverse(mFix->Tr) * (mMov->Tr * (*vi)->P());
00215 queryNrm = inv33_matFix * (inv33_matMov * (*vi)->N());
00216
00217 if(mFix->bbox.IsIn(queryPnt)) closestVertex = gridFix->GetClosest(PDistFunct,markerFunctorFix,queryPnt,consDist,dist,closestPnt);
00218 else closestVertex=NULL;
00219
00220 if(closestVertex!=NULL && dist < consDist){
00221 assert(closestVertex->P()==closestPnt);
00222
00223
00224 if(queryNrm.dot(closestVertex->N())>param.consensusNormalsAngle)
00225 {
00226 consensus++;
00227 if(param.paint) (*vi)->Q() = 0.0f;
00228 }
00229 else{
00230 if(param.paint) (*vi)->Q() = 1.0f;
00231 }
00232 }
00233 else{
00234 if(param.paint) (*vi)->Q() = 2.0f;
00235 }
00236 }
00237
00238
00239 if(param.paint){
00240 if(consensus>=param.bestScore && consensus>=cons_succ) Paint();
00241 }
00242
00243 return consensus;
00244 }
00245
00246 private:
00252 void SampleVertUniform(MESH_TYPE& m, vector<typename MESH_TYPE::VertexPointer>& vert, int sampleNum)
00253 {
00254 VertexPointerSampler sampler;
00255 tri::SurfaceSampling<MeshType, VertexPointerSampler>::VertexUniform(m, sampler, sampleNum);
00256 for(unsigned int i=0; i<sampler.sampleVec.size(); i++) vert.push_back(sampler.sampleVec[i]);
00257 }
00261 vector<vector<int> >* BucketVertexNormal(typename MESH_TYPE::VertContainer& vert, int bucketDim = 30)
00262 {
00263 static vector<Point3f> NV;
00264 if(NV.size()==0) GenNormal<float>::Uniform(bucketDim,NV);
00265
00266 vector<vector<int> >* BKT = new vector<vector<int> >(NV.size());
00267
00268 int ind;
00269 for(int i=0;i<vert.size();++i){
00270 ind=GenNormal<float>::BestMatchingNormal(vert[i].N(),NV);
00271 (*BKT)[ind].push_back(i);
00272 }
00273
00274 return BKT;
00275 }
00280 bool SampleVertNormalEqualized(vector<typename MESH_TYPE::VertexPointer>& vert, int SampleNum)
00281 {
00282 assert(normBuckets);
00283
00284 vector<int> BKTpos(normBuckets->size(),0);
00285
00286 if(SampleNum >= int(vert.size())) SampleNum= int(vert.size()-1);
00287
00288 int ind;
00289 for(int i=0;i<SampleNum;){
00290 ind=LocRnd(normBuckets->size());
00291 int &CURpos = BKTpos[ind];
00292 vector<int> &CUR = (*normBuckets)[ind];
00293
00294 if(CURpos<int(CUR.size())){
00295 swap(CUR[CURpos], CUR[ CURpos + LocRnd((*normBuckets)[ind].size()-CURpos)]);
00296 swap(vert[i],vert[CUR[CURpos]]);
00297 ++BKTpos[ind];
00298 ++i;
00299 }
00300 }
00301
00302 vert.resize(SampleNum);
00303 return true;
00304 }
00308 static math::SubtractiveRingRNG &LocRnd(){
00309 static math::SubtractiveRingRNG myrnd(time(NULL));
00310 return myrnd;
00311 }
00316 static int LocRnd(int n){
00317 return LocRnd().generate(n);
00318 }
00320 inline void SetupGrid()
00321 {
00322 gridFix->Set(mFix->vert.begin(),mFix->vert.end());
00323 markerFunctorFix.SetMesh(mFix);
00324 }
00325 };
00326
00327 #endif // OVERLAP_ESTIMATION_H