Go to the documentation of this file.
17 template<
typename _MatrixType,
int _UpLo>
struct traits<
LLT<_MatrixType, _UpLo> >
26 template<
typename MatrixType,
int UpLo>
struct LLT_Traits;
66 template<
typename _MatrixType,
int _UpLo>
class LLT
104 template<
typename InputType>
119 template<
typename InputType>
128 inline typename Traits::MatrixU
matrixU()
const
135 inline typename Traits::MatrixL
matrixL()
const
141 #ifdef EIGEN_PARSED_BY_DOXYGEN
152 template<
typename Rhs>
157 template<
typename Derived>
160 template<
typename InputType>
207 template<
typename VectorType>
210 #ifndef EIGEN_PARSED_BY_DOXYGEN
211 template<
typename RhsType,
typename DstType>
212 void _solve_impl(
const RhsType &rhs, DstType &dst)
const;
214 template<
bool Conjugate,
typename RhsType,
typename DstType>
239 template<
typename MatrixType,
typename VectorType>
271 ColXprSegment
x(
mat.col(
i).tail(rs));
272 TempVecSegment
y(temp.tail(rs));
293 mat.coeffRef(
j,
j) = nLjj;
300 temp.tail(rs) -= (wj/Ljj) *
mat.col(
j).tail(rs);
312 template<
typename MatrixType>
328 if (k>0)
x -=
A10.squaredNorm();
332 if (k>0 && rs>0)
A21.noalias() -= A20 *
A10.adjoint();
338 template<
typename MatrixType>
347 blockSize = (blockSize/16)*16;
363 if((
ret=unblocked(
A11))>=0)
return k+
ret;
364 if(rs>0)
A11.adjoint().template triangularView<Upper>().template solveInPlace<OnTheRight>(
A21);
370 template<
typename MatrixType,
typename VectorType>
381 template<
typename MatrixType>
387 template<
typename MatrixType>
393 template<
typename MatrixType,
typename VectorType>
430 template<
typename MatrixType,
int _UpLo>
431 template<
typename InputType>
434 check_template_parameters();
440 m_matrix =
a.derived();
448 abs_col_sum = m_matrix.col(
col).tail(
size -
col).template lpNorm<1>() + m_matrix.row(
col).head(
col).template lpNorm<1>();
450 abs_col_sum = m_matrix.col(
col).head(
col).template lpNorm<1>() + m_matrix.row(
col).tail(
size -
col).template lpNorm<1>();
451 if (abs_col_sum > m_l1_norm)
452 m_l1_norm = abs_col_sum;
455 m_isInitialized =
true;
456 bool ok = Traits::inplace_decomposition(m_matrix);
467 template<
typename _MatrixType,
int _UpLo>
468 template<
typename VectorType>
482 #ifndef EIGEN_PARSED_BY_DOXYGEN
483 template<
typename _MatrixType,
int _UpLo>
484 template<
typename RhsType,
typename DstType>
487 _solve_impl_transposed<true>(rhs, dst);
490 template<
typename _MatrixType,
int _UpLo>
491 template<
bool Conjugate,
typename RhsType,
typename DstType>
496 matrixL().template conjugateIf<!Conjugate>().solveInPlace(dst);
497 matrixU().template conjugateIf<!Conjugate>().solveInPlace(dst);
514 template<
typename MatrixType,
int _UpLo>
515 template<
typename Derived>
518 eigen_assert(m_isInitialized &&
"LLT is not initialized.");
520 matrixL().solveInPlace(bAndX);
521 matrixU().solveInPlace(bAndX);
527 template<
typename MatrixType,
int _UpLo>
530 eigen_assert(m_isInitialized &&
"LLT is not initialized.");
531 return matrixL() * matrixL().adjoint().toDenseMatrix();
538 template<
typename Derived>
549 template<
typename MatrixType,
unsigned int UpLo>
558 #endif // EIGEN_LLT_H
static bool inplace_decomposition(MatrixType &m)
const LLT & adjoint() const EIGEN_NOEXCEPT
Namespace containing all symbols from the Eigen library.
static MatrixL getL(const MatrixType &m)
internal::traits< LLT< Matrix< double, Eigen::Dynamic, Eigen::Dynamic >, _UpLo > >::Scalar Scalar
Expression of a fixed-size or dynamic-size block.
Eigen::Index Index
The interface type of indices.
internal::LLT_Traits< MatrixType, UpLo > Traits
const LLT< PlainObject > llt() const
void solveInPlace(const MatrixBase< Derived > &bAndX) const
VectorBlock< Derived > SegmentReturnType
NumTraits< Scalar >::Real RealScalar
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
static Index unblocked(MatrixType &mat)
const LLT< PlainObject, UpLo > llt() const
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index size() const EIGEN_NOEXCEPT
NumTraits< Scalar >::Real RealScalar
const typedef TriangularView< const MatrixType, Upper > MatrixU
#define EIGEN_STATIC_ASSERT_VECTOR_ONLY(TYPE)
const typedef TriangularView< const typename MatrixType::AdjointReturnType, Upper > MatrixU
Rotation given by a cosine-sine pair.
double beta(double a, double b)
Decomposition::RealScalar rcond_estimate_helper(typename Decomposition::RealScalar matrix_norm, const Decomposition &dec)
Reciprocal condition number estimator.
static bool inplace_decomposition(MatrixType &m)
Expression of the transpose of a matrix.
static const double sigma
EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
static Index blocked(MatrixType &m)
LLT & compute(const EigenBase< InputType > &matrix)
#define EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)
Traits::MatrixL matrixL() const
static MatrixL getL(const MatrixType &m)
const typedef TriangularView< const typename MatrixType::AdjointReturnType, Lower > MatrixL
#define EIGEN_STRONG_INLINE
LLT & rankUpdate(const VectorType &vec, const RealScalar &sigma=1)
EIGEN_DEVICE_FUNC LLT< _MatrixType, _UpLo > & derived()
static Index rankUpdate(MatrixType &mat, const VectorType &vec, const RealScalar &sigma)
static MatrixU getU(const MatrixType &m)
MatrixType reconstructedMatrix() const
const typedef TriangularView< const MatrixType, Lower > MatrixL
void _solve_impl(const RhsType &rhs, DstType &dst) const
static void check_template_parameters()
AnnoyingScalar conj(const AnnoyingScalar &x)
static MatrixU getU(const MatrixType &m)
void g(const string &key, int i)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Block< Derived, internal::traits< Derived >::RowsAtCompileTime, 1, !IsRowMajor > ColXpr
static Index llt_rank_update_lower(MatrixType &mat, const VectorType &vec, const typename MatrixType::RealScalar &sigma)
static Index rankUpdate(MatrixType &mat, const VectorType &vec, const RealScalar &sigma)
NumTraits< Scalar >::Real RealScalar
static const double A10[]
static EIGEN_STRONG_INLINE Index blocked(MatrixType &mat)
Standard Cholesky decomposition (LL^T) of a matrix and associated features.
static EIGEN_STRONG_INLINE Index unblocked(MatrixType &mat)
EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const
EIGEN_DEVICE_FUNC bool abs2(bool x)
Pseudo expression representing a solving operation.
ComputationInfo info() const
Reports whether previous computation was successful.
LLT(Index size)
Default Constructor with memory preallocation.
LLT(EigenBase< InputType > &matrix)
Constructs a LLT factorization from a given matrix.
SolverStorage StorageKind
EIGEN_DEVICE_FUNC bool is_same_dense(const T1 &mat1, const T2 &mat2, typename enable_if< possibly_same_dense< T1, T2 >::value >::type *=0)
Array< int, Dynamic, 1 > v
static const double A11[]
LLT(const EigenBase< InputType > &matrix)
Traits::MatrixU matrixU() const
Base class for all dense matrices, vectors, and expressions.
EIGEN_CONSTEXPR Index size(const T &x)
const MatrixType & matrixLLT() const
LLT()
Default Constructor.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
Jet< T, N > sqrt(const Jet< T, N > &f)
EIGEN_DEVICE_FUNC void apply_rotation_in_the_plane(DenseBase< VectorX > &xpr_x, DenseBase< VectorY > &xpr_y, const JacobiRotation< OtherScalar > &j)
const Solve< LLT< _MatrixType, _UpLo >, Rhs > solve(const MatrixBase< Rhs > &b) const
A base class for matrix decomposition and solvers.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:43