math/lanczos-decomposition.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2024 INRIA
3 //
4 
5 #ifndef __pinocchio_math_lanczos_decomposition_hpp__
6 #define __pinocchio_math_lanczos_decomposition_hpp__
7 
8 #include "pinocchio/math/fwd.hpp"
11 
12 namespace pinocchio
13 {
14 
17  template<typename _Matrix>
19  {
20  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
21 
22  typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(_Matrix) PlainMatrix;
23  typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(typename PlainMatrix::ColXpr) Vector;
24  typedef typename _Matrix::Scalar Scalar;
25  enum
26  {
28  };
30 
32  template<typename MatrixLikeType>
33  LanczosDecompositionTpl(const MatrixLikeType & mat, const Eigen::DenseIndex decomposition_size)
34  : m_Qs(mat.rows(), decomposition_size)
35  , m_Ts(decomposition_size)
36  , m_A_times_q(mat.rows())
37  , m_rank(-1)
38  {
39  PINOCCHIO_CHECK_INPUT_ARGUMENT(mat.rows() == mat.cols(), "The input matrix is not square.");
41  decomposition_size >= 1, "The size of the decomposition should be greater than one.");
43  decomposition_size <= mat.rows(),
44  "The size of the decomposition should not be larger than the number of rows.");
45 
46  compute(mat);
47  }
48 
49  bool operator==(const LanczosDecompositionTpl & other) const
50  {
51  if (this == &other)
52  return true;
53  return m_Qs == other.m_Qs && m_Ts == other.m_Ts && m_rank == other.m_rank;
54  }
55 
56  bool operator!=(const LanczosDecompositionTpl & other) const
57  {
58  return !(*this == other);
59  }
60 
66  template<typename MatrixLikeType>
67  void compute(const MatrixLikeType & A)
68  {
69  PINOCCHIO_CHECK_INPUT_ARGUMENT(A.rows() == A.cols(), "The input matrix is not square.");
71  A.rows() == m_Qs.rows(), "The input matrix is of correct size.");
72 
73  const Eigen::DenseIndex decomposition_size = m_Ts.cols();
74  auto & alphas = m_Ts.diagonal();
75  auto & betas = m_Ts.subDiagonal();
76 
77  m_Qs.col(0).fill(Scalar(1) / math::sqrt(Scalar(m_Qs.rows())));
78  m_Ts.setZero();
79  Eigen::DenseIndex k;
80  for (k = 0; k < decomposition_size; ++k)
81  {
82  const auto q = m_Qs.col(k);
83  m_A_times_q.noalias() = A * q;
84  alphas[k] = q.dot(m_A_times_q);
85 
86  if (k < decomposition_size - 1)
87  {
88  auto q_next = m_Qs.col(k + 1);
89  m_A_times_q -= alphas[k] * q;
90  if (k > 0)
91  {
92  m_A_times_q -= betas[k - 1] * m_Qs.col(k - 1);
93  }
94 
95  // Perform Gram-Schmidt orthogonalization procedure.
96  if (k > 0)
97  orthonormalisation(m_Qs.leftCols(k), m_A_times_q);
98 
99  // Compute beta
100  betas[k] = m_A_times_q.norm();
101  if (betas[k] <= 1e2 * Eigen::NumTraits<Scalar>::epsilon())
102  {
103  break;
104  }
105  else
106  {
107  q_next.noalias() = m_A_times_q / betas[k];
108  }
109  }
110  }
111  m_rank = math::max(Eigen::DenseIndex(1), k);
112  }
113 
122  template<typename MatrixLikeType>
123  PlainMatrix computeDecompositionResidual(const MatrixLikeType & A) const
124  {
125  const Eigen::DenseIndex last_col_id = m_Ts.cols() - 1;
126  const auto & alphas = m_Ts.diagonal();
127  const auto & betas = m_Ts.subDiagonal();
128 
129  PlainMatrix residual = A * m_Qs;
130  residual -= (m_Qs * m_Ts).eval();
131 
132  const auto & q = m_Qs.col(last_col_id);
133 
134  auto & tmp_vec = m_A_times_q; // use m_A_times_q as a temporary vector
135  tmp_vec.noalias() = A * q;
136  tmp_vec -= alphas[last_col_id] * q;
137  if (last_col_id > 0)
138  tmp_vec -= betas[last_col_id - 1] * m_Qs.col(last_col_id - 1);
139 
140  residual.col(last_col_id) -= tmp_vec;
141 
142  return residual;
143  }
144 
146  const TridiagonalMatrix & Ts() const
147  {
148  return m_Ts;
149  }
152  {
153  return m_Ts;
154  }
155 
157  const PlainMatrix & Qs() const
158  {
159  return m_Qs;
160  }
162  PlainMatrix & Qs()
163  {
164  return m_Qs;
165  }
166 
168  Eigen::DenseIndex rank() const
169  {
170  return m_rank;
171  }
172 
173  protected:
174  PlainMatrix m_Qs;
176  mutable Vector m_A_times_q;
177  Eigen::DenseIndex m_rank;
178  };
179 } // namespace pinocchio
180 
181 #endif // ifndef __pinocchio_math_lanczos_decomposition_hpp__
pinocchio::TridiagonalSymmetricMatrixTpl::subDiagonal
CoeffVectorType & subDiagonal()
Definition: math/tridiagonal-matrix.hpp:209
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
Macro to check an assert-like condition and throw a std::invalid_argument exception (with a message) ...
Definition: include/pinocchio/macros.hpp:193
pinocchio::LanczosDecompositionTpl::Ts
TridiagonalMatrix & Ts()
Returns the tridiagonal matrix associated with the Lanczos decomposition.
Definition: math/lanczos-decomposition.hpp:151
pinocchio::LanczosDecompositionTpl::m_A_times_q
Vector m_A_times_q
Definition: math/lanczos-decomposition.hpp:176
pinocchio::LanczosDecompositionTpl::rank
Eigen::DenseIndex rank() const
Returns the rank of the decomposition.
Definition: math/lanczos-decomposition.hpp:168
floating-base-velocity-viewer.q_next
def q_next
Definition: floating-base-velocity-viewer.py:82
pinocchio::LanczosDecompositionTpl::TridiagonalMatrix
TridiagonalSymmetricMatrixTpl< Scalar, Options > TridiagonalMatrix
Definition: math/lanczos-decomposition.hpp:29
rows
int rows
pinocchio::LanczosDecompositionTpl::operator==
bool operator==(const LanczosDecompositionTpl &other) const
Definition: math/lanczos-decomposition.hpp:49
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::LanczosDecompositionTpl
Compute the largest eigenvalues and the associated principle eigenvector via power iteration.
Definition: math/lanczos-decomposition.hpp:18
pinocchio::LanczosDecompositionTpl::m_Ts
TridiagonalMatrix m_Ts
Definition: math/lanczos-decomposition.hpp:175
pinocchio::LanczosDecompositionTpl::operator!=
bool operator!=(const LanczosDecompositionTpl &other) const
Definition: math/lanczos-decomposition.hpp:56
pinocchio::LanczosDecompositionTpl::m_Qs
PlainMatrix m_Qs
Definition: math/lanczos-decomposition.hpp:174
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
pinocchio::LanczosDecompositionTpl::Options
@ Options
Definition: math/lanczos-decomposition.hpp:27
pinocchio::TridiagonalSymmetricMatrixTpl< Scalar, Options >
pinocchio::LanczosDecompositionTpl::m_rank
Eigen::DenseIndex m_rank
Definition: math/lanczos-decomposition.hpp:177
pinocchio::TridiagonalSymmetricMatrixTpl::setZero
void setZero()
Definition: math/tridiagonal-matrix.hpp:229
pinocchio::LanczosDecompositionTpl::Qs
const PlainMatrix & Qs() const
Returns the orthogonal basis associated with the Lanczos decomposition.
Definition: math/lanczos-decomposition.hpp:157
mat
mat
pinocchio::TridiagonalSymmetricMatrixTpl::diagonal
CoeffVectorType & diagonal()
Definition: math/tridiagonal-matrix.hpp:201
fwd.hpp
pinocchio::LanczosDecompositionTpl::PINOCCHIO_EIGEN_PLAIN_TYPE
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef PINOCCHIO_EIGEN_PLAIN_TYPE(_Matrix) PlainMatrix
pinocchio::LanczosDecompositionTpl::Scalar
_Matrix::Scalar Scalar
Definition: math/lanczos-decomposition.hpp:24
simulation-contact-dynamics.A
A
Definition: simulation-contact-dynamics.py:115
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::LanczosDecompositionTpl::computeDecompositionResidual
PlainMatrix computeDecompositionResidual(const MatrixLikeType &A) const
Computes the residual associated with the decomposition, namely, the quantity .
Definition: math/lanczos-decomposition.hpp:123
tridiagonal-matrix.hpp
pinocchio::orthonormalisation
void orthonormalisation(const Eigen::MatrixBase< MatrixType > &basis, const Eigen::MatrixBase< VectorType > &vec_)
Perform the Gram-Schmidt orthonormalisation on the input/output vector for a given input basis.
Definition: gram-schmidt-orthonormalisation.hpp:20
pinocchio::LanczosDecompositionTpl::Qs
PlainMatrix & Qs()
Returns the orthogonal basis associated with the Lanczos decomposition.
Definition: math/lanczos-decomposition.hpp:162
gram-schmidt-orthonormalisation.hpp
pinocchio::LanczosDecompositionTpl::compute
void compute(const MatrixLikeType &A)
Computes the Lanczos decomposition of the input matrix A.
Definition: math/lanczos-decomposition.hpp:67
pinocchio::LanczosDecompositionTpl::Ts
const TridiagonalMatrix & Ts() const
Returns the tridiagonal matrix associated with the Lanczos decomposition.
Definition: math/lanczos-decomposition.hpp:146
pinocchio::LanczosDecompositionTpl::LanczosDecompositionTpl
LanczosDecompositionTpl(const MatrixLikeType &mat, const Eigen::DenseIndex decomposition_size)
Default constructor for the Lanczos decomposition from an input matrix.
Definition: math/lanczos-decomposition.hpp:33
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:180
pinocchio::TridiagonalSymmetricMatrixTpl::cols
EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT
Definition: math/tridiagonal-matrix.hpp:267
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:39