Lanczos.h
Go to the documentation of this file.
1 // Copyright (C) 2018-2025 Yixuan Qiu <yixuan.qiu@cos.name>
2 //
3 // This Source Code Form is subject to the terms of the Mozilla
4 // Public License v. 2.0. If a copy of the MPL was not distributed
5 // with this file, You can obtain one at https://mozilla.org/MPL/2.0/.
6 
7 #ifndef SPECTRA_LANCZOS_H
8 #define SPECTRA_LANCZOS_H
9 
10 #include <Eigen/Core>
11 #include <cmath> // std::sqrt
12 #include <utility> // std::forward
13 #include <stdexcept> // std::invalid_argument
14 
15 #include "Arnoldi.h"
16 
17 namespace Spectra {
18 
19 // Lanczos factorization A * V = V * H + f * e'
20 // A: n x n
21 // V: n x k
22 // H: k x k
23 // f: n x 1
24 // e: [0, ..., 0, 1]
25 // V and H are allocated of dimension m, so the maximum value of k is m
26 template <typename Scalar, typename ArnoldiOpType>
27 class Lanczos : public Arnoldi<Scalar, ArnoldiOpType>
28 {
29 private:
30  // The real part type of the matrix element
39 
50 
51 public:
52  // Forward parameter `op` to the constructor of Arnoldi
53  template <typename T>
54  Lanczos(T&& op, Index m) :
55  Arnoldi<Scalar, ArnoldiOpType>(std::forward<T>(op), m)
56  {}
57 
58  // Lanczos factorization starting from step-k
59  void factorize_from(Index from_k, Index to_m, Index& op_counter) override
60  {
61  using std::abs;
62  using std::sqrt;
63 
64  if (to_m <= from_k)
65  return;
66 
67  if (from_k > m_k)
68  {
69  std::string msg = "Lanczos: from_k (= " + std::to_string(from_k) +
70  ") is larger than the current subspace dimension (= " + std::to_string(m_k) + ")";
71  throw std::invalid_argument(msg);
72  }
73 
74  const RealScalar beta_thresh = m_eps * sqrt(RealScalar(m_n));
75  const RealScalar eps_sqrt = sqrt(m_eps);
76 
77  // Pre-allocate vectors
78  Vector Vf(to_m);
79  Vector w(m_n);
80 
81  // Keep the upperleft k x k submatrix of H and set other elements to 0
82  m_fac_H.rightCols(m_m - from_k).setZero();
83  m_fac_H.block(from_k, 0, m_m - from_k, from_k).setZero();
84 
85  for (Index i = from_k; i <= to_m - 1; i++)
86  {
87  // If beta = 0, then the next V is not full rank
88  // We need to generate a new residual vector that is orthogonal
89  // to the current V, which we call a restart
90  //
91  // A simple criterion is beta < near_0, but it may be too stringent
92  // Another heuristic is to test whether (V^H)B(f/||f||) ~= 0 when ||f|| is small,
93  // and to reduce the computational cost, we only use the latest Vi
94 
95  // Test the first criterion
96  bool restart = (m_beta < m_near_0);
97  // If not met, test the second criterion
98  // v is the (i+1)-th column of V
99  MapVec v(&m_fac_V(0, i), m_n);
100  if (!restart)
101  {
102  // Save v <- f / ||f|| to the (i+1)-th column of V
103  v.noalias() = m_fac_f / m_beta;
104  if (m_beta < eps_sqrt)
105  {
106  // Test (Vi^H)v
107  const Scalar Viv = m_op.inner_product(m_fac_V.col(i - 1), v);
108  // Restart V if (Vi^H)v is much larger than eps
109  restart = (abs(Viv) > eps_sqrt);
110  }
111  }
112 
113  if (restart)
114  {
115  MapConstMat V(m_fac_V.data(), m_n, i); // The first i columns
116  this->expand_basis(V, 2 * i, m_fac_f, m_beta, op_counter);
117  v.noalias() = m_fac_f / m_beta;
118  }
119 
120  // Whether there is a restart or not, right now the (i+1)-th column of V
121  // contains f / ||f||
122 
123  // Note that H[i+1, i] equals to the unrestarted beta
124  m_fac_H(i, i - 1) = restart ? Scalar(0) : Scalar(m_beta);
125  m_fac_H(i - 1, i) = m_fac_H(i, i - 1); // Due to symmetry
126 
127  // w <- A * v
128  m_op.perform_op(v.data(), w.data());
129  op_counter++;
130 
131  // f <- w - V * (V^H)Bw = w - H[i+1, i] * V{i} - H[i+1, i+1] * V{i+1}
132  // If restarting, we know that H[i+1, i] = 0
133  // First do w <- w - H[i+1, i] * V{i}, see the discussions in Section 2.3 of
134  // Cullum and Willoughby (2002). Lanczos Algorithms for Large Symmetric Eigenvalue Computations: Vol. 1
135  if (!restart)
136  w.noalias() -= m_fac_H(i, i - 1) * m_fac_V.col(i - 1);
137 
138  // H[i+1, i+1] = <v, w> = (v^H)Bw
139  m_fac_H(i, i) = m_op.inner_product(v, w);
140 
141  // f <- w - H[i+1, i+1] * V{i+1}
142  m_fac_f.noalias() = w - m_fac_H(i, i) * v;
143  m_beta = m_op.norm(m_fac_f);
144 
145  // f/||f|| is going to be the next column of V, so we need to test
146  // whether (V^H)B(f/||f||) ~= 0
147  const Index i1 = i + 1;
148  MapMat Vs(m_fac_V.data(), m_n, i1); // The first (i+1) columns
149  m_op.adjoint_product(Vs, m_fac_f, Vf.head(i1));
150  RealScalar ortho_err = Vf.head(i1).cwiseAbs().maxCoeff();
151  // If not, iteratively correct the residual
152  int count = 0;
153  while (count < 5 && ortho_err > m_eps * m_beta)
154  {
155  // There is an edge case: when beta=||f|| is close to zero, f mostly consists
156  // of noises of rounding errors, so the test [ortho_err < eps * beta] is very
157  // likely to fail. In particular, if beta=0, then the test is ensured to fail.
158  // Hence when this happens, we force f to be zero, and then restart in the
159  // next iteration.
160  if (m_beta < beta_thresh)
161  {
162  m_fac_f.setZero();
163  m_beta = RealScalar(0);
164  break;
165  }
166 
167  // f <- f - V * Vf
168  m_fac_f.noalias() -= Vs * Vf.head(i1);
169  // h <- h + Vf
170  m_fac_H(i - 1, i) += Vf[i - 1];
171  m_fac_H(i, i - 1) = m_fac_H(i - 1, i);
172  m_fac_H(i, i) += Vf[i];
173  // beta <- ||f||
174  m_beta = m_op.norm(m_fac_f);
175 
176  m_op.adjoint_product(Vs, m_fac_f, Vf.head(i1));
177  ortho_err = Vf.head(i1).cwiseAbs().maxCoeff();
178  count++;
179  }
180  }
181 
182  // Indicate that this is a step-m factorization
183  m_k = to_m;
184  }
185 
186  // Apply H -> Q'HQ, where Q is from a tridiagonal QR decomposition
187  // Function overloading here, not overriding
188  //
189  // Note that H is by nature a real symmetric matrix, but it may be stored
190  // as a complex matrix (e.g. in HermEigsSolver).
191  // Therefore, if m_fac_H has a real type (as in SymEigsSolver), then we
192  // directly overwrite m_fac_H. Otherwise, m_fac_H has a complex type
193  // (as in HermEigsSolver), so we first compute the real-typed result,
194  // and then cast to the complex type. This is done in the TridiagQR class
195  void compress_H(const TridiagQR<RealScalar>& decomp)
196  {
197  decomp.matrix_QtHQ(m_fac_H);
198  m_k--;
199  }
200 
201  // In some cases we know that H has the form H = [X e 0],
202  // [e' s 0]
203  // [0 0 D]
204  // where X is an irreducible tridiagonal matrix, D is a diagonal matrix,
205  // s is a scalar, and e = (0, ..., 0, eps), eps ~= 0
206  //
207  // In this case we can force H[m+1, m] = H[m, m+1] = 0 and H[m+1, m+1] = s,
208  // where m is the size of X
209  void deflate_H(Index irr_size, const Scalar& s)
210  {
211  m_fac_H(irr_size, irr_size - 1) = Scalar(0);
212  m_fac_H(irr_size - 1, irr_size) = Scalar(0);
213  m_fac_H(irr_size, irr_size) = s;
214  }
215 };
216 
217 } // namespace Spectra
218 
219 #endif // SPECTRA_LANCZOS_H
Spectra::Lanczos::factorize_from
void factorize_from(Index from_k, Index to_m, Index &op_counter) override
Definition: Lanczos.h:59
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
Spectra::Arnoldi
Definition: Arnoldi.h:31
Spectra::Arnoldi::m_fac_f
Vector m_fac_f
Definition: Arnoldi.h:56
s
RealScalar s
Definition: level1_cplx_impl.h:126
Spectra::Arnoldi::m_near_0
const RealScalar m_near_0
Definition: Arnoldi.h:46
Spectra::Arnoldi::RealScalar
typename Eigen::NumTraits< Scalar >::Real RealScalar
Definition: Arnoldi.h:35
Spectra::Arnoldi::m_beta
RealScalar m_beta
Definition: Arnoldi.h:57
Spectra::Arnoldi::m_n
const Index m_n
Definition: Arnoldi.h:51
Spectra::Lanczos::Lanczos
Lanczos(T &&op, Index m)
Definition: Lanczos.h:54
Spectra::Lanczos::deflate_H
void deflate_H(Index irr_size, const Scalar &s)
Definition: Lanczos.h:209
Arnoldi.h
Spectra::Arnoldi::m_op
ArnoldiOpType m_op
Definition: Arnoldi.h:50
Spectra::Arnoldi::Index
Eigen::Index Index
Definition: Arnoldi.h:36
Spectra::Lanczos
Definition: Lanczos.h:27
Spectra::Arnoldi::m_k
Index m_k
Definition: Arnoldi.h:53
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
Spectra::Arnoldi::expand_basis
void expand_basis(MapConstMat &V, const Index seed, Vector &f, RealScalar &fnorm, Index &op_counter)
Definition: Arnoldi.h:62
Eigen::Triplet< double >
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
Spectra::Arnoldi::m_m
const Index m_m
Definition: Arnoldi.h:52
Spectra::Arnoldi::m_fac_H
Matrix m_fac_H
Definition: Arnoldi.h:55
Spectra::Lanczos::RealScalar
typename Eigen::NumTraits< Scalar >::Real RealScalar
Definition: Lanczos.h:31
forward
Definition: testScenarioRunner.cpp:79
i1
double i1(double x)
Definition: i1.c:150
std
Definition: BFloat16.h:88
Spectra::Arnoldi::m_fac_V
Matrix m_fac_V
Definition: Arnoldi.h:54
Spectra
Definition: LOBPCGSolver.h:19
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
Eigen::PlainObjectBase::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:247
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic >
abs
#define abs(x)
Definition: datatypes.h:17
Eigen::PlainObjectBase::setZero
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Definition: CwiseNullaryOp.h:562
Spectra::Arnoldi::m_eps
const RealScalar m_eps
Definition: Arnoldi.h:48
Spectra::Lanczos::compress_H
void compress_H(const TridiagQR< RealScalar > &decomp)
Definition: Lanczos.h:195
Spectra::TridiagQR
Definition: UpperHessenbergQR.h:545
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Scalar
SCALAR Scalar
Definition: bench_gemm.cpp:46
Spectra::TridiagQR::matrix_QtHQ
void matrix_QtHQ(Matrix &dest) const override
Definition: UpperHessenbergQR.h:713
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
pybind11.msg
msg
Definition: wrap/pybind11/pybind11/__init__.py:6


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:01:42