sparsetv.h
Go to the documentation of this file.
1 // kate: replace-tabs off; indent-width 4; indent-mode normal
2 // vim: ts=4:sw=4:noexpandtab
3 /*
4 
5 Copyright (c) 2010--2018
6 
7 All rights reserved.
8 
9 Redistribution and use in source and binary forms, with or without
10 modification, are permitted provided that the following conditions are met:
11  * Redistributions of source code must retain the above copyright
12  notice, this list of conditions and the following disclaimer.
13  * Redistributions in binary form must reproduce the above copyright
14  notice, this list of conditions and the following disclaimer in the
15  documentation and/or other materials provided with the distribution.
16  * Neither the name of the <organization> nor the
17  names of its contributors may be used to endorse or promote products
18  derived from this software without specific prior written permission.
19 
20 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
21 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
22 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
24 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
25 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
27 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
28 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
29 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30 
31 */
32 #pragma once
33 
35 
36 #include <Eigen/Core>
37 #include <Eigen/Eigenvalues>
38 
39 #include <nabo/nabo.h>
40 
50 //Sparse Tensor Voting
51 template <typename T>
52 struct TensorVoting
53 {
54 //--types
56  using DP = typename PM::DataPoints;
57 
58  using InvalidField = typename DP::InvalidField;
59 
60  using SparseTensor = Eigen::Matrix<T, 4, 1>; // (saliency, ex,ey,ez)
61  using Tensor = Eigen::Matrix<T, 3, 3>;
62 
63  using Field = Eigen::Matrix< Tensor, Eigen::Dynamic, 1>;
64  using Tensors = Eigen::Matrix< Tensor, Eigen::Dynamic, 1>;
65  using SparseTensors = Eigen::Matrix< SparseTensor, Eigen::Dynamic, 1>;
66 
67  using Vector3 = Eigen::Matrix<T, 3, 1>;
68  using Matrix33 = Eigen::Matrix<T, 3, 3>;
69 
70  using Matrix = typename PM::Matrix;
71  using Vector = typename PM::Vector;
72 
74  using Index = typename NNS::Index;
75  using IndexMatrix = typename NNS::IndexMatrix;
76 
78 
79 public:
80 //--attributes
81  const T sigma; //control the scale of the voting field
82  std::size_t k; //number of neighbors
83 
85 
89 
90 public:
91 //--resulting descriptors
92  Matrix surfaceness; //surface saliency map (stick)
93  Matrix curveness; //curve saliency map (plate)
94  Matrix pointness; //junction saliency map (ball)
95 
96  Matrix normals; //normals (stick orientation)
97  Matrix tangents; //tangents (plate orientation)
98 
99  Matrix sticks; //(s,n)
100  Matrix plates; //(s,n1,n2)
101  Matrix balls; // (s)
102 private:
103 //knn
106 
107 public:
108 //--ctor
109  TensorVoting(T sigma_ = T(0.2), std::size_t k_ = 50);
110 //--dtor
111  ~TensorVoting();
112 
113 //--methods
114 
116  void vote(const DP& pts);
117  void refine(const DP& pts);
118 
119  void encode(const DP& pts, Encoding encoding = Encoding::UBALL);
120 
121  void disableBallComponent();
122 
123  void ballVote(const DP& pts, bool doKnn = true);
124  void stickVote(const DP& pts, bool doKnn = true);
125  void plateVote(const DP& pts, bool doKnn = true);
126 
127  void cfvote(const DP& pts, bool doKnn = true);
128 
129  void decompose();
130 
131  void toDescriptors();
132 
135  {
136  static inline T sradial(const T z)
137  {
138  if(z < 3.)
139  return std::pow(z, 2) * std::pow(z - 3, 4) / 16.;
140  else
141  return 0.;
142  }
143 
144  static inline T radial(const T z)
145  {
146  return std::exp(-std::pow(z, 2));
147  }
148 
149  static inline T angular(const T theta)
150  {
151  return std::pow(std::cos(theta), 8);
152  }
153 
154  /***************************************************************************
155  * See Eq (1) in :
156  * G. Guy and G. Medioni, “Inference of surfaces, 3D curves, and junctions
157  * from sparse, noisy, 3D Data,” 1997.
158  **************************************************************************/
159  static inline T diabolo(const T s, const T c, const T k, const T sigma)
160  {
161  return std::exp(-1. * std::pow(s, 2) / std::pow(sigma, 2) - c * std::pow(k, 2) );
162  }
163 
164  /***************************************************************************
165  * See Eq (1) and Eq (2) in :
166  * T.-P. Wu, S.-K. Yeung, J. Jia, C.-K. Tang, and G. Medioni,
167  * “A Closed-Form Solution to Tensor Voting: Theory and Applications,” 2016.
168  ***************************************************************************/
169  static inline T eta(const T vv, const T sigma, const T vvn)
170  {
171  return cij(vv, sigma) * (1. - vvn * vvn);
172  }
173 
174  static inline T cij(const T vv, const T sigma)
175  {
176  return std::exp(- std::pow(vv, 2) / sigma);
177  }
178  };
179 private:
180  void computeKnn(const DP& pts);
181 };
182 
183 #include "sparsetv.hpp"
sparsetv.hpp
TensorVoting::PLATE
@ PLATE
Definition: sparsetv.h:77
TensorVoting::DP
typename PM::DataPoints DP
Definition: sparsetv.h:56
TensorVoting::decompose
void decompose()
Definition: sparsetv.hpp:427
setup.encoding
encoding
Definition: setup.py:22
TensorVoting::DecayFunction::angular
static T angular(const T theta)
Definition: sparsetv.h:149
TensorVoting::vote
void vote(const DP &pts)
Voting methods.
Definition: sparsetv.hpp:49
TensorVoting::Vector3
Eigen::Matrix< T, 3, 1 > Vector3
Definition: sparsetv.h:67
TensorVoting::BALL
@ BALL
Definition: sparsetv.h:77
TensorVoting::DecayFunction::sradial
static T sradial(const T z)
Definition: sparsetv.h:136
TensorVoting::normals
Matrix normals
Definition: sparsetv.h:96
TensorVoting::ZERO
@ ZERO
Definition: sparsetv.h:77
build_map.T
T
Definition: build_map.py:34
DataPoints
PM::DataPoints DataPoints
Definition: pypoint_matcher_helper.h:16
TensorVoting::Tensor
Eigen::Matrix< T, 3, 3 > Tensor
Definition: sparsetv.h:61
TensorVoting::plateVote
void plateVote(const DP &pts, bool doKnn=true)
Definition: sparsetv.hpp:312
TensorVoting::k
std::size_t k
Definition: sparsetv.h:82
TensorVoting::cfvote
void cfvote(const DP &pts, bool doKnn=true)
Definition: sparsetv.hpp:381
PointMatcher
Functions and classes that are dependant on scalar type are defined in this templatized class.
Definition: PointMatcher.h:130
TensorVoting::sigma
const T sigma
Definition: sparsetv.h:81
TensorVoting::IndexMatrix
typename NNS::IndexMatrix IndexMatrix
Definition: sparsetv.h:75
Nabo::NearestNeighbourSearch::IndexMatrix
Eigen::Matrix< Index, Eigen::Dynamic, Eigen::Dynamic > IndexMatrix
PointMatcher::DataPoints
A point cloud.
Definition: PointMatcher.h:207
TensorVoting::curveness
Matrix curveness
Definition: sparsetv.h:93
TensorVoting::Matrix33
Eigen::Matrix< T, 3, 3 > Matrix33
Definition: sparsetv.h:68
TensorVoting
Definition: sparsetv.h:52
TensorVoting::sparseStick
SparseTensors sparseStick
Definition: sparsetv.h:86
TensorVoting::USTICK
@ USTICK
Definition: sparsetv.h:77
TensorVoting::Field
Eigen::Matrix< Tensor, Eigen::Dynamic, 1 > Field
Definition: sparsetv.h:63
TensorVoting::sparsePlate
SparseTensors sparsePlate
Definition: sparsetv.h:87
TensorVoting::Tensors
Eigen::Matrix< Tensor, Eigen::Dynamic, 1 > Tensors
Definition: sparsetv.h:64
TensorVoting::DecayFunction::cij
static T cij(const T vv, const T sigma)
Definition: sparsetv.h:174
TensorVoting::DecayFunction::eta
static T eta(const T vv, const T sigma, const T vvn)
Definition: sparsetv.h:169
TensorVoting::UPLATE
@ UPLATE
Definition: sparsetv.h:77
TensorVoting::DecayFunction
Kernel methods.
Definition: sparsetv.h:134
TensorVoting::UBALL
@ UBALL
Definition: sparsetv.h:77
nabo.h
TensorVoting::SSTICK
@ SSTICK
Definition: sparsetv.h:77
PointMatcher::DataPoints::InvalidField
An exception thrown when one tries to access features or descriptors unexisting or of wrong dimension...
Definition: PointMatcher.h:250
Nabo::NearestNeighbourSearch
TensorVoting::STICK
@ STICK
Definition: sparsetv.h:77
TensorVoting::surfaceness
Matrix surfaceness
Definition: sparsetv.h:92
TensorVoting::SparseTensors
Eigen::Matrix< SparseTensor, Eigen::Dynamic, 1 > SparseTensors
Definition: sparsetv.h:65
TensorVoting::sparseBall
SparseTensors sparseBall
Definition: sparsetv.h:88
TensorVoting::balls
Matrix balls
Definition: sparsetv.h:101
TensorVoting::SparseTensor
Eigen::Matrix< T, 4, 1 > SparseTensor
Definition: sparsetv.h:60
PointMatcher::Matrix
Eigen::Matrix< T, Eigen::Dynamic, Eigen::Dynamic > Matrix
A dense matrix over ScalarType.
Definition: PointMatcher.h:169
TensorVoting::refine
void refine(const DP &pts)
Definition: sparsetv.hpp:187
TensorVoting::DecayFunction::diabolo
static T diabolo(const T s, const T c, const T k, const T sigma)
Definition: sparsetv.h:159
TensorVoting::ballVote
void ballVote(const DP &pts, bool doKnn=true)
Definition: sparsetv.hpp:215
TensorVoting::tensors
Tensors tensors
Definition: sparsetv.h:84
TensorVoting::SPLATE
@ SPLATE
Definition: sparsetv.h:77
TensorVoting::disableBallComponent
void disableBallComponent()
Definition: sparsetv.hpp:173
PointMatcher::Vector
Eigen::Matrix< T, Eigen::Dynamic, 1 > Vector
A vector over ScalarType.
Definition: PointMatcher.h:161
TensorVoting::encode
void encode(const DP &pts, Encoding encoding=Encoding::UBALL)
Definition: sparsetv.hpp:55
TensorVoting::toDescriptors
void toDescriptors()
Definition: sparsetv.hpp:474
TensorVoting::SBALL
@ SBALL
Definition: sparsetv.h:77
TensorVoting::TensorVoting
TensorVoting(T sigma_=T(0.2), std::size_t k_=50)
Definition: sparsetv.hpp:38
TensorVoting::InvalidField
typename DP::InvalidField InvalidField
Definition: sparsetv.h:58
TensorVoting::DecayFunction::radial
static T radial(const T z)
Definition: sparsetv.h:144
TensorVoting::AWARE_TENSOR
@ AWARE_TENSOR
Definition: sparsetv.h:77
TensorVoting::plates
Matrix plates
Definition: sparsetv.h:100
Nabo::NearestNeighbourSearch::Index
int Index
TensorVoting::stickVote
void stickVote(const DP &pts, bool doKnn=true)
Definition: sparsetv.hpp:252
TensorVoting::Encoding
Encoding
Definition: sparsetv.h:77
TensorVoting::sticks
Matrix sticks
Definition: sparsetv.h:99
TensorVoting::pointness
Matrix pointness
Definition: sparsetv.h:94
TensorVoting::Vector
typename PM::Vector Vector
Definition: sparsetv.h:71
TensorVoting::tangents
Matrix tangents
Definition: sparsetv.h:97
PointMatcher.h
public interface
TensorVoting::~TensorVoting
~TensorVoting()
Definition: sparsetv.hpp:43
PointMatcherSupport::pow
constexpr T pow(const T base, const std::size_t exponent)
Definition: utils.h:47
TensorVoting::indices
IndexMatrix indices
Definition: sparsetv.h:104
TensorVoting::Matrix
typename PM::Matrix Matrix
Definition: sparsetv.h:70
TensorVoting::dist
Matrix dist
Definition: sparsetv.h:105
TensorVoting::computeKnn
void computeKnn(const DP &pts)
Definition: sparsetv.hpp:510
TensorVoting::Index
typename NNS::Index Index
Definition: sparsetv.h:74


libpointmatcher
Author(s):
autogenerated on Mon Jan 1 2024 03:24:43