GenEigsComplexShiftSolver.h
Go to the documentation of this file.
1 // Copyright (C) 2016-2019 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 GEN_EIGS_COMPLEX_SHIFT_SOLVER_H
8 #define GEN_EIGS_COMPLEX_SHIFT_SOLVER_H
9 
10 #include <Eigen/Core>
11 
12 #include "GenEigsBase.h"
13 #include "Util/SelectionRule.h"
15 
16 namespace Spectra {
17 
37 template <typename Scalar = double,
38  int SelectionRule = LARGEST_MAGN,
39  typename OpType = DenseGenComplexShiftSolve<double> >
40 class GenEigsComplexShiftSolver : public GenEigsBase<Scalar, SelectionRule, OpType, IdentityBOp>
41 {
42 private:
44  typedef std::complex<Scalar> Complex;
47 
50 
51  // First transform back the Ritz values, and then sort
52  void sort_ritzpair(int sort_rule)
53  {
54  using std::abs;
55  using std::sqrt;
56  using std::norm;
57 
58  // The eigenvalues we get from the iteration is
59  // nu = 0.5 * (1 / (lambda - sigma) + 1 / (lambda - conj(sigma)))
60  // So the eigenvalues of the original problem is
61  // 1 \pm sqrt(1 - 4 * nu^2 * sigmai^2)
62  // lambda = sigmar + -----------------------------------
63  // 2 * nu
64  // We need to pick the correct root
65  // Let (lambdaj, vj) be the j-th eigen pair, then A * vj = lambdaj * vj
66  // and inv(A - r * I) * vj = 1 / (lambdaj - r) * vj
67  // where r is any shift value.
68  // We can use this identity to determine lambdaj
69  //
70  // op(v) computes Re(inv(A - r * I) * v) for any real v
71  // If r is real, then op(v) is also real. Let a = Re(vj), b = Im(vj),
72  // then op(vj) = op(a) + op(b) * i
73  // By comparing op(vj) and [1 / (lambdaj - r) * vj], we can determine
74  // which one is the correct root
75 
76  // Select a random shift value
77  SimpleRandom<Scalar> rng(0);
78  const Scalar shiftr = rng.random() * m_sigmar + rng.random();
79  const Complex shift = Complex(shiftr, Scalar(0));
80  this->m_op->set_shift(shiftr, Scalar(0));
81 
82  // Calculate inv(A - r * I) * vj
83  Vector v_real(this->m_n), v_imag(this->m_n), OPv_real(this->m_n), OPv_imag(this->m_n);
85  for (Index i = 0; i < this->m_nev; i++)
86  {
87  v_real.noalias() = this->m_fac.matrix_V() * this->m_ritz_vec.col(i).real();
88  v_imag.noalias() = this->m_fac.matrix_V() * this->m_ritz_vec.col(i).imag();
89  this->m_op->perform_op(v_real.data(), OPv_real.data());
90  this->m_op->perform_op(v_imag.data(), OPv_imag.data());
91 
92  // Two roots computed from the quadratic equation
93  const Complex nu = this->m_ritz_val[i];
94  const Complex root_part1 = m_sigmar + Scalar(0.5) / nu;
95  const Complex root_part2 = Scalar(0.5) * sqrt(Scalar(1) - Scalar(4) * m_sigmai * m_sigmai * (nu * nu)) / nu;
96  const Complex root1 = root_part1 + root_part2;
97  const Complex root2 = root_part1 - root_part2;
98 
99  // Test roots
100  Scalar err1 = Scalar(0), err2 = Scalar(0);
101  for (int k = 0; k < this->m_n; k++)
102  {
103  const Complex rhs1 = Complex(v_real[k], v_imag[k]) / (root1 - shift);
104  const Complex rhs2 = Complex(v_real[k], v_imag[k]) / (root2 - shift);
105  const Complex OPv = Complex(OPv_real[k], OPv_imag[k]);
106  err1 += norm(OPv - rhs1);
107  err2 += norm(OPv - rhs2);
108  }
109 
110  const Complex lambdaj = (err1 < err2) ? root1 : root2;
111  this->m_ritz_val[i] = lambdaj;
112 
113  if (abs(Eigen::numext::imag(lambdaj)) > eps)
114  {
115  this->m_ritz_val[i + 1] = Eigen::numext::conj(lambdaj);
116  i++;
117  }
118  else
119  {
120  this->m_ritz_val[i] = Complex(Eigen::numext::real(lambdaj), Scalar(0));
121  }
122  }
123 
125  }
126 
127 public:
147  GenEigsComplexShiftSolver(OpType* op, Index nev, Index ncv, const Scalar& sigmar, const Scalar& sigmai) :
148  GenEigsBase<Scalar, SelectionRule, OpType, IdentityBOp>(op, NULL, nev, ncv),
149  m_sigmar(sigmar), m_sigmai(sigmai)
150  {
151  this->m_op->set_shift(m_sigmar, m_sigmai);
152  }
153 };
154 
155 } // namespace Spectra
156 
157 #endif // GEN_EIGS_COMPLEX_SHIFT_SOLVER_H
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
Spectra::Arnoldi::matrix_V
const Matrix & matrix_V() const
Definition: Arnoldi.h:96
Spectra::GenEigsComplexShiftSolver::Complex
std::complex< Scalar > Complex
Definition: GenEigsComplexShiftSolver.h:44
Spectra::GenEigsComplexShiftSolver::Index
Eigen::Index Index
Definition: GenEigsComplexShiftSolver.h:43
Spectra::DenseGenComplexShiftSolve::set_shift
void set_shift(Scalar sigmar, Scalar sigmai)
Definition: DenseGenComplexShiftSolve.h:77
real
float real
Definition: datatypes.h:10
Spectra::GenEigsComplexShiftSolver::GenEigsComplexShiftSolver
GenEigsComplexShiftSolver(OpType *op, Index nev, Index ncv, const Scalar &sigmar, const Scalar &sigmai)
Definition: GenEigsComplexShiftSolver.h:147
Spectra::GenEigsComplexShiftSolver::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: GenEigsComplexShiftSolver.h:45
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_n
const Index m_n
Definition: GenEigsBase.h:63
Spectra::IdentityBOp
Definition: ArnoldiOp.h:90
epsilon
static double epsilon
Definition: testRot3.cpp:37
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_op
DenseGenComplexShiftSolve< double > * m_op
Definition: GenEigsBase.h:61
imag
const EIGEN_DEVICE_FUNC ImagReturnType imag() const
Definition: CommonCwiseUnaryOps.h:109
Spectra::GenEigsBase
Definition: GenEigsBase.h:40
Spectra::LARGEST_MAGN
@ LARGEST_MAGN
Definition: SelectionRule.h:32
conj
AnnoyingScalar conj(const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:104
Spectra::GenEigsBase::sort_ritzpair
virtual void sort_ritzpair(int sort_rule)
Definition: GenEigsBase.h:214
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_fac
ArnoldiFac m_fac
Definition: GenEigsBase.h:69
Spectra::GenEigsComplexShiftSolver::ComplexVector
Eigen::Matrix< Complex, Eigen::Dynamic, 1 > ComplexVector
Definition: GenEigsComplexShiftSolver.h:46
Spectra::DenseGenComplexShiftSolve::perform_op
void perform_op(const Scalar *x_in, Scalar *y_out)
Definition: DenseGenComplexShiftSolve.h:92
Spectra::GenEigsComplexShiftSolver::m_sigmar
const Scalar m_sigmar
Definition: GenEigsComplexShiftSolver.h:48
SelectionRule.h
DenseGenComplexShiftSolve.h
Spectra::GenEigsComplexShiftSolver
Definition: GenEigsComplexShiftSolver.h:40
Spectra::GenEigsComplexShiftSolver::m_sigmai
const Scalar m_sigmai
Definition: GenEigsComplexShiftSolver.h:49
Spectra
Definition: LOBPCGSolver.h:19
Eigen::PlainObjectBase::data
EIGEN_DEVICE_FUNC const EIGEN_STRONG_INLINE Scalar * data() const
Definition: PlainObjectBase.h:247
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 >
abs
#define abs(x)
Definition: datatypes.h:17
NULL
#define NULL
Definition: ccolamd.c:609
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_ritz_vec
ComplexMatrix m_ritz_vec
Definition: GenEigsBase.h:72
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_ritz_val
ComplexVector m_ritz_val
Definition: GenEigsBase.h:71
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
Spectra::GenEigsBase< double, LARGEST_MAGN, DenseGenComplexShiftSolve< double >, IdentityBOp >::m_nev
const Index m_nev
Definition: GenEigsBase.h:64
Spectra::GenEigsComplexShiftSolver::sort_ritzpair
void sort_ritzpair(int sort_rule)
Definition: GenEigsComplexShiftSolver.h:52
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
GenEigsBase.h


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:00:54