00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_SURFACE_IMPL_GP3_H_
00039 #define PCL_SURFACE_IMPL_GP3_H_
00040
00041 #include "pcl/surface/gp3.h"
00042
00044 template <typename PointInT> void
00045 pcl::GreedyProjectionTriangulation<PointInT>::performReconstruction (pcl::PolygonMesh &output)
00046 {
00047 if (search_radius_ <= 0 || mu_ <= 0)
00048 {
00049 ROS_ERROR ("[pcl::%s::performReconstruction] Invalid search radius (%f) or mu parameter (%f)!", getClassName ().c_str (), search_radius_, mu_);
00050 output.cloud.width = output.cloud.height = 0;
00051 output.cloud.data.clear ();
00052 output.polygons.clear ();
00053 return;
00054 }
00055 const double sqr_mu = mu_*mu_;
00056 const double sqr_max_edge = search_radius_*search_radius_;
00057 if (nnn_ > (int)indices_->size ())
00058 nnn_ = indices_->size ();
00059
00060
00061 std::vector<int> nnIdx (nnn_);
00062 std::vector<float> sqrDists (nnn_);
00063
00064
00065 int part_index = 0;
00066
00067
00068 const Eigen::Vector2f uvn_nn_qp_zero = Eigen::Vector2f::Zero();
00069 Eigen::Vector2f uvn_current;
00070 Eigen::Vector2f uvn_prev;
00071 Eigen::Vector2f uvn_next;
00072
00073
00074 already_connected_ = false;
00075
00076
00077 part_.clear ();
00078 state_.clear ();
00079 source_.clear ();
00080 ffn_.clear ();
00081 sfn_.clear ();
00082 part_.resize(indices_->size (), -1);
00083 state_.resize(indices_->size (), FREE);
00084 source_.resize(indices_->size (), NONE);
00085 ffn_.resize(indices_->size (), NONE);
00086 sfn_.resize(indices_->size (), NONE);
00087 fringe_queue_.clear ();
00088 int fqIdx = 0;
00089
00090
00091 coords_.clear ();
00092 coords_.reserve (indices_->size ());
00093 for (size_t cp = 0; cp < indices_->size (); ++cp)
00094 {
00095 coords_.push_back(input_->points[(*indices_)[cp]].getVector3fMap());
00096 }
00097
00098
00099 int is_free=0, nr_parts=0, increase_nnn4fn=0, increase_nnn4s=0, increase_dist=0, nr_touched = 0;
00100 bool is_fringe;
00101 angles_.resize(nnn_);
00102 std::vector<Eigen::Vector2f> uvn_nn (nnn_);
00103 Eigen::Vector2f uvn_s;
00104
00105
00106 while (is_free != NONE)
00107 {
00108 R_ = is_free;
00109 if (state_[R_] == FREE)
00110 {
00111 ROS_DEBUG ("Starting to build part %d starting at point: %d", nr_parts+1, R_);
00112 state_[R_] = NONE;
00113 part_[R_] = part_index++;
00114
00115
00116 searchForNeighbors ((*indices_)[R_], nnIdx, sqrDists);
00117 double sqr_dist_threshold = (std::min)(sqr_max_edge, sqr_mu * sqrDists[1]);
00118
00119
00120 const Eigen::Vector3f nc = input_->points[(*indices_)[R_]].getNormalVector3fMap ();
00121
00122
00123 Eigen::Vector3f v = nc.unitOrthogonal ();
00124 Eigen::Vector3f u = nc.cross (v);
00125
00126
00127 double dist = nc.dot(coords_[R_]);
00128 proj_qp_ = coords_[R_] - dist * nc;
00129
00130
00131 int nr_edge = 0;
00132 std::vector<doubleEdge> doubleEdges;
00133 for (int i = 1; i < nnn_; i++)
00134 {
00135
00136 tmp_ = coords_[nnIdx[i]] - proj_qp_;
00137 uvn_nn[i][0] = tmp_.dot(u);
00138 uvn_nn[i][1] = tmp_.dot(v);
00139
00140 angles_[i].angle = atan2(uvn_nn[i][1], uvn_nn[i][0]);
00141
00142 angles_[i].index = nnIdx[i];
00143 if (
00144 (state_[nnIdx[i]] == COMPLETED) || (state_[nnIdx[i]] == BOUNDARY)
00145 || (sqrDists[i] > sqr_dist_threshold)
00146 )
00147 angles_[i].visible = false;
00148 else
00149 angles_[i].visible = true;
00150
00151 if ((state_[nnIdx[i]] == FRINGE) || (state_[nnIdx[i]] == BOUNDARY))
00152 {
00153 doubleEdge e;
00154 e.index = i;
00155 nr_edge++;
00156 tmp_ = coords_[ffn_[nnIdx[i]]] - proj_qp_;
00157 e.first[0] = tmp_.dot(u);
00158 e.first[1] = tmp_.dot(v);
00159 tmp_ = coords_[sfn_[nnIdx[i]]] - proj_qp_;
00160 e.second[0] = tmp_.dot(u);
00161 e.second[1] = tmp_.dot(v);
00162 doubleEdges.push_back(e);
00163 }
00164 }
00165 angles_[0].visible = false;
00166
00167
00168 for (int i = 1; i < nnn_; i++)
00169 if ((angles_[i].visible) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i]))
00170 {
00171 bool visibility = true;
00172 for (int j = 0; j < nr_edge; j++)
00173 {
00174 if (ffn_[nnIdx[doubleEdges[j].index]] != nnIdx[i])
00175 visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].first, Eigen::Vector2f::Zero());
00176 if (!visibility)
00177 break;
00178 if (sfn_[nnIdx[doubleEdges[j].index]] != nnIdx[i])
00179 visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].second, Eigen::Vector2f::Zero());
00180 if (!visibility == false)
00181 break;
00182 }
00183 angles_[i].visible = visibility;
00184 }
00185
00186
00187 bool not_found = true;
00188 int left = 1;
00189 do
00190 {
00191 while ((left < nnn_) && ((!angles_[left].visible) || (state_[nnIdx[left]] > FREE))) left++;
00192 if (left >= nnn_)
00193 break;
00194 else
00195 {
00196 int right = left+1;
00197 do
00198 {
00199 while ((right < nnn_) && ((!angles_[right].visible) || (state_[nnIdx[right]] > FREE))) right++;
00200 if (right >= nnn_)
00201 break;
00202 else if ((coords_[nnIdx[left]] - coords_[nnIdx[right]]).squaredNorm () > sqr_max_edge)
00203 right++;
00204 else
00205 {
00206 addFringePoint (nnIdx[right], R_);
00207 addFringePoint (nnIdx[left], nnIdx[right]);
00208 addFringePoint (R_, nnIdx[left]);
00209 state_[R_] = state_[nnIdx[left]] = state_[nnIdx[right]] = FRINGE;
00210 ffn_[R_] = nnIdx[left];
00211 sfn_[R_] = nnIdx[right];
00212 ffn_[nnIdx[left]] = nnIdx[right];
00213 sfn_[nnIdx[left]] = R_;
00214 ffn_[nnIdx[right]] = R_;
00215 sfn_[nnIdx[right]] = nnIdx[left];
00216 addTriangle (R_, nnIdx[left], nnIdx[right], output);
00217 nr_parts++;
00218 not_found = false;
00219 break;
00220 }
00221 }
00222 while (true);
00223 left++;
00224 }
00225 }
00226 while (not_found);
00227 }
00228 is_free = NONE;
00229 for (unsigned temp = 0; temp < indices_->size (); temp++)
00230 {
00231 if (state_[temp] == FREE)
00232 {
00233 is_free = temp;
00234 break;
00235 }
00236 }
00237
00238 is_fringe = true;
00239 while (is_fringe)
00240 {
00241 is_fringe = false;
00242
00243 int fqSize = fringe_queue_.size();
00244 while ((fqIdx < fqSize) && (state_[fringe_queue_[fqIdx]] != FRINGE))
00245 fqIdx++;
00246
00247
00248 if (fqIdx >= fqSize)
00249 {
00250 continue;
00251 }
00252
00253 R_ = fringe_queue_[fqIdx];
00254 is_fringe = true;
00255
00256 if (ffn_[R_] == sfn_[R_])
00257 {
00258 state_[R_] = COMPLETED;
00259 continue;
00260 }
00261 searchForNeighbors ((*indices_)[R_], nnIdx, sqrDists);
00262
00263
00264 double sqr_source_dist = (coords_[R_] - coords_[source_[R_]]).squaredNorm ();
00265 double sqr_ffn_dist = (coords_[R_] - coords_[ffn_[R_]]).squaredNorm ();
00266 double sqr_sfn_dist = (coords_[R_] - coords_[sfn_[R_]]).squaredNorm ();
00267 double max_sqr_fn_dist = (std::max)(sqr_ffn_dist, sqr_sfn_dist);
00268 double sqr_dist_threshold = (std::min)(sqr_max_edge, sqr_mu * sqrDists[1]);
00269 if (max_sqr_fn_dist > sqrDists[nnn_-1])
00270 {
00271 if (0 == increase_nnn4fn)
00272 ROS_WARN("Not enough neighbors are considered: ffn or sfn out of range! Consider increasing nnn_... Setting R=%d to be BOUNDARY!\n", R_);
00273 increase_nnn4fn++;
00274 state_[R_] = BOUNDARY;
00275 continue;
00276 }
00277 double max_sqr_fns_dist = (std::max)(sqr_source_dist, max_sqr_fn_dist);
00278 if (max_sqr_fns_dist > sqrDists[nnn_-1])
00279 {
00280 if (0 == increase_nnn4s)
00281 ROS_WARN("Not enough neighbors are considered: source of R=%d is out of range! Consider increasing nnn_...\n", R_);
00282 increase_nnn4s++;
00283 }
00284
00285
00286 const Eigen::Vector3f nc = input_->points[(*indices_)[R_]].getNormalVector3fMap ();
00287
00288
00289 Eigen::Vector3f v = nc.unitOrthogonal ();
00290 Eigen::Vector3f u = nc.cross (v);
00291
00292
00293 double dist = nc.dot(coords_[R_]);
00294 proj_qp_ = coords_[R_] - dist * nc;
00295
00296
00297 int nr_edge = 0;
00298 std::vector<doubleEdge> doubleEdges;
00299 for (int i = 1; i < nnn_; i++)
00300 {
00301 tmp_ = coords_[nnIdx[i]] - proj_qp_;
00302 uvn_nn[i][0] = tmp_.dot(u);
00303 uvn_nn[i][1] = tmp_.dot(v);
00304
00305
00306 angles_[i].angle = atan2(uvn_nn[i][1], uvn_nn[i][0]);
00307
00308 angles_[i].index = nnIdx[i];
00309 angles_[i].nnIndex = i;
00310 if (
00311 (state_[nnIdx[i]] == COMPLETED) || (state_[nnIdx[i]] == BOUNDARY)
00312 || (sqrDists[i] > sqr_dist_threshold)
00313 )
00314 angles_[i].visible = false;
00315 else
00316 angles_[i].visible = true;
00317 if ((ffn_[R_] == nnIdx[i]) || (sfn_[R_] == nnIdx[i]))
00318 angles_[i].visible = true;
00319 bool same_side = true;
00320 const Eigen::Vector3f neighbor_normal = input_->points[(*indices_)[nnIdx[i]]].getNormalVector3fMap ();
00321 double cosine = nc.dot (neighbor_normal);
00322 if (cosine > 1) cosine = 1;
00323 if (cosine < -1) cosine = -1;
00324 double angle = acos (cosine);
00325 if ((!consistent_) && (angle > M_PI/2))
00326 angle = M_PI - angle;
00327 if (angle > eps_angle_)
00328 {
00329 angles_[i].visible = false;
00330 same_side = false;
00331 }
00332
00333 if ((i!=0) && (same_side) && ((state_[nnIdx[i]] == FRINGE) || (state_[nnIdx[i]] == BOUNDARY)))
00334 {
00335 doubleEdge e;
00336 e.index = i;
00337 nr_edge++;
00338 tmp_ = coords_[ffn_[nnIdx[i]]] - proj_qp_;
00339 e.first[0] = tmp_.dot(u);
00340 e.first[1] = tmp_.dot(v);
00341 tmp_ = coords_[sfn_[nnIdx[i]]] - proj_qp_;
00342 e.second[0] = tmp_.dot(u);
00343 e.second[1] = tmp_.dot(v);
00344 doubleEdges.push_back(e);
00345
00346 if ((state_[nnIdx[i]] == FRINGE) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i]))
00347 {
00348 double angle1 = atan2(e.first[1] - uvn_nn[i][1], e.first[0] - uvn_nn[i][0]);
00349 double angle2 = atan2(e.second[1] - uvn_nn[i][1], e.second[0] - uvn_nn[i][0]);
00350 double angleMin, angleMax;
00351 if (angle1 < angle2)
00352 {
00353 angleMin = angle1;
00354 angleMax = angle2;
00355 }
00356 else
00357 {
00358 angleMin = angle2;
00359 angleMax = angle1;
00360 }
00361 double angleR = angles_[i].angle + M_PI;
00362 if (angleR >= 2*M_PI)
00363 angleR -= 2*M_PI;
00364 if ((source_[nnIdx[i]] == ffn_[nnIdx[i]]) || (source_[nnIdx[i]] == sfn_[nnIdx[i]]))
00365 {
00366 if ((angleMax - angleMin) < M_PI)
00367 {
00368 if ((angleMin < angleR) && (angleR < angleMax))
00369 angles_[i].visible = false;
00370 }
00371 else
00372 {
00373 if ((angleR < angleMin) || (angleMax < angleR))
00374 angles_[i].visible = false;
00375 }
00376 }
00377 else
00378 {
00379 tmp_ = coords_[source_[nnIdx[i]]] - proj_qp_;
00380 uvn_s[0] = tmp_.dot(u);
00381 uvn_s[1] = tmp_.dot(v);
00382 double angleS = atan2(uvn_s[1] - uvn_nn[i][1], uvn_s[0] - uvn_nn[i][0]);
00383 if ((angleMin < angleS) && (angleS < angleMax))
00384 {
00385 if ((angleMin < angleR) && (angleR < angleMax))
00386 angles_[i].visible = false;
00387 }
00388 else
00389 {
00390 if ((angleR < angleMin) || (angleMax < angleR))
00391 angles_[i].visible = false;
00392 }
00393 }
00394 }
00395 }
00396 }
00397 angles_[0].visible = false;
00398
00399
00400 for (int i = 1; i < nnn_; i++)
00401 if ((angles_[i].visible) && (ffn_[R_] != nnIdx[i]) && (sfn_[R_] != nnIdx[i]))
00402 {
00403 bool visibility = true;
00404 for (int j = 0; j < nr_edge; j++)
00405 {
00406 if (doubleEdges[j].index != i)
00407 {
00408 int f = ffn_[nnIdx[doubleEdges[j].index]];
00409 if ((f != nnIdx[i]) && (f != R_))
00410 visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].first, Eigen::Vector2f::Zero());
00411 if (visibility == false)
00412 break;
00413
00414 int s = sfn_[nnIdx[doubleEdges[j].index]];
00415 if ((s != nnIdx[i]) && (s != R_))
00416 visibility = isVisible(uvn_nn[i], uvn_nn[doubleEdges[j].index], doubleEdges[j].second, Eigen::Vector2f::Zero());
00417 if (visibility == false)
00418 break;
00419 }
00420 }
00421 angles_[i].visible = visibility;
00422 }
00423
00424
00425 sort (angles_.begin (), angles_.end (), GreedyProjectionTriangulation<PointInT>::nnAngleSortAsc);
00426
00427
00428 if (angles_[2].visible == false)
00429 {
00430 if ( !( (angles_[0].index == ffn_[R_] && angles_[1].index == sfn_[R_]) || (angles_[0].index == sfn_[R_] && angles_[1].index == ffn_[R_]) ) )
00431 {
00432 state_[R_] = BOUNDARY;
00433 }
00434 else
00435 {
00436 if ((source_[R_] == angles_[0].index) || (source_[R_] == angles_[1].index))
00437 state_[R_] = BOUNDARY;
00438 else
00439 {
00440 if (sqr_max_edge < (coords_[ffn_[R_]] - coords_[sfn_[R_]]).squaredNorm ())
00441 {
00442 state_[R_] = BOUNDARY;
00443 }
00444 else
00445 {
00446 tmp_ = coords_[source_[R_]] - proj_qp_;
00447 uvn_s[0] = tmp_.dot(u);
00448 uvn_s[1] = tmp_.dot(v);
00449 double angleS = atan2(uvn_s[1], uvn_s[0]);
00450 double dif = angles_[1].angle - angles_[0].angle;
00451 if ((angles_[0].angle < angleS) && (angleS < angles_[1].angle))
00452 {
00453 if (dif < 2*M_PI - maximum_angle_)
00454 state_[R_] = BOUNDARY;
00455 else
00456 closeTriangle (output);
00457 }
00458 else
00459 {
00460 if (dif >= maximum_angle_)
00461 state_[R_] = BOUNDARY;
00462 else
00463 closeTriangle (output);
00464 }
00465 }
00466 }
00467 }
00468 continue;
00469 }
00470
00471
00472 int start = -1, end = -1;
00473 for (int i=0; i<nnn_; i++)
00474 {
00475 if (ffn_[R_] == angles_[i].index)
00476 {
00477 start = i;
00478 if (sfn_[R_] == angles_[i+1].index)
00479 end = i+1;
00480 else
00481 if (i==0)
00482 {
00483 for (i = i+2; i < nnn_; i++)
00484 if (sfn_[R_] == angles_[i].index)
00485 break;
00486 end = i;
00487 }
00488 else
00489 {
00490 for (i = i+2; i < nnn_; i++)
00491 if (sfn_[R_] == angles_[i].index)
00492 break;
00493 end = i;
00494 }
00495 break;
00496 }
00497 if (sfn_[R_] == angles_[i].index)
00498 {
00499 start = i;
00500 if (ffn_[R_] == angles_[i+1].index)
00501 end = i+1;
00502 else
00503 if (i==0)
00504 {
00505 for (i = i+2; i < nnn_; i++)
00506 if (ffn_[R_] == angles_[i].index)
00507 break;
00508 end = i;
00509 }
00510 else
00511 {
00512 for (i = i+2; i < nnn_; i++)
00513 if (ffn_[R_] == angles_[i].index)
00514 break;
00515 end = i;
00516 }
00517 break;
00518 }
00519 }
00520
00521
00522 if ((start < 0) || (end < 0) || (end == nnn_) || (!angles_[start].visible) || (!angles_[end].visible))
00523 {
00524 state_[R_] = BOUNDARY;
00525 continue;
00526 }
00527
00528
00529 int last_visible = end;
00530 while ((last_visible+1<nnn_) && (angles_[last_visible+1].visible)) last_visible++;
00531
00532
00533 bool need_invert = false;
00534 int sourceIdx = nnn_;
00535 if ((source_[R_] == ffn_[R_]) || (source_[R_] == sfn_[R_]))
00536 {
00537 if ((angles_[end].angle - angles_[start].angle) < M_PI)
00538 need_invert = true;
00539 }
00540 else
00541 {
00542 for (sourceIdx=0; sourceIdx<nnn_; sourceIdx++)
00543 if (angles_[sourceIdx].index == source_[R_])
00544 break;
00545 if (sourceIdx == nnn_)
00546 {
00547 int vis_free = NONE, nnCB = NONE;
00548 for (int i=0; i<nnn_; i++)
00549 {
00550
00551 if ((state_[nnIdx[i]] == COMPLETED) || (state_[nnIdx[i]] == BOUNDARY))
00552 {
00553 if (nnCB == NONE)
00554 {
00555 nnCB = i;
00556 if (vis_free != NONE)
00557 break;
00558 }
00559 }
00560
00561 if (state_[angles_[i].index] <= FREE)
00562 {
00563 if (i <= last_visible)
00564 {
00565 vis_free = i;
00566 if (nnCB != NONE)
00567 break;
00568 }
00569 }
00570 }
00571
00572 int nCB = 0;
00573 if (nnCB != NONE)
00574 while (angles_[nCB].index != nnIdx[nnCB]) nCB++;
00575 else
00576 nCB = NONE;
00577
00578 if (vis_free != NONE)
00579 {
00580 if ((vis_free < start) || (vis_free > end))
00581 need_invert = true;
00582 }
00583 else
00584 {
00585 if (nCB != NONE)
00586 {
00587 if ((nCB == start) || (nCB == end))
00588 {
00589 bool inside_CB = false;
00590 bool outside_CB = false;
00591 for (int i=0; i<nnn_; i++)
00592 {
00593 if (
00594 ((state_[angles_[i].index] == COMPLETED) || (state_[angles_[i].index] == BOUNDARY))
00595 && (i != start) && (i != end)
00596 )
00597 {
00598 if ((angles_[start].angle <= angles_[i].angle) && (angles_[i].angle <= angles_[end].angle))
00599 {
00600 inside_CB = true;
00601 if (outside_CB)
00602 break;
00603 }
00604 else
00605 {
00606 outside_CB = true;
00607 if (inside_CB)
00608 break;
00609 }
00610 }
00611 }
00612 if (inside_CB && !outside_CB)
00613 need_invert = true;
00614 else if (!(!inside_CB && outside_CB))
00615 {
00616 if ((angles_[end].angle - angles_[start].angle) < M_PI)
00617 need_invert = true;
00618 }
00619 }
00620 else
00621 {
00622 if ((angles_[nCB].angle > angles_[start].angle) && (angles_[nCB].angle < angles_[end].angle))
00623 need_invert = true;
00624 }
00625 }
00626 else
00627 {
00628 if (start == end-1)
00629 need_invert = true;
00630 }
00631 }
00632 }
00633 else if ((angles_[start].angle < angles_[sourceIdx].angle) && (angles_[sourceIdx].angle < angles_[end].angle))
00634 need_invert = true;
00635 }
00636
00637
00638 if (need_invert)
00639 {
00640 int tmp = start;
00641 start = end;
00642 end = tmp;
00643 }
00644
00645
00646
00647 bool is_boundary = false, is_skinny = false;
00648 std::vector<bool> gaps (nnn_, false);
00649 std::vector<bool> skinny (nnn_, false);
00650 std::vector<double> dif (nnn_);
00651 std::vector<int> angleIdx; angleIdx.reserve (nnn_);
00652 if (start > end)
00653 {
00654 for (int j=start; j<last_visible; j++)
00655 {
00656 dif[j] = (angles_[j+1].angle - angles_[j].angle);
00657 if (dif[j] < minimum_angle_)
00658 {
00659 skinny[j] = is_skinny = true;
00660 }
00661 else if (maximum_angle_ <= dif[j])
00662 {
00663 gaps[j] = is_boundary = true;
00664 }
00665 if ((!gaps[j]) && (sqr_max_edge < (coords_[angles_[j+1].index] - coords_[angles_[j].index]).squaredNorm ()))
00666 {
00667 gaps[j] = is_boundary = true;
00668 }
00669 angleIdx.push_back(j);
00670 }
00671
00672 dif[last_visible] = (2*M_PI + angles_[0].angle - angles_[last_visible].angle);
00673 if (dif[last_visible] < minimum_angle_)
00674 {
00675 skinny[last_visible] = is_skinny = true;
00676 }
00677 else if (maximum_angle_ <= dif[last_visible])
00678 {
00679 gaps[last_visible] = is_boundary = true;
00680 }
00681 if ((!gaps[last_visible]) && (sqr_max_edge < (coords_[angles_[0].index], coords_[angles_[last_visible].index]).squaredNorm ()))
00682 {
00683 gaps[last_visible] = is_boundary = true;
00684 }
00685 angleIdx.push_back(last_visible);
00686
00687 for (int j=0; j<end; j++)
00688 {
00689 dif[j] = (angles_[j+1].angle - angles_[j].angle);
00690 if (dif[j] < minimum_angle_)
00691 {
00692 skinny[j] = is_skinny = true;
00693 }
00694 else if (maximum_angle_ <= dif[j])
00695 {
00696 gaps[j] = is_boundary = true;
00697 }
00698 if ((!gaps[j]) && (sqr_max_edge < (coords_[angles_[j+1].index], coords_[angles_[j].index]).squaredNorm ()))
00699 {
00700 gaps[j] = is_boundary = true;
00701 }
00702 angleIdx.push_back(j);
00703 }
00704 angleIdx.push_back(end);
00705 }
00706
00707 else
00708 {
00709 for (int j=start; j<end; j++)
00710 {
00711 dif[j] = (angles_[j+1].angle - angles_[j].angle);
00712 if (dif[j] < minimum_angle_)
00713 {
00714 skinny[j] = is_skinny = true;
00715 }
00716 else if (maximum_angle_ <= dif[j])
00717 {
00718 gaps[j] = is_boundary = true;
00719 }
00720 if ((!gaps[j]) && (sqr_max_edge < (coords_[angles_[j+1].index], coords_[angles_[j].index]).squaredNorm ()))
00721 {
00722 gaps[j] = is_boundary = true;
00723 }
00724 angleIdx.push_back(j);
00725 }
00726 angleIdx.push_back(end);
00727 }
00728
00729
00730 state_[R_] = is_boundary ? BOUNDARY : COMPLETED;
00731
00732 std::vector<int>::iterator first_gap_after = angleIdx.end ();
00733 std::vector<int>::iterator last_gap_before = angleIdx.begin ();
00734 int nr_gaps = 0;
00735 for (std::vector<int>::iterator it = angleIdx.begin (); it != angleIdx.end () - 1; it++)
00736 {
00737 if (gaps[*it])
00738 {
00739 nr_gaps++;
00740 if (first_gap_after == angleIdx.end())
00741 first_gap_after = it;
00742 last_gap_before = it+1;
00743 }
00744 }
00745 if (nr_gaps > 1)
00746 {
00747 angleIdx.erase(first_gap_after+1, last_gap_before);
00748 }
00749
00750
00751 if (is_skinny)
00752 {
00753 double angle_so_far = 0, angle_would_be;
00754 double max_combined_angle = (std::min)(maximum_angle_, M_PI-2*minimum_angle_);
00755 Eigen::Vector2f X;
00756 Eigen::Vector2f S1;
00757 Eigen::Vector2f S2;
00758 std::vector<int> to_erase;
00759 for (std::vector<int>::iterator it = angleIdx.begin()+1; it != angleIdx.end()-1; it++)
00760 {
00761 if (gaps[*(it-1)])
00762 angle_so_far = 0;
00763 else
00764 angle_so_far += dif[*(it-1)];
00765 if (gaps[*it])
00766 angle_would_be = angle_so_far;
00767 else
00768 angle_would_be = angle_so_far + dif[*it];
00769 if (
00770 (skinny[*it] || skinny[*(it-1)]) &&
00771 ((state_[angles_[*it].index] <= FREE) || (state_[angles_[*(it-1)].index] <= FREE)) &&
00772 ((!gaps[*it]) || (angles_[*it].nnIndex > angles_[*(it-1)].nnIndex)) &&
00773 ((!gaps[*(it-1)]) || (angles_[*it].nnIndex > angles_[*(it+1)].nnIndex)) &&
00774 (angle_would_be < max_combined_angle)
00775 )
00776 {
00777 if (gaps[*(it-1)])
00778 {
00779 gaps[*it] = true;
00780 to_erase.push_back(*it);
00781 }
00782 else if (gaps[*it])
00783 {
00784 gaps[*(it-1)] = true;
00785 to_erase.push_back(*it);
00786 }
00787 else
00788 {
00789 std::vector<int>::iterator prev_it;
00790 int erased_idx = to_erase.size()-1;
00791 for (prev_it = it-1; (erased_idx != -1) && (it != angleIdx.begin()); it--)
00792 if (*it == to_erase[erased_idx])
00793 erased_idx--;
00794 else
00795 break;
00796 bool can_delete = true;
00797 for (std::vector<int>::iterator curr_it = prev_it+1; curr_it != it+1; curr_it++)
00798 {
00799 tmp_ = coords_[angles_[*curr_it].index] - proj_qp_;
00800 X[0] = tmp_.dot(u);
00801 X[1] = tmp_.dot(v);
00802 tmp_ = coords_[angles_[*prev_it].index] - proj_qp_;
00803 S1[0] = tmp_.dot(u);
00804 S1[1] = tmp_.dot(v);
00805 tmp_ = coords_[angles_[*(it+1)].index] - proj_qp_;
00806 S2[0] = tmp_.dot(u);
00807 S2[1] = tmp_.dot(v);
00808
00809 if (isVisible(X,S1,S2))
00810 {
00811 can_delete = false;
00812 angle_so_far = 0;
00813 break;
00814 }
00815 }
00816 if (can_delete)
00817 {
00818 to_erase.push_back(*it);
00819 }
00820 }
00821 }
00822 else
00823 angle_so_far = 0;
00824 }
00825 for (std::vector<int>::iterator it = to_erase.begin(); it != to_erase.end(); it++)
00826 {
00827 for (std::vector<int>::iterator iter = angleIdx.begin(); iter != angleIdx.end(); iter++)
00828 if (*it == *iter)
00829 {
00830 angleIdx.erase(iter);
00831 break;
00832 }
00833 }
00834 }
00835
00836
00837 changed_1st_fn_ = false;
00838 changed_2nd_fn_ = false;
00839 new2boundary_ = NONE;
00840 for (std::vector<int>::iterator it = angleIdx.begin()+1; it != angleIdx.end()-1; it++)
00841 {
00842 current_index_ = angles_[*it].index;
00843
00844 is_current_free_ = false;
00845 if (state_[current_index_] <= FREE)
00846 {
00847 state_[current_index_] = FRINGE;
00848 is_current_free_ = true;
00849 }
00850 else if (!already_connected_)
00851 {
00852 prev_is_ffn_ = (ffn_[current_index_] == angles_[*(it-1)].index) && (!gaps[*(it-1)]);
00853 prev_is_sfn_ = (sfn_[current_index_] == angles_[*(it-1)].index) && (!gaps[*(it-1)]);
00854 next_is_ffn_ = (ffn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]);
00855 next_is_sfn_ = (sfn_[current_index_] == angles_[*(it+1)].index) && (!gaps[*it]);
00856 if (!prev_is_ffn_ && !next_is_sfn_ && !prev_is_sfn_ && !next_is_ffn_)
00857 {
00858 nr_touched++;
00859 }
00860 }
00861
00862 if (gaps[*it])
00863 if (gaps[*(it-1)])
00864 {
00865 if (is_current_free_)
00866 state_[current_index_] = NONE;
00867 }
00868
00869 else
00870 {
00871 addTriangle (current_index_, angles_[*(it-1)].index, R_, output);
00872 addFringePoint (current_index_, R_);
00873 new2boundary_ = current_index_;
00874 if (!already_connected_)
00875 connectPoint (output, angles_[*(it-1)].index, R_,
00876 angles_[*(it+1)].index,
00877 uvn_nn[angles_[*it].nnIndex], uvn_nn[angles_[*(it-1)].nnIndex], uvn_nn_qp_zero);
00878 else already_connected_ = false;
00879 if (ffn_[R_] == angles_[*(angleIdx.begin())].index)
00880 {
00881 ffn_[R_] = new2boundary_;
00882 }
00883 else if (sfn_[R_] == angles_[*(angleIdx.begin())].index)
00884 {
00885 sfn_[R_] = new2boundary_;
00886 }
00887 }
00888
00889 else
00890 if (gaps[*(it-1)])
00891 {
00892 addFringePoint (current_index_, R_);
00893 new2boundary_ = current_index_;
00894 if (!already_connected_) connectPoint(output, R_, angles_[*(it+1)].index,
00895 (it+2) == angleIdx.end() ? -1 : angles_[*(it+2)].index,
00896 uvn_nn[angles_[*it].nnIndex], uvn_nn_qp_zero, uvn_nn[angles_[*(it+1)].nnIndex]);
00897 else already_connected_ = false;
00898 if (ffn_[R_] == angles_[*(angleIdx.end()-1)].index)
00899 {
00900 ffn_[R_] = new2boundary_;
00901 }
00902 else if (sfn_[R_] == angles_[*(angleIdx.end()-1)].index)
00903 {
00904 sfn_[R_] = new2boundary_;
00905 }
00906 }
00907
00908 else
00909 {
00910 addTriangle (current_index_, angles_[*(it-1)].index, R_, output);
00911 addFringePoint (current_index_, R_);
00912 if (!already_connected_) connectPoint(output, angles_[*(it-1)].index, angles_[*(it+1)].index,
00913 (it+2) == angleIdx.end() ? -1 : gaps[*(it+1)] ? R_ : angles_[*(it+2)].index,
00914 uvn_nn[angles_[*it].nnIndex], uvn_nn[angles_[*(it-1)].nnIndex], uvn_nn[angles_[*(it+1)].nnIndex]);
00915 else already_connected_ = false;
00916 }
00917 }
00918 if (ffn_[R_] == sfn_[R_])
00919 {
00920 state_[R_] = COMPLETED;
00921 }
00922 if (!gaps[*(angleIdx.end()-2)])
00923 {
00924 addTriangle (angles_[*(angleIdx.end()-2)].index, angles_[*(angleIdx.end()-1)].index, R_, output);
00925 addFringePoint (angles_[*(angleIdx.end()-2)].index, R_);
00926 if (R_ == ffn_[angles_[*(angleIdx.end()-1)].index])
00927 {
00928 if (angles_[*(angleIdx.end()-2)].index == sfn_[angles_[*(angleIdx.end()-1)].index])
00929 {
00930 state_[angles_[*(angleIdx.end()-1)].index] = COMPLETED;
00931 }
00932 else
00933 {
00934 ffn_[angles_[*(angleIdx.end()-1)].index] = angles_[*(angleIdx.end()-2)].index;
00935 }
00936 }
00937 else if (R_ == sfn_[angles_[*(angleIdx.end()-1)].index])
00938 {
00939 if (angles_[*(angleIdx.end()-2)].index == ffn_[angles_[*(angleIdx.end()-1)].index])
00940 {
00941 state_[angles_[*(angleIdx.end()-1)].index] = COMPLETED;
00942 }
00943 else
00944 {
00945 sfn_[angles_[*(angleIdx.end()-1)].index] = angles_[*(angleIdx.end()-2)].index;
00946 }
00947 }
00948 }
00949 if (!gaps[*(angleIdx.begin())])
00950 {
00951 if (R_ == ffn_[angles_[*(angleIdx.begin())].index])
00952 {
00953 if (angles_[*(angleIdx.begin()+1)].index == sfn_[angles_[*(angleIdx.begin())].index])
00954 {
00955 state_[angles_[*(angleIdx.begin())].index] = COMPLETED;
00956 }
00957 else
00958 {
00959 ffn_[angles_[*(angleIdx.begin())].index] = angles_[*(angleIdx.begin()+1)].index;
00960 }
00961 }
00962 else if (R_ == sfn_[angles_[*(angleIdx.begin())].index])
00963 {
00964 if (angles_[*(angleIdx.begin()+1)].index == ffn_[angles_[*(angleIdx.begin())].index])
00965 {
00966 state_[angles_[*(angleIdx.begin())].index] = COMPLETED;
00967 }
00968 else
00969 {
00970 sfn_[angles_[*(angleIdx.begin())].index] = angles_[*(angleIdx.begin()+1)].index;
00971 }
00972 }
00973 }
00974 }
00975 }
00976 ROS_DEBUG ("Number of triangles: %d", (int)output.polygons.size());
00977 ROS_DEBUG ("Number of unconnected parts: %d", nr_parts);
00978 if (increase_nnn4fn > 0)
00979 ROS_WARN ("Number of neighborhood size increase requests for fringe neighbors: %d", increase_nnn4fn);
00980 if (increase_nnn4s > 0)
00981 ROS_WARN ("Number of neighborhood size increase requests for source: %d", increase_nnn4s);
00982 if (increase_dist > 0)
00983 ROS_WARN ("Number of automatic maximum distance increases: %d", increase_dist);
00984
00985
00986 sort(fringe_queue_.begin(), fringe_queue_.end());
00987 fringe_queue_.erase(unique(fringe_queue_.begin(), fringe_queue_.end()), fringe_queue_.end());
00988 ROS_DEBUG ("Number of processed points: %d / %d", (int)fringe_queue_.size(), (int)indices_->size ());
00989 }
00990
00992 template <typename PointInT> void
00993 pcl::GreedyProjectionTriangulation<PointInT>::closeTriangle (pcl::PolygonMesh &output)
00994 {
00995 state_[R_] = COMPLETED;
00996 addTriangle (angles_[0].index, angles_[1].index, R_, output);
00997 short hole[2] = {0,0};
00998 for (int aIdx=0; aIdx<2; aIdx++)
00999 {
01000 if (ffn_[angles_[aIdx].index] == R_)
01001 {
01002 if (sfn_[angles_[aIdx].index] == angles_[(aIdx+1)%2].index)
01003 {
01004 hole[aIdx] = 1;
01005 state_[angles_[aIdx].index] = COMPLETED;
01006 }
01007 else
01008 {
01009 ffn_[angles_[aIdx].index] = angles_[(aIdx+1)%2].index;
01010 }
01011 }
01012 else if (sfn_[angles_[aIdx].index] == R_)
01013 {
01014 if (ffn_[angles_[aIdx].index] == angles_[(aIdx+1)%2].index)
01015 {
01016 hole[aIdx] = 1;
01017 state_[angles_[aIdx].index] = COMPLETED;
01018 }
01019 else
01020 {
01021 sfn_[angles_[aIdx].index] = angles_[(aIdx+1)%2].index;
01022 }
01023 }
01024 }
01025 }
01026
01028 template <typename PointInT> void
01029 pcl::GreedyProjectionTriangulation<PointInT>::connectPoint (
01030 pcl::PolygonMesh &output,
01031 const int prev_index, const int next_index, const int next_next_index,
01032 const Eigen::Vector2f &uvn_current,
01033 const Eigen::Vector2f &uvn_prev,
01034 const Eigen::Vector2f &uvn_next)
01035 {
01036 if (is_current_free_)
01037 {
01038 ffn_[current_index_] = prev_index;
01039 sfn_[current_index_] = next_index;
01040 }
01041 else
01042 {
01043 if ((prev_is_ffn_ && next_is_sfn_) || (prev_is_sfn_ && next_is_ffn_))
01044 {
01045 state_[current_index_] = COMPLETED;
01046 }
01047 else if (prev_is_ffn_ && !next_is_sfn_)
01048 {
01049 ffn_[current_index_] = next_index;
01050 }
01051 else if (next_is_ffn_ && !prev_is_sfn_)
01052 {
01053 ffn_[current_index_] = prev_index;
01054 }
01055 else if (prev_is_sfn_ && !next_is_ffn_)
01056 {
01057 sfn_[current_index_] = next_index;
01058 }
01059 else if (next_is_sfn_ && !prev_is_ffn_)
01060 {
01061 sfn_[current_index_] = prev_index;
01062 }
01063 else
01064 {
01065 bool found_triangle = false;
01066 if ((prev_index != R_) && ((ffn_[current_index_] == ffn_[prev_index]) || (ffn_[current_index_] == sfn_[prev_index])))
01067 {
01068 found_triangle = true;
01069 addTriangle (current_index_, ffn_[current_index_], prev_index, output);
01070 state_[prev_index] = COMPLETED;
01071 state_[ffn_[current_index_]] = COMPLETED;
01072 ffn_[current_index_] = next_index;
01073 }
01074 else if ((prev_index != R_) && ((sfn_[current_index_] == ffn_[prev_index]) || (sfn_[current_index_] == sfn_[prev_index])))
01075 {
01076 found_triangle = true;
01077 addTriangle (current_index_, sfn_[current_index_], prev_index, output);
01078 state_[prev_index] = COMPLETED;
01079 state_[sfn_[current_index_]] = COMPLETED;
01080 sfn_[current_index_] = next_index;
01081 }
01082 else if (state_[next_index] > FREE)
01083 {
01084 if ((ffn_[current_index_] == ffn_[next_index]) || (ffn_[current_index_] == sfn_[next_index]))
01085 {
01086 found_triangle = true;
01087 addTriangle (current_index_, ffn_[current_index_], next_index, output);
01088
01089 if (ffn_[current_index_] == ffn_[next_index])
01090 {
01091 ffn_[next_index] = current_index_;
01092 }
01093 else
01094 {
01095 sfn_[next_index] = current_index_;
01096 }
01097 state_[ffn_[current_index_]] = COMPLETED;
01098 ffn_[current_index_] = prev_index;
01099 }
01100 else if ((sfn_[current_index_] == ffn_[next_index]) || (sfn_[current_index_] == sfn_[next_index]))
01101 {
01102 found_triangle = true;
01103 addTriangle (current_index_, sfn_[current_index_], next_index, output);
01104
01105 if (sfn_[current_index_] == ffn_[next_index])
01106 {
01107 ffn_[next_index] = current_index_;
01108 }
01109 else
01110 {
01111 sfn_[next_index] = current_index_;
01112 }
01113 state_[sfn_[current_index_]] = COMPLETED;
01114 sfn_[current_index_] = prev_index;
01115 }
01116 }
01117
01118 if (found_triangle)
01119 {
01120 }
01121 else
01122 {
01123 tmp_ = coords_[ffn_[current_index_]] - proj_qp_;
01124 uvn_ffn_[0] = tmp_.dot(u_);
01125 uvn_ffn_[1] = tmp_.dot(v_);
01126 tmp_ = coords_[sfn_[current_index_]] - proj_qp_;
01127 uvn_sfn_[0] = tmp_.dot(u_);
01128 uvn_sfn_[1] = tmp_.dot(v_);
01129 bool prev_ffn = isVisible(uvn_prev, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_prev, uvn_sfn_, uvn_current, uvn_ffn_);
01130 bool prev_sfn = isVisible(uvn_prev, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_prev, uvn_ffn_, uvn_current, uvn_sfn_);
01131 bool next_ffn = isVisible(uvn_next, uvn_prev, uvn_current, uvn_ffn_) && isVisible(uvn_next, uvn_sfn_, uvn_current, uvn_ffn_);
01132 bool next_sfn = isVisible(uvn_next, uvn_prev, uvn_current, uvn_sfn_) && isVisible(uvn_next, uvn_ffn_, uvn_current, uvn_sfn_);
01133 int min_dist = -1;
01134 if (prev_ffn && next_sfn && prev_sfn && next_ffn)
01135 {
01137 double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01138 double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm ();
01139 double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01140 double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm ();
01141 if (prev2f < prev2s)
01142 {
01143 if (prev2f < next2f)
01144 {
01145 if (prev2f < next2s)
01146 min_dist = 0;
01147 else
01148 min_dist = 3;
01149 }
01150 else
01151 {
01152 if (next2f < next2s)
01153 min_dist = 2;
01154 else
01155 min_dist = 3;
01156 }
01157 }
01158 else
01159 {
01160 if (prev2s < next2f)
01161 {
01162 if (prev2s < next2s)
01163 min_dist = 1;
01164 else
01165 min_dist = 3;
01166 }
01167 else
01168 {
01169 if (next2f < next2s)
01170 min_dist = 2;
01171 else
01172 min_dist = 3;
01173 }
01174 }
01175 }
01176 else if (prev_ffn && next_sfn)
01177 {
01179 double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01180 double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm ();
01181 if (prev2f < next2s)
01182 min_dist = 0;
01183 else
01184 min_dist = 3;
01185 }
01186 else if (prev_sfn && next_ffn)
01187 {
01189 double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01190 double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm ();
01191 if (prev2s < next2f)
01192 min_dist = 1;
01193 else
01194 min_dist = 2;
01195 }
01197 else if (prev_ffn && !next_sfn && !prev_sfn && !next_ffn)
01198 min_dist = 0;
01199 else if (!prev_ffn && !next_sfn && prev_sfn && !next_ffn)
01200 min_dist = 1;
01201 else if (!prev_ffn && !next_sfn && !prev_sfn && next_ffn)
01202 min_dist = 2;
01203 else if (!prev_ffn && next_sfn && !prev_sfn && !next_ffn)
01204 min_dist = 3;
01206 else if (prev_ffn)
01207 {
01208 double prev2f = (coords_[ffn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01209 if (prev_sfn)
01210 {
01211 double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01212 if (prev2s < prev2f)
01213 min_dist = 1;
01214 else
01215 min_dist = 0;
01216 }
01217 else if (next_ffn)
01218 {
01219 double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm ();
01220 if (next2f < prev2f)
01221 min_dist = 2;
01222 else
01223 min_dist = 0;
01224 }
01225 }
01226 else if (next_sfn)
01227 {
01228 double next2s = (coords_[sfn_[current_index_]] - coords_[next_index]).squaredNorm ();
01229 if (prev_sfn)
01230 {
01231 double prev2s = (coords_[sfn_[current_index_]] - coords_[prev_index]).squaredNorm ();
01232 if (prev2s < next2s)
01233 min_dist = 1;
01234 else
01235 min_dist = 3;
01236 }
01237 else if (next_ffn)
01238 {
01239 double next2f = (coords_[ffn_[current_index_]] - coords_[next_index]).squaredNorm ();
01240 if (next2f < next2s)
01241 min_dist = 2;
01242 else
01243 min_dist = 3;
01244 }
01245 }
01246 switch (min_dist)
01247 {
01248 case 0:
01249 {
01250 addTriangle (current_index_, ffn_[current_index_], prev_index, output);
01251
01253 if (ffn_[prev_index] == current_index_)
01254 {
01255 ffn_[prev_index] = ffn_[current_index_];
01256 }
01257 else if (sfn_[prev_index] == current_index_)
01258 {
01259 sfn_[prev_index] = ffn_[current_index_];
01260 }
01261 else if (ffn_[prev_index] == R_)
01262 {
01263 changed_1st_fn_ = true;
01264 ffn_[prev_index] = ffn_[current_index_];
01265 }
01266 else if (sfn_[prev_index] == R_)
01267 {
01268 changed_1st_fn_ = true;
01269 sfn_[prev_index] = ffn_[current_index_];
01270 }
01271 else if (prev_index == R_)
01272 {
01273 new2boundary_ = ffn_[current_index_];
01274 }
01275
01277 if (ffn_[ffn_[current_index_]] == current_index_)
01278 {
01279 ffn_[ffn_[current_index_]] = prev_index;
01280 }
01281 else if (sfn_[ffn_[current_index_]] == current_index_)
01282 {
01283 sfn_[ffn_[current_index_]] = prev_index;
01284 }
01285
01287 ffn_[current_index_] = next_index;
01288
01289 break;
01290 }
01291 case 1:
01292 {
01293 addTriangle (current_index_, sfn_[current_index_], prev_index, output);
01294
01296 if (ffn_[prev_index] == current_index_)
01297 {
01298 ffn_[prev_index] = sfn_[current_index_];
01299 }
01300 else if (sfn_[prev_index] == current_index_)
01301 {
01302 sfn_[prev_index] = sfn_[current_index_];
01303 }
01304 else if (ffn_[prev_index] == R_)
01305 {
01306 changed_1st_fn_ = true;
01307 ffn_[prev_index] = sfn_[current_index_];
01308 }
01309 else if (sfn_[prev_index] == R_)
01310 {
01311 changed_1st_fn_ = true;
01312 sfn_[prev_index] = sfn_[current_index_];
01313 }
01314 else if (prev_index == R_)
01315 {
01316 new2boundary_ = sfn_[current_index_];
01317 }
01318
01320 if (ffn_[sfn_[current_index_]] == current_index_)
01321 {
01322 ffn_[sfn_[current_index_]] = prev_index;
01323 }
01324 else if (sfn_[sfn_[current_index_]] == current_index_)
01325 {
01326 sfn_[sfn_[current_index_]] = prev_index;
01327 }
01328
01330 sfn_[current_index_] = next_index;
01331
01332 break;
01333 }
01334 case 2:
01335 {
01336 addTriangle (current_index_, ffn_[current_index_], next_index, output);
01337 int neighbor_update = next_index;
01338
01340 if (state_[next_index] <= FREE)
01341 {
01342 state_[next_index] = FRINGE;
01343 ffn_[next_index] = current_index_;
01344 sfn_[next_index] = ffn_[current_index_];
01345 }
01346 else
01347 {
01348 if (ffn_[next_index] == R_)
01349 {
01350 changed_2nd_fn_ = true;
01351 ffn_[next_index] = ffn_[current_index_];
01352 }
01353 else if (sfn_[next_index] == R_)
01354 {
01355 changed_2nd_fn_ = true;
01356 sfn_[next_index] = ffn_[current_index_];
01357 }
01358 else if (next_index == R_)
01359 {
01360 new2boundary_ = ffn_[current_index_];
01361 if (next_next_index == new2boundary_)
01362 already_connected_ = true;
01363 }
01364 else if (ffn_[next_index] == next_next_index)
01365 {
01366 already_connected_ = true;
01367 ffn_[next_index] = ffn_[current_index_];
01368 }
01369 else if (sfn_[next_index] == next_next_index)
01370 {
01371 already_connected_ = true;
01372 sfn_[next_index] = ffn_[current_index_];
01373 }
01374 else
01375 {
01376 tmp_ = coords_[ffn_[next_index]] - proj_qp_;
01377 uvn_next_ffn_[0] = tmp_.dot(u_);
01378 uvn_next_ffn_[1] = tmp_.dot(v_);
01379 tmp_ = coords_[sfn_[next_index]] - proj_qp_;
01380 uvn_next_sfn_[0] = tmp_.dot(u_);
01381 uvn_next_sfn_[1] = tmp_.dot(v_);
01382
01383 bool ffn_next_ffn = isVisible(uvn_next_ffn_, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_next_ffn_, uvn_next, uvn_next_sfn_, uvn_ffn_);
01384 bool sfn_next_ffn = isVisible(uvn_next_sfn_, uvn_next, uvn_current, uvn_ffn_) && isVisible(uvn_next_sfn_, uvn_next, uvn_next_ffn_, uvn_ffn_);
01385
01386 int connect2ffn = -1;
01387 if (ffn_next_ffn && sfn_next_ffn)
01388 {
01389 double fn2f = (coords_[ffn_[current_index_]] - coords_[ffn_[next_index]]).squaredNorm ();
01390 double sn2f = (coords_[ffn_[current_index_]] - coords_[sfn_[next_index]]).squaredNorm ();
01391 if (fn2f < sn2f) connect2ffn = 0;
01392 else connect2ffn = 1;
01393 }
01394 else if (ffn_next_ffn) connect2ffn = 0;
01395 else if (sfn_next_ffn) connect2ffn = 1;
01396
01397 switch (connect2ffn)
01398 {
01399 case 0:
01400 {
01401 addTriangle (next_index, ffn_[current_index_], ffn_[next_index], output);
01402 neighbor_update = ffn_[next_index];
01403
01405 if ((ffn_[ffn_[next_index]] == ffn_[current_index_]) || (sfn_[ffn_[next_index]] == ffn_[current_index_]))
01406 {
01407 state_[ffn_[next_index]] = COMPLETED;
01408 }
01409 else if (ffn_[ffn_[next_index]] == next_index)
01410 {
01411 ffn_[ffn_[next_index]] = ffn_[current_index_];
01412 }
01413 else if (sfn_[ffn_[next_index]] == next_index)
01414 {
01415 sfn_[ffn_[next_index]] = ffn_[current_index_];
01416 }
01417
01418 ffn_[next_index] = current_index_;
01419
01420 break;
01421 }
01422 case 1:
01423 {
01424 addTriangle (next_index, ffn_[current_index_], sfn_[next_index], output);
01425 neighbor_update = sfn_[next_index];
01426
01428 if ((ffn_[sfn_[next_index]] = ffn_[current_index_]) || (sfn_[sfn_[next_index]] == ffn_[current_index_]))
01429 {
01430 state_[sfn_[next_index]] = COMPLETED;
01431 }
01432 else if (ffn_[sfn_[next_index]] == next_index)
01433 {
01434 ffn_[sfn_[next_index]] = ffn_[current_index_];
01435 }
01436 else if (sfn_[sfn_[next_index]] == next_index)
01437 {
01438 sfn_[sfn_[next_index]] = ffn_[current_index_];
01439 }
01440
01441 sfn_[next_index] = current_index_;
01442
01443 break;
01444 }
01445 default:;
01446 }
01447 }
01448 }
01449
01451 if ((ffn_[ffn_[current_index_]] == neighbor_update) || (sfn_[ffn_[current_index_]] == neighbor_update))
01452 {
01453 state_[ffn_[current_index_]] = COMPLETED;
01454 }
01455 else if (ffn_[ffn_[current_index_]] == current_index_)
01456 {
01457 ffn_[ffn_[current_index_]] = neighbor_update;
01458 }
01459 else if (sfn_[ffn_[current_index_]] == current_index_)
01460 {
01461 sfn_[ffn_[current_index_]] = neighbor_update;
01462 }
01463
01465 ffn_[current_index_] = prev_index;
01466
01467 break;
01468 }
01469 case 3:
01470 {
01471 addTriangle (current_index_, sfn_[current_index_], next_index, output);
01472 int neighbor_update = next_index;
01473
01475 if (state_[next_index] <= FREE)
01476 {
01477 state_[next_index] = FRINGE;
01478 ffn_[next_index] = current_index_;
01479 sfn_[next_index] = sfn_[current_index_];
01480 }
01481 else
01482 {
01483 if (ffn_[next_index] == R_)
01484 {
01485 changed_2nd_fn_ = true;
01486 ffn_[next_index] = sfn_[current_index_];
01487 }
01488 else if (sfn_[next_index] == R_)
01489 {
01490 changed_2nd_fn_ = true;
01491 sfn_[next_index] = sfn_[current_index_];
01492 }
01493 else if (next_index == R_)
01494 {
01495 new2boundary_ = sfn_[current_index_];
01496 if (next_next_index == new2boundary_)
01497 already_connected_ = true;
01498 }
01499 else if (ffn_[next_index] == next_next_index)
01500 {
01501 already_connected_ = true;
01502 ffn_[next_index] = sfn_[current_index_];
01503 }
01504 else if (sfn_[next_index] == next_next_index)
01505 {
01506 already_connected_ = true;
01507 sfn_[next_index] = sfn_[current_index_];
01508 }
01509 else
01510 {
01511 tmp_ = coords_[ffn_[next_index]] - proj_qp_;
01512 uvn_next_ffn_[0] = tmp_.dot(u_);
01513 uvn_next_ffn_[1] = tmp_.dot(v_);
01514 tmp_ = coords_[sfn_[next_index]] - proj_qp_;
01515 uvn_next_sfn_[0] = tmp_.dot(u_);
01516 uvn_next_sfn_[1] = tmp_.dot(v_);
01517
01518 bool ffn_next_sfn = isVisible(uvn_next_ffn_, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_next_ffn_, uvn_next, uvn_next_sfn_, uvn_sfn_);
01519 bool sfn_next_sfn = isVisible(uvn_next_sfn_, uvn_next, uvn_current, uvn_sfn_) && isVisible(uvn_next_sfn_, uvn_next, uvn_next_ffn_, uvn_sfn_);
01520
01521 int connect2sfn = -1;
01522 if (ffn_next_sfn && sfn_next_sfn)
01523 {
01524 double fn2s = (coords_[sfn_[current_index_]] - coords_[ffn_[next_index]]).squaredNorm ();
01525 double sn2s = (coords_[sfn_[current_index_]] - coords_[sfn_[next_index]]).squaredNorm ();
01526 if (fn2s < sn2s) connect2sfn = 0;
01527 else connect2sfn = 1;
01528 }
01529 else if (ffn_next_sfn) connect2sfn = 0;
01530 else if (sfn_next_sfn) connect2sfn = 1;
01531
01532 switch (connect2sfn)
01533 {
01534 case 0:
01535 {
01536 addTriangle (next_index, sfn_[current_index_], ffn_[next_index], output);
01537 neighbor_update = ffn_[next_index];
01538
01540 if ((ffn_[ffn_[next_index]] == sfn_[current_index_]) || (sfn_[ffn_[next_index]] == sfn_[current_index_]))
01541 {
01542 state_[ffn_[next_index]] = COMPLETED;
01543 }
01544 else if (ffn_[ffn_[next_index]] == next_index)
01545 {
01546 ffn_[ffn_[next_index]] = sfn_[current_index_];
01547 }
01548 else if (sfn_[ffn_[next_index]] == next_index)
01549 {
01550 sfn_[ffn_[next_index]] = sfn_[current_index_];
01551 }
01552
01553 ffn_[next_index] = current_index_;
01554
01555 break;
01556 }
01557 case 1:
01558 {
01559 addTriangle (next_index, sfn_[current_index_], sfn_[next_index], output);
01560 neighbor_update = sfn_[next_index];
01561
01563 if ((ffn_[sfn_[next_index]] == sfn_[current_index_]) || (sfn_[sfn_[next_index]] == sfn_[current_index_]))
01564 {
01565 state_[sfn_[next_index]] = COMPLETED;
01566 }
01567 else if (ffn_[sfn_[next_index]] == next_index)
01568 {
01569 ffn_[sfn_[next_index]] = sfn_[current_index_];
01570 }
01571 else if (sfn_[sfn_[next_index]] == next_index)
01572 {
01573 sfn_[sfn_[next_index]] = sfn_[current_index_];
01574 }
01575
01576 sfn_[next_index] = current_index_;
01577
01578 break;
01579 }
01580 default:;
01581 }
01582 }
01583 }
01584
01586 if ((ffn_[sfn_[current_index_]] == neighbor_update) || (sfn_[sfn_[current_index_]] == neighbor_update))
01587 {
01588 state_[sfn_[current_index_]] = COMPLETED;
01589 }
01590 else if (ffn_[sfn_[current_index_]] == current_index_)
01591 {
01592 ffn_[sfn_[current_index_]] = neighbor_update;
01593 }
01594 else if (sfn_[sfn_[current_index_]] == current_index_)
01595 {
01596 sfn_[sfn_[current_index_]] = neighbor_update;
01597 }
01598
01599 sfn_[current_index_] = prev_index;
01600
01601 break;
01602 }
01603 default:;
01604 }
01605 }
01606 }
01607 }
01608 }
01609
01610 #define PCL_INSTANTIATE_GreedyProjectionTriangulation(T) \
01611 template class pcl::GreedyProjectionTriangulation<T>;
01612
01613 #endif // PCL_SURFACE_IMPL_GP3_H_
01614
01615