Go to the documentation of this file.
10 #ifndef EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H
11 #define EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H
16 template <
typename _MatrixType>
50 template <
typename _MatrixType>
class CompleteOrthogonalDecomposition
51 :
public SolverBase<CompleteOrthogonalDecomposition<_MatrixType> >
57 template<
typename Derived>
117 template <
typename InputType>
132 template<
typename InputType>
141 #ifdef EIGEN_PARSED_BY_DOXYGEN
151 template <
typename Rhs>
163 applyZOnTheLeftInPlace<false>(
Z);
185 template <
typename InputType>
371 #ifndef EIGEN_PARSED_BY_DOXYGEN
372 template <
typename RhsType,
typename DstType>
373 void _solve_impl(
const RhsType& rhs, DstType& dst)
const;
375 template<
bool Conjugate,
typename RhsType,
typename DstType>
384 template<
bool Transpose_,
typename Rhs>
388 eigen_assert((Transpose_?derived().
cols():derived().
rows())==
b.rows() &&
"CompleteOrthogonalDecomposition::solve(): invalid number of rows of the right hand side matrix b");
397 template <
bool Conjugate,
typename Rhs>
402 template <
typename Rhs>
410 template <
typename MatrixType>
413 return m_cpqr.absDeterminant();
416 template <
typename MatrixType>
419 return m_cpqr.logAbsDeterminant();
429 template <
typename MatrixType>
432 check_template_parameters();
437 const Index rank = m_cpqr.rank();
455 for (
Index k = rank - 1; k >= 0; --k) {
460 m_cpqr.m_qr.col(k).head(k + 1).swap(
461 m_cpqr.m_qr.col(rank - 1).head(k + 1));
468 .tail(
cols - rank + 1)
469 .makeHouseholderInPlace(m_zCoeffs(k),
beta);
470 m_cpqr.m_qr(k, rank - 1) =
beta;
473 m_cpqr.m_qr.topRightCorner(k,
cols - rank + 1)
474 .applyHouseholderOnTheRight(
475 m_cpqr.m_qr.row(k).tail(
cols - rank).adjoint(), m_zCoeffs(k),
480 m_cpqr.m_qr.col(k).head(k + 1).swap(
481 m_cpqr.m_qr.col(rank - 1).head(k + 1));
487 template <
typename MatrixType>
488 template <
bool Conjugate,
typename Rhs>
492 const Index nrhs = rhs.cols();
493 const Index rank = this->rank();
495 for (
Index k = rank-1; k >= 0; --k) {
497 rhs.row(k).swap(rhs.row(rank - 1));
499 rhs.middleRows(rank - 1,
cols - rank + 1)
500 .applyHouseholderOnTheLeft(
501 matrixQTZ().
row(k).
tail(
cols - rank).transpose().
template conjugateIf<!Conjugate>(), zCoeffs().
template conjugateIf<Conjugate>()(k),
504 rhs.row(k).swap(rhs.row(rank - 1));
509 template <
typename MatrixType>
510 template <
typename Rhs>
514 const Index nrhs = rhs.cols();
515 const Index rank = this->rank();
517 for (
Index k = 0; k < rank; ++k) {
519 rhs.row(k).swap(rhs.row(rank - 1));
521 rhs.middleRows(rank - 1,
cols - rank + 1)
522 .applyHouseholderOnTheLeft(
526 rhs.row(k).swap(rhs.row(rank - 1));
531 #ifndef EIGEN_PARSED_BY_DOXYGEN
532 template <
typename _MatrixType>
533 template <
typename RhsType,
typename DstType>
535 const RhsType& rhs, DstType& dst)
const {
536 const Index rank = this->rank();
543 typename RhsType::PlainObject
c(rhs);
544 c.applyOnTheLeft(matrixQ().setLength(rank).
adjoint());
547 dst.topRows(rank) = matrixT()
548 .topLeftCorner(rank, rank)
549 .template triangularView<Upper>()
550 .solve(
c.topRows(rank));
556 dst.bottomRows(
cols - rank).setZero();
557 applyZAdjointOnTheLeftInPlace(dst);
561 dst = colsPermutation() * dst;
564 template<
typename _MatrixType>
565 template<
bool Conjugate,
typename RhsType,
typename DstType>
568 const Index rank = this->rank();
575 typename RhsType::PlainObject
c(colsPermutation().transpose()*rhs);
578 applyZOnTheLeftInPlace<!Conjugate>(
c);
581 matrixT().topLeftCorner(rank, rank)
582 .template triangularView<Upper>()
583 .transpose().template conjugateIf<Conjugate>()
584 .solveInPlace(
c.topRows(rank));
586 dst.topRows(rank) =
c.topRows(rank);
587 dst.bottomRows(
rows()-rank).setZero();
589 dst.applyOnTheLeft(householderQ().setLength(rank).
template conjugateIf<!Conjugate>() );
595 template<
typename MatrixType>
597 :
traits<typename Transpose<typename MatrixType::PlainObject>::PlainObject>
602 template<
typename DstXprType,
typename MatrixType>
617 template <
typename MatrixType>
620 return m_cpqr.householderQ();
627 template <
typename Derived>
635 #endif // EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H
Expression of the inverse of another expression.
ColPivHouseholderQR & setThreshold(const RealScalar &threshold)
const PermutationType & colsPermutation() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE FixedSegmentReturnType< internal::get_fixed_value< NType >::value >::Type tail(NType n)
Namespace containing all symbols from the Eigen library.
Index dimensionOfKernel() const
RealScalar threshold() const
const HCoeffsType & hCoeffs() const
ColPivHouseholderQR< MatrixType > m_cpqr
Inverse< CodType > SrcXprType
MatrixType::RealScalar logAbsDeterminant() const
const Inverse< CompleteOrthogonalDecomposition > pseudoInverse() const
Eigen::Index Index
The interface type of indices.
const HCoeffsType & hCoeffs() const
bool isInvertible() const
MatrixType::PlainObject PlainObject
const HCoeffsType & zCoeffs() const
void applyZOnTheLeftInPlace(Rhs &rhs) const
void _check_solve_assertion(const Rhs &b) const
double beta(double a, double b)
PermutationType::Index PermIndexType
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
CompleteOrthogonalDecomposition(Index rows, Index cols)
Default Constructor with memory preallocation.
HouseholderSequence< MatrixType, typename internal::remove_all< typename HCoeffsType::ConjugateReturnType >::type > HouseholderSequenceType
RealScalar maxPivot() const
bool isSurjective() const
CompleteOrthogonalDecomposition(EigenBase< InputType > &matrix)
Constructs a complete orthogonal decomposition from a given matrix.
#define EIGEN_ONLY_USED_FOR_DEBUG(x)
CompleteOrthogonalDecomposition & compute(const EigenBase< InputType > &matrix)
static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op< typename DstXprType::Scalar, typename CodType::Scalar > &)
HouseholderSequenceType householderQ(void) const
SolverStorage StorageKind
#define EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)
const MatrixType & matrixT() const
internal::plain_row_type< MatrixType, Index >::type IntRowVectorType
CompleteOrthogonalDecomposition & setThreshold(const RealScalar &threshold)
const MatrixType & matrixQTZ() const
SolverBase< CompleteOrthogonalDecomposition > Base
ColPivHouseholderQR & compute(const EigenBase< InputType > &matrix)
RealScalar maxPivot() const
void applyZAdjointOnTheLeftInPlace(Rhs &rhs) const
const EIGEN_DEVICE_FUNC XprTypeNestedCleaned & nestedExpression() const
MatrixType::RealScalar absDeterminant() const
CompleteOrthogonalDecomposition(const EigenBase< InputType > &matrix)
Constructs a complete orthogonal decomposition from a given matrix.
Complete orthogonal decomposition (COD) of a matrix.
MatrixType matrixZ() const
Index dimensionOfKernel() const
internal::plain_row_type< MatrixType >::type RowVectorType
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
ComputationInfo info() const
Reports whether the complete orthogonal decomposition was successful.
static void check_template_parameters()
NumTraits< Scalar >::Real RealScalar
PermutationMatrix< ColsAtCompileTime, MaxColsAtCompileTime > PermutationType
const CompleteOrthogonalDecomposition< PlainObject > completeOrthogonalDecomposition() const
void _solve_impl(const RhsType &rhs, DstType &dst) const
Pseudo expression representing a solving operation.
bool isInvertible() const
const MatrixType & matrixQR() const
Index nonzeroPivots() const
internal::conditional< NumTraits< Scalar >::IsComplex, const CwiseUnaryOp< internal::scalar_conjugate_op< Scalar >, const Derived >, const Derived & >::type ConjugateReturnType
RealScalar threshold() const
The matrix class, also used for vectors and row-vectors.
Index nonzeroPivots() const
Base class for all dense matrices, vectors, and expressions.
CleanedUpDerType< DerType >::type() min(const AutoDiffScalar< DerType > &x, const T &y)
internal::plain_diag_type< MatrixType >::type HCoeffsType
bool isSurjective() const
void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const
HouseholderSequenceType matrixQ(void) const
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
void adjoint(const MatrixType &m)
internal::nested_eval< T, 1 >::type eval(const T &xpr)
HouseholderSequenceType householderQ() const
const PermutationType & colsPermutation() const
internal::plain_row_type< MatrixType, RealScalar >::type RealRowVectorType
CompleteOrthogonalDecomposition()
Default Constructor.
A base class for matrix decomposition and solvers.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
CompleteOrthogonalDecomposition & setThreshold(Default_t)
Sequence of Householder reflections acting on subspaces with decreasing size.
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
CompleteOrthogonalDecomposition< MatrixType > CodType
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:00