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