Go to the documentation of this file.
35 template<
typename Vector,
typename RealScalar>
53 return angle * (ns / nt) * (ts /
abs(ts));
55 return ts / (nt * nt);
58 template <
typename MatrixType,
typename Rhs,
typename Dest,
typename Preconditioner>
68 S =
S <
x.rows() ?
S :
x.rows();
72 Index replacements = 0;
80 P = (
qr.householderQ() * DenseMatrixType::Identity(
N,
S));
126 relres = normr / normb;
130 DenseMatrixType
G = DenseMatrixType::Zero(
N,
S);
131 DenseMatrixType
U = DenseMatrixType::Zero(
N,
S);
132 DenseMatrixType
M = DenseMatrixType::Identity(
S,
S);
139 while (normr > tolb &&
iter < maxit)
144 for (
Index k = 0; k <
S; ++k)
148 lu_solver.
compute(
M.block(k , k ,
S -k,
S - k ));
151 v = r -
G.rightCols(
S - k ) *
c;
153 v = precond.solve(
v);
156 U.col(k) =
U.rightCols(
S - k ) *
c + om *
v;
157 G.col(k) =
A *
U.col(k );
164 G.col(k ) =
G.col(k ) -
alpha *
G.col(
i );
165 U.col(k ) =
U.col(k ) -
alpha *
U.col(
i );
170 M.block(k , k ,
S - k , 1) = (
G.col(k ).adjoint() *
P.rightCols(
S - k )).
adjoint();
179 r = r -
beta *
G.col(k );
183 if (replacement && normr > tolb /
mp)
195 x_s = x_s -
gamma * (x_s -
x);
199 if (normr < tolb ||
iter == maxit)
207 f.segment(k + 1,
S - (k + 1) ) =
f.segment(k + 1 ,
S - (k + 1)) -
beta *
M.block(k + 1 , k ,
S - (k + 1), 1);
211 if (normr < tolb ||
iter == maxit)
220 v = precond.solve(
v);
237 if (replacement && normr > tolb /
mp)
243 if (trueres && normr < normb)
256 x_s = x_s -
gamma * (x_s -
x);
274 template <
typename _MatrixType,
typename _Preconditioner = DiagonalPreconditioner<
typename _MatrixType::Scalar> >
280 template <
typename _MatrixType,
typename _Preconditioner>
330 template <
typename _MatrixType,
typename _Preconditioner>
366 template <
typename MatrixDerived>
376 template <
typename Rhs,
typename Dest>
Namespace containing all symbols from the Eigen library.
IterativeSolverBase< IDRS > Base
_Preconditioner Preconditioner
IDRS(const EigenBase< MatrixDerived > &A)
void _solve_vector_with_guess_impl(const Rhs &b, Dest &x) const
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
_Preconditioner Preconditioner
EIGEN_DEVICE_FUNC bool isApprox(const Scalar &x, const Scalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
void setResidualUpdate(bool update)
LU decomposition of a matrix with complete pivoting, and related features.
double beta(double a, double b)
void setAngle(RealScalar angle)
FullPivLU & compute(const EigenBase< InputType > &matrix)
Index maxIterations() const
MatrixType::RealScalar RealScalar
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
The Induced Dimension Reduction method (IDR(s)) is a short-recurrences Krylov method for sparse squar...
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Base class for linear iterative solvers.
NumTraits< Scalar >::Real RealScalar
HouseholderQR< MatrixXf > qr(A)
iterator iter(handle obj)
void setSmoothing(bool smoothing)
JacobiRotation< float > G
const ActualMatrixType & matrix() const
Array< int, Dynamic, 1 > v
EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE internal::enable_if< NumTraits< T >::IsSigned||NumTraits< T >::IsComplex, typename NumTraits< T >::Real >::type abs(const T &x)
Preconditioner m_preconditioner
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
void adjoint(const MatrixType &m)
bool idrs(const MatrixType &A, const Rhs &b, Dest &x, const Preconditioner &precond, Index &iter, typename Dest::RealScalar &relres, Index S, bool smoothing, typename Dest::RealScalar angle, bool replacement)
Householder QR decomposition of a matrix.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
MatrixType::Scalar Scalar
Matrix< RealScalar, Dynamic, Dynamic > M
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:44