TridiagEigen.h
Go to the documentation of this file.
1 // The code was adapted from Eigen/src/Eigenvaleus/SelfAdjointEigenSolver.h
2 //
3 // Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>
4 // Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>
5 // Copyright (C) 2016-2025 Yixuan Qiu <yixuan.qiu@cos.name>
6 //
7 // This Source Code Form is subject to the terms of the Mozilla
8 // Public License v. 2.0. If a copy of the MPL was not distributed
9 // with this file, You can obtain one at https://mozilla.org/MPL/2.0/.
10 
11 #ifndef SPECTRA_TRIDIAG_EIGEN_H
12 #define SPECTRA_TRIDIAG_EIGEN_H
13 
14 #include <Eigen/Core>
15 #include <Eigen/Jacobi>
16 #include <stdexcept>
17 
18 #include "../Util/TypeTraits.h"
19 
20 namespace Spectra {
21 
22 template <typename Scalar = double>
24 {
25 private:
27  // For convenience in adapting the tridiagonal_qr_step() function
28  using RealScalar = Scalar;
33 
35  Vector m_main_diag; // Main diagonal elements of the matrix
36  Vector m_sub_diag; // Sub-diagonal elements of the matrix
37  Matrix m_evecs; // To store eigenvectors
38  bool m_computed;
39 
40  // Adapted from Eigen/src/Eigenvaleus/SelfAdjointEigenSolver.h
41  // Francis implicit QR step.
43  RealScalar* subdiag, Index start,
44  Index end, Scalar* matrixQ,
45  Index n)
46  {
47  using std::abs;
48 
49  // Wilkinson Shift.
50  RealScalar td = (diag[end - 1] - diag[end]) * RealScalar(0.5);
51  RealScalar e = subdiag[end - 1];
52  // Note that thanks to scaling, e^2 or td^2 cannot overflow, however they can still
53  // underflow thus leading to inf/NaN values when using the following commented code:
54  // RealScalar e2 = numext::abs2(subdiag[end-1]);
55  // RealScalar mu = diag[end] - e2 / (td + (td>0 ? 1 : -1) * sqrt(td*td + e2));
56  // This explain the following, somewhat more complicated, version:
57  RealScalar mu = diag[end];
58  if (td == RealScalar(0))
59  mu -= abs(e);
60  else if (e != RealScalar(0))
61  {
62  const RealScalar e2 = Eigen::numext::abs2(e);
63  const RealScalar h = Eigen::numext::hypot(td, e);
64  if (e2 == RealScalar(0))
65  mu -= e / ((td + (td > RealScalar(0) ? h : -h)) / e);
66  else
67  mu -= e2 / (td + (td > RealScalar(0) ? h : -h));
68  }
69 
70  RealScalar x = diag[start] - mu;
71  RealScalar z = subdiag[start];
72  Eigen::Map<Matrix> q(matrixQ, n, n);
73  // If z ever becomes zero, the Givens rotation will be the identity and
74  // z will stay zero for all future iterations.
75  for (Index k = start; k < end && z != RealScalar(0); ++k)
76  {
78  rot.makeGivens(x, z);
79 
80  const RealScalar s = rot.s();
81  const RealScalar c = rot.c();
82 
83  // do T = G' T G
84  RealScalar sdk = s * diag[k] + c * subdiag[k];
85  RealScalar dkp1 = s * subdiag[k] + c * diag[k + 1];
86 
87  diag[k] = c * (c * diag[k] - s * subdiag[k]) - s * (c * subdiag[k] - s * diag[k + 1]);
88  diag[k + 1] = s * sdk + c * dkp1;
89  subdiag[k] = c * sdk - s * dkp1;
90 
91  if (k > start)
92  subdiag[k - 1] = c * subdiag[k - 1] - s * z;
93 
94  // "Chasing the bulge" to return to triangular form.
95  x = subdiag[k];
96  if (k < end - 1)
97  {
98  z = -s * subdiag[k + 1];
99  subdiag[k + 1] = c * subdiag[k + 1];
100  }
101 
102  // apply the givens rotation to the unit matrix Q = Q * G
103  if (matrixQ)
104  q.applyOnTheRight(k, k + 1, rot);
105  }
106  }
107 
108 public:
110  m_n(0), m_computed(false)
111  {}
112 
114  m_n(mat.rows()), m_computed(false)
115  {
116  compute(mat);
117  }
118 
120  {
121  using std::abs;
122 
123  // A very small value, but 1.0 / near_0 does not overflow
124  // ~= 1e-307 for the "double" type
125  const Scalar near_0 = TypeTraits<Scalar>::min() * Scalar(10);
126 
127  m_n = mat.rows();
128  if (m_n != mat.cols())
129  throw std::invalid_argument("TridiagEigen: matrix must be square");
130 
132  m_sub_diag.resize(m_n - 1);
133  m_evecs.resize(m_n, m_n);
134  m_evecs.setIdentity();
135 
136  // Scale matrix to improve stability
137  const Scalar scale = (std::max)(mat.diagonal().cwiseAbs().maxCoeff(),
138  mat.diagonal(-1).cwiseAbs().maxCoeff());
139  // If scale=0, mat is a zero matrix, so we can early stop
140  if (scale < near_0)
141  {
142  // m_main_diag contains eigenvalues
144  // m_evecs has been set identity
145  // m_evecs.setIdentity();
146  m_computed = true;
147  return;
148  }
149  m_main_diag.noalias() = mat.diagonal() / scale;
150  m_sub_diag.noalias() = mat.diagonal(-1) / scale;
151 
153  Scalar* subdiag = m_sub_diag.data();
154 
155  Index end = m_n - 1;
156  Index start = 0;
157  Index iter = 0; // total number of iterations
158  int info = 0; // 0 for success, 1 for failure
159 
160  const Scalar considerAsZero = TypeTraits<Scalar>::min();
161  const Scalar precision_inv = Scalar(1) / Eigen::NumTraits<Scalar>::epsilon();
162 
163  while (end > 0)
164  {
165  for (Index i = start; i < end; i++)
166  {
167  if (abs(subdiag[i]) <= considerAsZero)
168  subdiag[i] = Scalar(0);
169  else
170  {
171  // abs(subdiag[i]) <= epsilon * sqrt(abs(diag[i]) + abs(diag[i+1]))
172  // Scaled to prevent underflows.
173  const Scalar scaled_subdiag = precision_inv * subdiag[i];
174  if (scaled_subdiag * scaled_subdiag <= (abs(diag[i]) + abs(diag[i + 1])))
175  subdiag[i] = Scalar(0);
176  }
177  }
178 
179  // find the largest unreduced block at the end of the matrix.
180  while (end > 0 && subdiag[end - 1] == Scalar(0))
181  end--;
182 
183  if (end <= 0)
184  break;
185 
186  // if we spent too many iterations, we give up
187  iter++;
188  if (iter > 30 * m_n)
189  {
190  info = 1;
191  break;
192  }
193 
194  start = end - 1;
195  while (start > 0 && subdiag[start - 1] != Scalar(0))
196  start--;
197 
198  tridiagonal_qr_step(diag, subdiag, start, end, m_evecs.data(), m_n);
199  }
200 
201  if (info > 0)
202  throw std::runtime_error("TridiagEigen: eigen decomposition failed");
203 
204  // Scale eigenvalues back
205  m_main_diag *= scale;
206 
207  m_computed = true;
208  }
209 
210  const Vector& eigenvalues() const
211  {
212  if (!m_computed)
213  throw std::logic_error("TridiagEigen: need to call compute() first");
214 
215  // After calling compute(), main_diag will contain the eigenvalues.
216  return m_main_diag;
217  }
218 
219  const Matrix& eigenvectors() const
220  {
221  if (!m_computed)
222  throw std::logic_error("TridiagEigen: need to call compute() first");
223 
224  return m_evecs;
225  }
226 };
227 
228 } // namespace Spectra
229 
230 #endif // SPECTRA_TRIDIAG_EIGEN_H
Spectra::TridiagEigen::Index
Eigen::Index Index
Definition: TridiagEigen.h:26
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
mu
double mu
Definition: testBoundingConstraint.cpp:37
Spectra::TridiagEigen::compute
void compute(ConstGenericMatrix &mat)
Definition: TridiagEigen.h:119
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::diag
Matrix diag(const std::vector< Matrix > &Hs)
Definition: Matrix.cpp:196
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
Spectra::TridiagEigen::TridiagEigen
TridiagEigen()
Definition: TridiagEigen.h:109
Spectra::TridiagEigen::m_computed
bool m_computed
Definition: TridiagEigen.h:38
mat
MatrixXf mat
Definition: Tutorial_AdvancedInitialization_CommaTemporary.cpp:1
h
const double h
Definition: testSimpleHelicopter.cpp:19
Eigen::PlainObjectBase::resize
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
Definition: PlainObjectBase.h:271
Eigen::JacobiRotation
Rotation given by a cosine-sine pair.
Definition: ForwardDeclarations.h:283
Spectra::TridiagEigen::RealScalar
Scalar RealScalar
Definition: TridiagEigen.h:28
rot
int EIGEN_BLAS_FUNC() rot(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)
Definition: level1_real_impl.h:79
rows
int rows
Definition: Tutorial_commainit_02.cpp:1
Spectra::TridiagEigen::eigenvalues
const Vector & eigenvalues() const
Definition: TridiagEigen.h:210
Spectra::TridiagEigen::m_sub_diag
Vector m_sub_diag
Definition: TridiagEigen.h:36
n
int n
Definition: BiCGSTAB_simple.cpp:1
epsilon
static double epsilon
Definition: testRot3.cpp:37
scale
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics scale
Definition: gnuplot_common_settings.hh:54
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
Spectra::TridiagEigen::m_evecs
Matrix m_evecs
Definition: TridiagEigen.h:37
Spectra::TridiagEigen::m_n
Index m_n
Definition: TridiagEigen.h:34
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
Spectra::TridiagEigen::eigenvectors
const Matrix & eigenvectors() const
Definition: TridiagEigen.h:219
Spectra::TridiagEigen
Definition: TridiagEigen.h:23
Eigen::numext::abs2
EIGEN_DEVICE_FUNC bool abs2(bool x)
Definition: Eigen/src/Core/MathFunctions.h:1294
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
iter
iterator iter(handle obj)
Definition: pytypes.h:2475
Spectra
Definition: LOBPCGSolver.h:19
Eigen::PlainObjectBase::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:247
min
#define min(a, b)
Definition: datatypes.h:19
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic >
Spectra::TridiagEigen::m_main_diag
Vector m_main_diag
Definition: TridiagEigen.h:35
abs
#define abs(x)
Definition: datatypes.h:17
Eigen::PlainObjectBase::setZero
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Definition: CwiseNullaryOp.h:562
Spectra::TridiagEigen::TridiagEigen
TridiagEigen(ConstGenericMatrix &mat)
Definition: TridiagEigen.h:113
Eigen::placeholders::end
static const EIGEN_DEPRECATED end_t end
Definition: IndexedViewHelper.h:181
max
#define max(a, b)
Definition: datatypes.h:20
Spectra::TridiagEigen::tridiagonal_qr_step
static void tridiagonal_qr_step(RealScalar *diag, RealScalar *subdiag, Index start, Index end, Scalar *matrixQ, Index n)
Definition: TridiagEigen.h:42
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:08:22