00001 #ifndef BALL_PIVOTING_H
00002 #define BALL_PIVOTING_H
00003
00004 #include "advancing_front.h"
00005 #include <vcg/space/index/kdtree/kdtree.h>
00006
00007 #include <vcg/complex/algorithms/closest.h>
00008
00009
00010
00011
00012
00013
00014
00015
00016 namespace vcg {
00017 namespace tri {
00018
00019 template <class MESH> class BallPivoting: public AdvancingFront<MESH> {
00020 public:
00021 typedef typename MESH::VertexType VertexType;
00022 typedef typename MESH::FaceType FaceType;
00023 typedef typename MESH::ScalarType ScalarType;
00024 typedef typename MESH::VertexIterator VertexIterator;
00025 typedef typename MESH::VertexType::CoordType Point3x;
00026
00027 float radius;
00028 float min_edge;
00029 float max_edge;
00030 float max_angle;
00031
00032 public:
00033
00034
00035
00036
00037 BallPivoting(MESH &_mesh, float _radius = 0,
00038 float minr = 0.2, float angle = M_PI/2):
00039
00040 AdvancingFront<MESH>(_mesh), radius(_radius),
00041 min_edge(minr), max_edge(1.8), max_angle(cos(angle)),
00042 last_seed(-1) {
00043
00044
00045 baricenter = Point3x(0, 0, 0);
00046 UpdateBounding<MESH>::Box(_mesh);
00047 for(VertexIterator vi=this->mesh.vert.begin();vi!=this->mesh.vert.end();++vi)
00048 if( !(*vi).IsD() ) baricenter += (*vi).P();
00049
00050 baricenter /= this->mesh.vn;
00051
00052 assert(this->mesh.vn > 3);
00053 if(radius == 0)
00054 radius = sqrt((this->mesh.bbox.Diag()*this->mesh.bbox.Diag())/this->mesh.vn);
00055
00056
00057 min_edge *= radius;
00058 max_edge *= radius;
00059
00060 VertexConstDataWrapper<MESH> ww(this->mesh);
00061 tree = new KdTree<ScalarType>(ww);
00062
00063
00064 usedBit = VertexType::NewBitFlag();
00065 UpdateFlags<MESH>::VertexClear(this->mesh,usedBit);
00066 UpdateFlags<MESH>::VertexClearV(this->mesh);
00067
00068 for(int i = 0; i < (int)this->mesh.face.size(); i++) {
00069 FaceType &f = this->mesh.face[i];
00070 if(f.IsD()) continue;
00071 for(int k = 0; k < 3; k++) {
00072 Mark(f.V(k));
00073 }
00074 }
00075 }
00076
00077 ~BallPivoting() {
00078 VertexType::DeleteBitFlag(usedBit);
00079 delete tree;
00080 }
00081
00082 bool Seed(int &v0, int &v1, int &v2) {
00083
00084 while(++last_seed < (int)(this->mesh.vert.size())) {
00085 std::vector<VertexType *> targets;
00086 VertexType &seed = this->mesh.vert[last_seed];
00087 if(seed.IsD() || seed.IsUserBit(usedBit)) continue;
00088
00089 seed.SetUserBit(usedBit);
00090
00091 typename KdTree<ScalarType>::PriorityQueue pq;
00092 tree->doQueryK(seed.P(),16,pq);
00093 int nn = pq.getNofElements();
00094 for(int i=0;i<nn;++i)
00095 {
00096 VertexType *vp = &this->mesh.vert[pq.getIndex(i)];
00097 if(Distance(seed.P(),vp->cP()) > 2*radius) continue;
00098 targets.push_back(vp);
00099 }
00100
00101 int n = targets.size();
00102 if(n<3) continue;
00103
00104 bool success = true;
00105
00106 for(int i = 0; i < n; i++) {
00107 VertexType &v = *(targets[i]);
00108 if(v.IsV()) {
00109 success = false;
00110 break;
00111 }
00112 }
00113 if(!success) continue;
00114
00115 VertexType *vv0, *vv1, *vv2;
00116 success = false;
00117
00118 Point3x center;
00119 for(int i = 0; i < n; i++) {
00120 vv0 = targets[i];
00121 if(vv0->IsD()) continue;
00122 Point3x &p0 = vv0->P();
00123
00124 for(int k = i+1; k < n; k++) {
00125 vv1 = targets[k];
00126 if(vv1->IsD()) continue;
00127 Point3x &p1 = vv1->P();
00128 float d2 = (p1 - p0).Norm();
00129 if(d2 < min_edge || d2 > max_edge) continue;
00130
00131 for(int j = k+1; j < n; j++) {
00132 vv2 = targets[j];
00133 if(vv2->IsD()) continue;
00134 Point3x &p2 = vv2->P();
00135 float d1 = (p2 - p0).Norm();
00136 if(d1 < min_edge || d1 > max_edge) continue;
00137 float d0 = (p2 - p1).Norm();
00138 if(d0 < min_edge || d0 > max_edge) continue;
00139
00140 Point3x normal = (p1 - p0)^(p2 - p0);
00141 if(normal.dot(p0 - baricenter) < 0) continue;
00142
00143
00144
00145
00146
00147
00148 if(!FindSphere(p0, p1, p2, center)) {
00149 continue;
00150 }
00151
00152
00153 int t;
00154 for(t = 0; t < n; t++) {
00155 ScalarType rr= Distance(center, targets[t]->P());
00156 if( rr < radius - min_edge)
00157 break;
00158 }
00159 if(t < n) {
00160 continue;
00161 }
00162
00163
00164 Point3x opposite = center + normal*(((center - p0).dot(normal))*2/normal.SquaredNorm());
00165 for(t = 0; t < n; t++) {
00166 VertexType &v = *(targets[t]);
00167 if((v.IsV()) && (opposite - v.P()).Norm() <= radius)
00168 break;
00169 }
00170 if(t < n) {
00171 continue;
00172 }
00173 success = true;
00174 i = k = j = n;
00175 }
00176 }
00177 }
00178
00179 if(!success) {
00180 continue;
00181 }
00182 Mark(vv0);
00183 Mark(vv1);
00184 Mark(vv2);
00185
00186 v0 = tri::Index(this->mesh,vv0);
00187 v1 = tri::Index(this->mesh,vv1);
00188 v2 = tri::Index(this->mesh,vv2);
00189 return true;
00190 }
00191 return false;
00192 }
00193
00194
00195 int Place(FrontEdge &edge, typename AdvancingFront<MESH>::ResultIterator &touch) {
00196 Point3x v0 = this->mesh.vert[edge.v0].P();
00197 Point3x v1 = this->mesh.vert[edge.v1].P();
00198 Point3x v2 = this->mesh.vert[edge.v2].P();
00199
00200
00201
00202
00203
00204
00205 Point3x normal = ((v1 - v0)^(v2 - v0)).Normalize();
00206 Point3x middle = (v0 + v1)/2;
00207 Point3x center;
00208
00209 if(!FindSphere(v0, v1, v2, center)) {
00210
00211 return -1;
00212 }
00213
00214 Point3x start_pivot = center - middle;
00215 Point3x axis = (v1 - v0);
00216
00217 ScalarType axis_len = axis.SquaredNorm();
00218 if(axis_len > 4*radius*radius) {
00219 return -1;
00220 }
00221 axis.Normalize();
00222
00223
00224 ScalarType r = sqrt(radius*radius - axis_len/4);
00225
00226
00227 typename KdTree<ScalarType>::PriorityQueue pq;
00228 tree->doQueryK(middle,16,pq);
00229 int nn = pq.getNofElements();
00230 if(nn==0) return -1;
00231
00232 VertexType *candidate = NULL;
00233 ScalarType min_angle = M_PI;
00234
00235
00236
00237 for (int i = 0; i < nn; i++) {
00238 int vInd = pq.getIndex(i);
00239 VertexType *v = &this->mesh.vert[vInd];
00240 if(Distance(middle,v->cP()) > r + radius) continue;
00241
00242
00243 if(v->IsB()) assert(v->IsV());
00244 if(v->IsV()) assert(v->IsUserBit(usedBit));
00245
00246
00247 if(v->IsUserBit(usedBit) && !(v->IsB())) continue;
00248 if(vInd == edge.v0 || vInd == edge.v1 || vInd == edge.v2) continue;
00249
00250 Point3x p = this->mesh.vert[vInd].P();
00251
00252
00253 if(!FindSphere(v0, p, v1, center)) {
00254 continue;
00255 }
00256
00257
00258 ScalarType alpha = OrientedAngleRad(start_pivot, center - middle, axis);
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276 if(candidate == NULL || alpha < min_angle) {
00277 candidate = v;
00278 min_angle = alpha;
00279 }
00280 }
00281 if(min_angle >= M_PI - 0.1) {
00282 return -1;
00283 }
00284
00285 if(candidate == NULL) {
00286 return -1;
00287 }
00288 if(!candidate->IsB()) {
00289 assert((candidate->P() - v0).Norm() > min_edge);
00290 assert((candidate->P() - v1).Norm() > min_edge);
00291 }
00292
00293 int candidateIndex = tri::Index(this->mesh,candidate);
00294 assert(candidateIndex != edge.v0 && candidateIndex != edge.v1);
00295
00296 Point3x newnormal = ((candidate->P() - v0)^(v1 - v0)).Normalize();
00297 if(normal.dot(newnormal) < max_angle || this->nb[candidateIndex] >= 2) {
00298 return -1;
00299 }
00300
00301
00302 for(std::list<FrontEdge>::iterator k = this->front.begin(); k != this->front.end(); k++)
00303 {
00304 if((*k).v0 == candidateIndex)
00305 {
00306 touch.first = AdvancingFront<MESH>::FRONT;
00307 touch.second = k;
00308 }
00309 }
00310 for(std::list<FrontEdge>::iterator k = this->deads.begin(); k != this->deads.end(); k++)
00311 {
00312 if((*k).v0 == candidateIndex)
00313 {
00314 touch.first = AdvancingFront<MESH>::DEADS;
00315 touch.second = k;
00316 }
00317 }
00318
00319
00320 Mark(candidate);
00321 return candidateIndex;
00322 }
00323
00324 private:
00325 int last_seed;
00326 int usedBit;
00327 Point3x baricenter;
00328 KdTree<ScalarType> *tree;
00329
00330
00331
00332
00333
00334 bool FindSphere(const Point3x &p0, const Point3x &p1, const Point3x &p2, Point3x ¢er) {
00335
00336 Point3x p[3];
00337
00338 if(p0 < p1 && p0 < p2) {
00339 p[0] = p0;
00340 p[1] = p1;
00341 p[2] = p2;
00342 } else if(p1 < p0 && p1 < p2) {
00343 p[0] = p1;
00344 p[1] = p2;
00345 p[2] = p0;
00346 } else {
00347 p[0] = p2;
00348 p[1] = p0;
00349 p[2] = p1;
00350 }
00351 Point3x q1 = p[1] - p[0];
00352 Point3x q2 = p[2] - p[0];
00353
00354 Point3x up = q1^q2;
00355 ScalarType uplen = up.Norm();
00356
00357
00358 if(uplen < 0.001*q1.Norm()*q2.Norm()) {
00359 return false;
00360 }
00361 up /= uplen;
00362
00363
00364 ScalarType a11 = q1.dot(q1);
00365 ScalarType a12 = q1.dot(q2);
00366 ScalarType a22 = q2.dot(q2);
00367
00368 ScalarType m = 4*(a11*a22 - a12*a12);
00369 ScalarType l1 = 2*(a11*a22 - a22*a12)/m;
00370 ScalarType l2 = 2*(a11*a22 - a12*a11)/m;
00371
00372 center = q1*l1 + q2*l2;
00373 ScalarType circle_r = center.Norm();
00374 if(circle_r > radius) {
00375 return false;
00376 }
00377
00378 ScalarType height = sqrt(radius*radius - circle_r*circle_r);
00379 center += p[0] + up*height;
00380
00381 return true;
00382 }
00383
00384
00385 ScalarType OrientedAngleRad(Point3x p, Point3x q, Point3x &axis) {
00386 p.Normalize();
00387 q.Normalize();
00388 Point3x vec = p^q;
00389 ScalarType angle = acos(p.dot(q));
00390 if(vec.dot(axis) < 0) angle = -angle;
00391 if(angle < 0) angle += 2*M_PI;
00392 return angle;
00393 }
00394
00395 void Mark(VertexType *v) {
00396 typename KdTree<ScalarType>::PriorityQueue pq;
00397 tree->doQueryK(v->cP(),16,pq);
00398 int n = pq.getNofElements();
00399 for (int i = 0; i < n; i++) {
00400 VertexType *vp = &this->mesh.vert[pq.getIndex(i)];
00401 if(Distance(v->cP(),vp->cP())<min_edge)
00402 vp->SetUserBit(usedBit);
00403 }
00404 v->SetV();
00405 }
00406 };
00407
00408 }
00409 }
00410 #endif