Public Types | Public Member Functions | Protected Types | Protected Attributes | Friends | List of all members
Eigen::SparseQR Class Reference

Sparse left-looking QR factorization with numerical column pivoting. More...

#include <SparseQR.h>

Public Types

enum  { ColsAtCompileTime = MatrixType::ColsAtCompileTime, MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime }
 
typedef Matrix< StorageIndex, Dynamic, 1 > IndexVector
 
typedef _MatrixType MatrixType
 
typedef _OrderingType OrderingType
 
typedef PermutationMatrix< Dynamic, Dynamic, StorageIndexPermutationType
 
typedef SparseMatrix< Scalar, ColMajor, StorageIndexQRMatrixType
 
typedef MatrixType::RealScalar RealScalar
 
typedef MatrixType::Scalar Scalar
 
typedef Matrix< Scalar, Dynamic, 1 > ScalarVector
 
typedef MatrixType::StorageIndex StorageIndex
 

Public Member Functions

template<typename Rhs , typename Dest >
bool _solve_impl (const MatrixBase< Rhs > &B, MatrixBase< Dest > &dest) const
 
template<typename Rhs , typename Dest >
void _solve_impl (const SparseMatrixBase< Rhs > &b, SparseMatrixBase< Dest > &dest) const
 
void _sort_matrix_Q ()
 
void analyzePattern (const MatrixType &mat)
 Preprocessing step of a QR factorization. More...
 
Index cols () const
 
const PermutationTypecolsPermutation () const
 
void compute (const MatrixType &mat)
 
void factorize (const MatrixType &mat)
 Performs the numerical QR factorization of the input matrix. More...
 
ComputationInfo info () const
 Reports whether previous computation was successful. More...
 
std::string lastErrorMessage () const
 
SparseQRMatrixQReturnType< SparseQRmatrixQ () const
 
const QRMatrixTypematrixR () const
 
Index rank () const
 
Index rows () const
 
void setPivotThreshold (const RealScalar &threshold)
 
template<typename Rhs >
const Solve< SparseQR, Rhs > solve (const MatrixBase< Rhs > &B) const
 
template<typename Rhs >
const Solve< SparseQR, Rhs > solve (const SparseMatrixBase< Rhs > &B) const
 
 SparseQR ()
 
 SparseQR (const MatrixType &mat)
 

Protected Types

typedef SparseSolverBase< SparseQR< _MatrixType, _OrderingType > > Base
 

Protected Attributes

bool m_analysisIsok
 
IndexVector m_etree
 
bool m_factorizationIsok
 
IndexVector m_firstRowElt
 
ScalarVector m_hcoeffs
 
ComputationInfo m_info
 
bool m_isEtreeOk
 
bool m_isInitialized
 
bool m_isQSorted
 
std::string m_lastError
 
Index m_nonzeropivots
 
PermutationType m_outputPerm_c
 
PermutationType m_perm_c
 
PermutationType m_pivotperm
 
QRMatrixType m_pmat
 
QRMatrixType m_Q
 
QRMatrixType m_R
 
RealScalar m_threshold
 
bool m_useDefaultThreshold
 

Friends

template<typename , typename >
struct SparseQR_QProduct
 

Detailed Description

Sparse left-looking QR factorization with numerical column pivoting.

This class implements a left-looking QR decomposition of sparse matrices with numerical column pivoting. When a column has a norm less than a given tolerance it is implicitly permuted to the end. The QR factorization thus obtained is given by A*P = Q*R where R is upper triangular or trapezoidal.

P is the column permutation which is the product of the fill-reducing and the numerical permutations. Use colsPermutation() to get it.

Q is the orthogonal matrix represented as products of Householder reflectors. Use matrixQ() to get an expression and matrixQ().adjoint() to get the adjoint. You can then apply it to a vector.

R is the sparse triangular or trapezoidal matrix. The later occurs when A is rank-deficient. matrixR().topLeftCorner(rank(), rank()) always returns a triangular factor of full rank.

Template Parameters
_MatrixTypeThe type of the sparse matrix A, must be a column-major SparseMatrix<>
_OrderingTypeThe fill-reducing ordering method. See the OrderingMethods module for the list of built-in and external ordering methods.

\implsparsesolverconcept

The numerical pivoting strategy and default threshold are the same as in SuiteSparse QR, and detailed in the following paper: Tim Davis, "Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011. Even though it is qualified as "rank-revealing", this strategy might fail for some rank deficient problems. When this class is used to solve linear or least-square problems it is thus strongly recommended to check the accuracy of the computed solution. If it failed, it usually helps to increase the threshold with setPivotThreshold.

Warning
The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()).
For complex matrices matrixQ().transpose() will actually return the adjoint matrix.

Definition at line 16 of file SparseQR.h.

Member Typedef Documentation

◆ Base

typedef SparseSolverBase<SparseQR<_MatrixType,_OrderingType> > Eigen::SparseQR::Base
protected

Definition at line 87 of file SparseQR.h.

◆ IndexVector

Definition at line 97 of file SparseQR.h.

◆ MatrixType

typedef _MatrixType Eigen::SparseQR::MatrixType

Definition at line 91 of file SparseQR.h.

◆ OrderingType

typedef _OrderingType Eigen::SparseQR::OrderingType

Definition at line 92 of file SparseQR.h.

◆ PermutationType

Definition at line 99 of file SparseQR.h.

◆ QRMatrixType

Definition at line 96 of file SparseQR.h.

◆ RealScalar

typedef MatrixType::RealScalar Eigen::SparseQR::RealScalar

Definition at line 94 of file SparseQR.h.

◆ Scalar

typedef MatrixType::Scalar Eigen::SparseQR::Scalar

Definition at line 93 of file SparseQR.h.

◆ ScalarVector

Definition at line 98 of file SparseQR.h.

◆ StorageIndex

typedef MatrixType::StorageIndex Eigen::SparseQR::StorageIndex

Definition at line 95 of file SparseQR.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
ColsAtCompileTime 
MaxColsAtCompileTime 

Definition at line 101 of file SparseQR.h.

Constructor & Destructor Documentation

◆ SparseQR() [1/2]

Eigen::SparseQR::SparseQR ( )
inline

Definition at line 107 of file SparseQR.h.

◆ SparseQR() [2/2]

Eigen::SparseQR::SparseQR ( const MatrixType mat)
inlineexplicit

Construct a QR factorization of the matrix mat.

Warning
The matrix mat must be in compressed mode (see SparseMatrix::makeCompressed()).
See also
compute()

Definition at line 116 of file SparseQR.h.

Member Function Documentation

◆ _solve_impl() [1/2]

template<typename Rhs , typename Dest >
bool Eigen::SparseQR::_solve_impl ( const MatrixBase< Rhs > &  B,
MatrixBase< Dest > &  dest 
) const
inline

Definition at line 205 of file SparseQR.h.

◆ _solve_impl() [2/2]

template<typename Rhs , typename Dest >
void Eigen::SparseSolverBase< Derived >::_solve_impl ( typename Rhs  ,
typename Dest   
)
inline

Definition at line 111 of file SparseSolverBase.h.

◆ _sort_matrix_Q()

void Eigen::SparseQR::_sort_matrix_Q ( )
inline

Definition at line 276 of file SparseQR.h.

◆ analyzePattern()

void Eigen::SparseQR::analyzePattern ( const MatrixType mat)

Preprocessing step of a QR factorization.

Warning
The matrix mat must be in compressed mode (see SparseMatrix::makeCompressed()).

In this step, the fill-reducing permutation is computed and applied to the columns of A and the column elimination tree is computed as well. Only the sparsity pattern of mat is exploited.

Note
In this step it is assumed that there is no empty row in the matrix mat.

Definition at line 320 of file SparseQR.h.

◆ cols()

Index Eigen::SparseQR::cols ( ) const
inline
Returns
the number of columns of the represented matrix.

Definition at line 141 of file SparseQR.h.

◆ colsPermutation()

const PermutationType& Eigen::SparseQR::colsPermutation ( ) const
inline
Returns
a const reference to the column permutation P that was applied to A such that A*P = Q*R It is the combination of the fill-in reducing permutation and numerical column pivoting.

Definition at line 192 of file SparseQR.h.

◆ compute()

void Eigen::SparseQR::compute ( const MatrixType mat)
inline

Computes the QR factorization of the sparse matrix mat.

Warning
The matrix mat must be in compressed mode (see SparseMatrix::makeCompressed()).
See also
analyzePattern(), factorize()

Definition at line 127 of file SparseQR.h.

◆ factorize()

void Eigen::SparseQR::factorize ( const MatrixType mat)

Performs the numerical QR factorization of the input matrix.

The function SparseQR::analyzePattern(const MatrixType&) must have been called beforehand with a matrix having the same sparsity pattern than mat.

Parameters
matThe sparse column-major matrix

Definition at line 361 of file SparseQR.h.

◆ info()

ComputationInfo Eigen::SparseQR::info ( ) const
inline

Reports whether previous computation was successful.

Returns
Success if computation was successful, NumericalIssue if the QR factorization reports a numerical problem InvalidInput if the input matrix is invalid
See also
iparm()

Definition at line 268 of file SparseQR.h.

◆ lastErrorMessage()

std::string Eigen::SparseQR::lastErrorMessage ( ) const
inline
Returns
A string describing the type of error. This method is provided to ease debugging, not to handle errors.

Definition at line 201 of file SparseQR.h.

◆ matrixQ()

SparseQRMatrixQReturnType<SparseQR> Eigen::SparseQR::matrixQ ( ) const
inline
Returns
an expression of the matrix Q as products of sparse Householder reflectors. The common usage of this function is to apply it to a dense matrix or vector
VectorXd B1, B2;
// Initialize B1
B2 = matrixQ() * B1;

To get a plain SparseMatrix representation of Q:

SparseMatrix<double> Q;
Q = SparseQR<SparseMatrix<double> >(A).matrixQ();

Internally, this call simply performs a sparse product between the matrix Q and a sparse identity matrix. However, due to the fact that the sparse reflectors are stored unsorted, two transpositions are needed to sort them before performing the product.

Definition at line 186 of file SparseQR.h.

◆ matrixR()

const QRMatrixType& Eigen::SparseQR::matrixR ( ) const
inline
Returns
a const reference to the sparse upper triangular matrix R of the QR factorization.
Warning
The entries of the returned matrix are not sorted. This means that using it in algorithms expecting sorted entries will fail. This include random coefficient accesses (SpaseMatrix::coeff()), and coefficient-wise operations. Matrix products and triangular solves are fine though.

To sort the entries, you can assign it to a row-major matrix, and if a column-major matrix is required, you can copy it again:

SparseMatrix<double> R = qr.matrixR(); // column-major, not sorted!
SparseMatrix<double,RowMajor> Rr = qr.matrixR(); // row-major, sorted
SparseMatrix<double> Rc = Rr; // column-major, sorted

Definition at line 156 of file SparseQR.h.

◆ rank()

Index Eigen::SparseQR::rank ( ) const
inline
Returns
the number of non linearly dependent columns as determined by the pivoting threshold.
See also
setPivotThreshold()

Definition at line 162 of file SparseQR.h.

◆ rows()

Index Eigen::SparseQR::rows ( ) const
inline
Returns
the number of rows of the represented matrix.

Definition at line 137 of file SparseQR.h.

◆ setPivotThreshold()

void Eigen::SparseQR::setPivotThreshold ( const RealScalar threshold)
inline

Sets the threshold that is used to determine linearly dependent columns during the factorization.

In practice, if during the factorization the norm of the column that has to be eliminated is below this threshold, then the entire column is treated as zero, and it is moved at the end.

Definition at line 235 of file SparseQR.h.

◆ solve() [1/2]

template<typename Rhs >
const Solve<SparseQR, Rhs> Eigen::SparseQR::solve ( const MatrixBase< Rhs > &  B) const
inline
Returns
the solution X of $ A X = B $ using the current decomposition of A.
See also
compute()

Definition at line 246 of file SparseQR.h.

◆ solve() [2/2]

template<typename Rhs >
const Solve<SparseQR, Rhs> Eigen::SparseQR::solve ( const SparseMatrixBase< Rhs > &  B) const
inline

Definition at line 253 of file SparseQR.h.

Friends And Related Function Documentation

◆ SparseQR_QProduct

template<typename , typename >
friend struct SparseQR_QProduct
friend

Definition at line 306 of file SparseQR.h.

Member Data Documentation

◆ m_analysisIsok

bool Eigen::SparseQR::m_analysisIsok
protected

Definition at line 287 of file SparseQR.h.

◆ m_etree

IndexVector Eigen::SparseQR::m_etree
protected

Definition at line 301 of file SparseQR.h.

◆ m_factorizationIsok

bool Eigen::SparseQR::m_factorizationIsok
protected

Definition at line 288 of file SparseQR.h.

◆ m_firstRowElt

IndexVector Eigen::SparseQR::m_firstRowElt
protected

Definition at line 302 of file SparseQR.h.

◆ m_hcoeffs

ScalarVector Eigen::SparseQR::m_hcoeffs
protected

Definition at line 294 of file SparseQR.h.

◆ m_info

ComputationInfo Eigen::SparseQR::m_info
mutableprotected

Definition at line 289 of file SparseQR.h.

◆ m_isEtreeOk

bool Eigen::SparseQR::m_isEtreeOk
protected

Definition at line 304 of file SparseQR.h.

◆ m_isInitialized

bool Eigen::SparseSolverBase< Derived >::m_isInitialized
mutableprotected

Definition at line 119 of file SparseSolverBase.h.

◆ m_isQSorted

bool Eigen::SparseQR::m_isQSorted
protected

Definition at line 303 of file SparseQR.h.

◆ m_lastError

std::string Eigen::SparseQR::m_lastError
protected

Definition at line 290 of file SparseQR.h.

◆ m_nonzeropivots

Index Eigen::SparseQR::m_nonzeropivots
protected

Definition at line 300 of file SparseQR.h.

◆ m_outputPerm_c

PermutationType Eigen::SparseQR::m_outputPerm_c
protected

Definition at line 297 of file SparseQR.h.

◆ m_perm_c

PermutationType Eigen::SparseQR::m_perm_c
protected

Definition at line 295 of file SparseQR.h.

◆ m_pivotperm

PermutationType Eigen::SparseQR::m_pivotperm
protected

Definition at line 296 of file SparseQR.h.

◆ m_pmat

QRMatrixType Eigen::SparseQR::m_pmat
protected

Definition at line 291 of file SparseQR.h.

◆ m_Q

QRMatrixType Eigen::SparseQR::m_Q
protected

Definition at line 293 of file SparseQR.h.

◆ m_R

QRMatrixType Eigen::SparseQR::m_R
protected

Definition at line 292 of file SparseQR.h.

◆ m_threshold

RealScalar Eigen::SparseQR::m_threshold
protected

Definition at line 298 of file SparseQR.h.

◆ m_useDefaultThreshold

bool Eigen::SparseQR::m_useDefaultThreshold
protected

Definition at line 299 of file SparseQR.h.


The documentation for this class was generated from the following file:
Eigen::SparseQR::matrixQ
SparseQRMatrixQReturnType< SparseQR > matrixQ() const
Definition: SparseQR.h:186
Q
Quaternion Q
Definition: testQuaternion.cpp:27
A
Definition: test_numpy_dtypes.cpp:298
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
qr
HouseholderQR< MatrixXf > qr(A)
R
Rot2 R(Rot2::fromAngle(0.1))


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:10:52