57         const std::size_t nbPts = pts.getNbPoints();
 
   58         tensors.resize(nbPts, 1);
 
   64 #pragma omp parallel for 
   65                         for(std::size_t i = 0; i < nbPts; ++i) 
 
   66                                 tensors(i) = Tensor::Zero();
 
   73 #pragma omp parallel for 
   74                         for(std::size_t i = 0; i < nbPts; ++i)
 
   75                                 tensors(i) = Tensor::Identity();
 
   81                         if (not pts.descriptorExists(
"balls"))
 
   82                                 throw InvalidField(
"TensorVoting<T>::encode: Error, cannot find balls in descriptors.");
 
   84                         const auto& balls_ = pts.getDescriptorViewByName(
"balls");
 
   85 #pragma omp parallel for                                                 
   86                         for(std::size_t i = 0; i < nbPts; ++i)
 
   87                                 tensors(i) = Tensor::Identity() * balls_(0,i);
 
   92                 case Encoding::UPLATE:
 
   94 #pragma omp parallel for 
   95                         for(std::size_t i = 0; i < nbPts; ++i)
 
  102                 case Encoding::PLATE:
 
  103                 case Encoding::SPLATE:
 
  106                         if (not pts.descriptorExists(
"plates"))
 
  107                                 throw InvalidField(
"TensorVoting<T>::encode: Error, cannot find plates in descriptors.");
 
  109                         const auto& plates_ = pts.getDescriptorViewByName(
"plates");
 
  110 #pragma omp parallel for 
  111                         for(std::size_t i = 0; i < nbPts; ++i)
 
  113                                 const Vector3 n1 = plates_.col(i).segment(1,3);
 
  114                                 const Vector3 n2 = plates_.col(i).tail(3);
 
  116                                 tensors(i) = (
encoding == Encoding::SPLATE ? plates_(0,i) : 1.) * (n1 * n1.transpose() + n2 * n2.transpose());
 
  121                 case Encoding::USTICK:
 
  123 #pragma omp parallel for 
  124                         for(std::size_t i = 0; i < nbPts; ++i)
 
  131                 case Encoding::STICK:
 
  132                 case Encoding::SSTICK:
 
  135                         if (not pts.descriptorExists(
"sticks"))
 
  136                                 throw InvalidField(
"TensorVoting<T>::encode: Error, cannot find sticks in descriptors.");
 
  138                         const auto& sticks_ = pts.getDescriptorViewByName(
"sticks");
 
  139 #pragma omp parallel for 
  140                         for(std::size_t i = 0; i < nbPts; ++i)
 
  142                                 const Vector3 n = sticks_.col(i).tail(3);               
 
  143                                 tensors(i) = (
encoding == Encoding::SSTICK ? sticks_(0,i) : 1.) * (n * n.transpose());
 
  148                 case Encoding::AWARE_TENSOR:
 
  151                         if (not pts.descriptorExists(
"sticks"))
 
  152                                 throw InvalidField(
"TensorVoting<T>::encode: Error, cannot find sticks in descriptors.");
 
  154                         if (not pts.descriptorExists(
"plates"))
 
  155                                 throw InvalidField(
"TensorVoting<T>::encode: Error, cannot find plates in descriptors.");
 
  157                         const auto& sticks_ = pts.getDescriptorViewByName(
"sticks");
 
  158                         const auto& plates_ = pts.getDescriptorViewByName(
"plates");
 
  159 #pragma omp parallel for 
  160                         for(std::size_t i = 0; i < nbPts; ++i)
 
  162                                 const Tensor S = sticks_.col(i).tail(3) * sticks_.col(i).tail(3).transpose();
 
  163                                 const Tensor P = plates_.col(i).segment(1,3) * plates_.col(i).segment(1,3).transpose() + plates_.col(i).tail(3) * plates_.col(i).tail(3).transpose();
 
  165                                 tensors(i) = (sticks_(0,i) / k) * S + (plates_(0,i) / k) * 
P;
 
  172 template <
typename T>
 
  175         const std::size_t nbPts = tensors.rows();
 
  176 #pragma omp parallel for 
  177         for(std::size_t i = 0; i < nbPts; ++i)
 
  179                 const Tensor S = sticks.col(i).tail(3) * sticks.col(i).tail(3).transpose();
 
  180                 const Tensor P = plates.col(i).segment(1,3) * plates.col(i).segment(1,3).transpose() + plates.col(i).tail(3) * plates.col(i).tail(3).transpose();
 
  182                 tensors(i) = (sticks(0,i) / k) * S + (plates(0,i) / k) * 
P;
 
  186 template <
typename T>
 
  214 template <
typename T>
 
  217         const std::size_t nbPts = pts.getNbPoints();
 
  219         const Tensor I = Tensor::Identity();
 
  221         if(doKnn) computeKnn(pts);
 
  223         for(std::size_t voter = 0; voter < nbPts; ++voter)
 
  225                 for(std::size_t j = 0; j < k ; j++)
 
  227                         Index votee = indices(j,voter);
 
  229                         if(votee == NNS::InvalidIndex) 
break;
 
  230                         if(votee == 
Index(voter)) 
continue;
 
  232                         const Vector3 v = pts.features.col(votee).head(3) - pts.features.col(voter).head(3);
 
  233                         const T normDist = v.norm()/sigma;
 
  235                         if(normDist > 0. and normDist < 3.) 
 
  237                                         const Tensor vv = v * v.transpose(); 
 
  238                                         const T normVv = vv.norm(); 
 
  242                                                 const Tensor acc = tensors(votee) + DecayFunction::sradial(normDist) * (I - vv / normVv);
 
  243                                                 tensors(votee) = acc;
 
  251 template <
typename T>
 
  255         if (not pts.descriptorExists(
"sticks"))
 
  256                 throw InvalidField(
"TensorVoting<T>::stickVote: Error, cannot find sticks in descriptors.");
 
  258         const auto& sticks_ = pts.getDescriptorViewByName(
"sticks");
 
  260         const std::size_t nbPts = pts.getNbPoints();
 
  262         if(doKnn) computeKnn(pts);
 
  264         for(std::size_t voter = 0; voter < nbPts; ++voter)
 
  266                 Vector3 vn = sticks_.col(voter).tail(3).normalized(); 
 
  267                 const Vector3 O  = pts.features.col(voter).head(3); 
 
  269                 for(std::size_t j = 0; j < k ; j++)
 
  271                         Index votee = indices(j,voter);
 
  273                         if(votee == NNS::InvalidIndex) 
break;
 
  274                         if(votee == 
Index(voter)) 
continue;
 
  276                         Vector3 v = pts.features.col(votee).head(3) - O; 
 
  278                         const T normDist = v.norm()/sigma;
 
  280                         if(normDist > 0. and normDist < 3.) 
 
  284                                 const T vvn = v.dot(vn); 
 
  285                                 if(vvn < 0.) vn *= -1.; 
 
  287                                 const T theta = std::asin(vvn); 
 
  290                                 if (std::fabs(theta) <= M_PI / 4. or std::fabs(theta) >= 3. * M_PI / 4.)
 
  293                                         Vector3 vt = vn.cross(v.cross(vn)).normalized();
 
  295                                         const T vvt = v.dot(vt); 
 
  296                                         if(vvt < 0.) vt *= -1.; 
 
  299                                         const Vector3 vc = vn * std::cos(2. * theta) - vt * std::sin(2. * theta); 
 
  302                                         const Tensor acc = tensors(votee) + sticks_(0, voter) * DecayFunction::eta(normDist * sigma, sigma, vvn) * (vc * vc.transpose());                                       
 
  303                                         tensors(votee) = acc;
 
  311 template <
typename T>
 
  315         if (not pts.descriptorExists(
"plates"))
 
  316                 throw InvalidField(
"TensorVoting<T>::stickVote: Error, cannot find plates in descriptors.");
 
  318         const auto& plates_ = pts.getDescriptorViewByName(
"plates");
 
  320         const std::size_t nbPts = pts.getNbPoints();
 
  322         if(doKnn) computeKnn(pts);
 
  324         for(std::size_t voter = 0; voter < nbPts; ++voter)
 
  326                 Matrix U(3,2); U << plates_.col(voter).segment(1,3), plates_.col(voter).tail(3);
 
  327                 const Matrix Ns = U*U.transpose(); 
 
  329                 for(std::size_t d = 0; d <= 1 ; ++d)
 
  331                         Vector3 vn = Ns.col(d).normalized(); 
 
  332                         const Vector3 O  = pts.features.col(voter).head(3); 
 
  334                         for(std::size_t j = 0; j < k ; j++)
 
  336                                 Index votee = indices(j,voter);
 
  338                                 if(votee == NNS::InvalidIndex) 
break;
 
  339                                 if(votee == 
Index(voter)) 
continue;
 
  341                                 Vector3 v = pts.features.col(votee).head(3) - O; 
 
  343                                 const T normDist = v.norm()/sigma;
 
  345                                 if(normDist > 0. and normDist < 3.) 
 
  349                                         const T vvn = v.dot(vn); 
 
  350                                         if(vvn < 0.) vn *= -1.; 
 
  352                                         const T theta = std::asin(vvn); 
 
  355                                         if (std::fabs(theta) <= M_PI / 4. or std::fabs(theta) >= 3. * M_PI / 4.)
 
  358                                                 Vector3 vt = vn.cross(v.cross(vn)).normalized();
 
  360                                                 const T vvt = v.dot(vt); 
 
  361                                                 if(vvt < 0.) vt *= -1.; 
 
  363                                                 const Vector3 vc = vn * std::cos(2. * theta) - vt * std::sin(2. * theta); 
 
  366                                                 const Tensor acc = tensors(votee) + plates_(0, voter) * DecayFunction::eta(normDist*sigma, sigma, vvn) * (vc * vc.transpose());                         
 
  367                                                 tensors(votee) = acc;
 
  380 template <
typename T>
 
  383         const std::size_t nbPts = pts.getNbPoints();
 
  385         if(doKnn) computeKnn(pts);
 
  388         encode(pts, Encoding::ZERO); 
 
  390 #pragma omp parallel for 
  391         for(std::size_t votee = 0; votee < nbPts; ++votee) 
 
  393                 const Vector3 x_i  = pts.features.col(votee).head(3);
 
  395                 for(std::size_t j = 0; j < k ; j++) 
 
  397                         const Index voter = indices(j,votee); 
 
  399                         if(voter == NNS::InvalidIndex) 
continue;                
 
  400                         if(voter == 
Index(votee)) 
continue;
 
  402                         const Vector3 x_j = pts.features.col(voter).head(3); 
 
  405                         const T normDist = r_ij.norm() / sigma;
 
  407                         if(normDist > 0. and normDist < 3.) 
 
  411                                 const Tensor rrt = r_ij * r_ij.transpose();
 
  412                                 const Tensor R_ij = (Tensor::Identity() - 2. * rrt);
 
  413                                 const Tensor Rp_ij  = (Tensor::Identity() - .5 * rrt) * R_ij;
 
  414                                 const T c_ij = DecayFunction::cij((x_i - x_j).norm(), sigma);
 
  417                                 const Tensor S_ij = c_ij * R_ij * K(voter) * Rp_ij;
 
  419                                 const Tensor acc = tensors(votee) + S_ij;
 
  420                                 tensors(votee) = acc;
 
  426 template <
typename T>
 
  429         const std::size_t nbPts = tensors.rows();
 
  431         sparseStick.resize(nbPts);
 
  432         sparsePlate.resize(nbPts);
 
  433         sparseBall.resize(nbPts);
 
  435 #pragma omp parallel for         
  436         for(std::size_t i = 0; i < nbPts; ++i)
 
  438                 Eigen::SelfAdjointEigenSolver<Tensor> solver(tensors(i));
 
  440                 const Matrix33 eigenVe = solver.eigenvectors();
 
  441                 const Vector3 eigenVa = solver.eigenvalues().array().abs();
 
  444                 int lambda1_idx; 
const T lambda1 = eigenVa.maxCoeff(&lambda1_idx);
 
  445                 int lambda3_idx; 
const T lambda3 = eigenVa.minCoeff(&lambda3_idx);
 
  446                 const int lambda2_idx = (0+1+2) - (lambda1_idx + lambda3_idx);
 
  447                 const T lambda2 = eigenVa(lambda2_idx);
 
  451                 if(not (lambda1 >= lambda2 and lambda2 >= lambda3) or lambda2_idx > 2. or lambda2_idx < 0.)
 
  453                         sparseStick(i)  << 0.0001,0.,0.,0.;
 
  454                         sparsePlate(i)  << 0.0001,0.,0.,0.;
 
  455                         sparseBall(i)   << 0.0001,0.,0.,0.;
 
  462                 sparseStick(i)(0) = (lambda1 - lambda2) / norm; 
 
  463                 sparseStick(i).tail(3) = eigenVe.col(lambda1_idx); 
 
  465                 sparsePlate(i)(0) = (lambda2 - lambda3) / norm; 
 
  466                 sparsePlate(i).tail(3) = eigenVe.col(lambda3_idx); 
 
  468                 sparseBall(i)(0) = lambda3 / norm; 
 
  469                 sparseBall(i).tail(3) = eigenVe.col(lambda2_idx); 
 
  473 template <
typename T>
 
  476         const std::size_t nbPts = tensors.rows();
 
  478         pointness = PM::Matrix::Zero(1, nbPts);
 
  479         curveness = PM::Matrix::Zero(1, nbPts);
 
  480         surfaceness = PM::Matrix::Zero(1, nbPts);
 
  482         normals         = PM::Matrix::Zero(3, nbPts);
 
  483         tangents        = PM::Matrix::Zero(3, nbPts);
 
  485         sticks = PM::Matrix::Zero(4, nbPts);
 
  486         plates = PM::Matrix::Zero(7, nbPts);
 
  487         balls  = PM::Matrix::Zero(1, nbPts);
 
  489 #pragma omp parallel for   
  490         for(std::size_t i = 0; i < nbPts; i++)
 
  492                 surfaceness(i) = sparseStick(i)(0) / k;
 
  493                 curveness(i) = sparsePlate(i)(0) / k;
 
  494                 pointness(i) = sparseBall(i)(0) / k;
 
  496                 normals.col(i) = sparseStick(i).tail(3);
 
  497                 tangents.col(i) = sparsePlate(i).tail(3);
 
  499                 sticks.col(i) = sparseStick(i); 
 
  501                 plates(0,i) = sparsePlate(i)(0); 
 
  502                 plates.col(i).segment(1,3) = sparseStick(i).tail(3); 
 
  503                 plates.col(i).tail(3) = sparseBall(i).tail(3); 
 
  505                 balls(i) = sparseBall(i)(0); 
 
  509 template <
typename T>
 
  512         const std::size_t nbPts = pts.getNbPoints();
 
  514         if(k >= nbPts) k = nbPts - 1;
 
  516         std::shared_ptr<NNS> 
knn(
 
  517                 NNS::create(pts.features, pts.features.rows() - 1, 
 
  518                         (k<30? NNS::SearchType::KDTREE_LINEAR_HEAP : NNS::SearchType::KDTREE_TREE_HEAP) 
 
  522         indices = IndexMatrix::Zero(k, nbPts);
 
  523         dist = Matrix::Zero(k, nbPts);