57 :
public SolverBase<HouseholderQR<_MatrixType> >
67 MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,
68 MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
81 HouseholderQR() : m_qr(), m_hCoeffs(), m_temp(), m_isInitialized(false) {}
91 m_hCoeffs((
std::
min)(rows,cols)),
93 m_isInitialized(false) {}
107 template<
typename InputType>
109 : m_qr(matrix.
rows(), matrix.
cols()),
111 m_temp(matrix.
cols()),
112 m_isInitialized(false)
125 template<
typename InputType>
127 : m_qr(matrix.derived()),
129 m_temp(matrix.
cols()),
130 m_isInitialized(false)
135 #ifdef EIGEN_PARSED_BY_DOXYGEN 150 template<
typename Rhs>
165 eigen_assert(m_isInitialized &&
"HouseholderQR is not initialized.");
166 return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate());
174 eigen_assert(m_isInitialized &&
"HouseholderQR is not initialized.");
178 template<
typename InputType>
221 const HCoeffsType&
hCoeffs()
const {
return m_hCoeffs; }
223 #ifndef EIGEN_PARSED_BY_DOXYGEN 224 template<
typename RhsType,
typename DstType>
225 void _solve_impl(
const RhsType &rhs, DstType &dst)
const;
227 template<
bool Conjugate,
typename RhsType,
typename DstType>
228 void _solve_impl_transposed(
const RhsType &rhs, DstType &dst)
const;
238 void computeInPlace();
246 template<
typename MatrixType>
250 eigen_assert(m_isInitialized &&
"HouseholderQR is not initialized.");
251 eigen_assert(m_qr.rows() == m_qr.cols() &&
"You can't take the determinant of a non-square matrix!");
252 return abs(m_qr.diagonal().prod());
255 template<
typename MatrixType>
258 eigen_assert(m_isInitialized &&
"HouseholderQR is not initialized.");
259 eigen_assert(m_qr.rows() == m_qr.cols() &&
"You can't take the determinant of a non-square matrix!");
260 return m_qr.diagonal().cwiseAbs().array().log().sum();
266 template<
typename MatrixQR,
typename HCoeffs>
282 tempData = tempVector.data();
287 Index remainingRows = rows - k;
288 Index remainingCols = cols - k - 1;
291 mat.col(k).tail(remainingRows).makeHouseholderInPlace(hCoeffs.coeffRef(k), beta);
292 mat.coeffRef(k,k) = beta;
295 mat.bottomRightCorner(remainingRows, remainingCols)
296 .applyHouseholderOnTheLeft(mat.col(k).tail(remainingRows-1), hCoeffs.coeffRef(k), tempData+k+1);
301 template<
typename MatrixQR,
typename HCoeffs,
303 bool InnerStrideIsOne = (MatrixQR::InnerStrideAtCompileTime == 1 && HCoeffs::InnerStrideAtCompileTime == 1)>
307 static void run(MatrixQR&
mat, HCoeffs& hCoeffs,
Index maxBlockSize=32,
322 tempData = tempVector.data();
328 for (k = 0; k <
size; k += blockSize)
331 Index tcols = cols - k - bs;
332 Index brows = rows-k;
342 BlockType A11_21 = mat.block(k,k,brows,bs);
349 BlockType A21_22 = mat.block(k,k+bs,brows,tcols);
358 #ifndef EIGEN_PARSED_BY_DOXYGEN 359 template<
typename _MatrixType>
360 template<
typename RhsType,
typename DstType>
365 typename RhsType::PlainObject
c(rhs);
367 c.applyOnTheLeft(householderQ().setLength(rank).
adjoint() );
369 m_qr.topLeftCorner(rank, rank)
370 .template triangularView<Upper>()
371 .solveInPlace(c.topRows(rank));
373 dst.topRows(rank) = c.topRows(rank);
374 dst.bottomRows(
cols()-rank).setZero();
377 template<
typename _MatrixType>
378 template<
bool Conjugate,
typename RhsType,
typename DstType>
383 typename RhsType::PlainObject
c(rhs);
385 m_qr.topLeftCorner(rank, rank)
386 .template triangularView<Upper>()
387 .transpose().template conjugateIf<Conjugate>()
388 .solveInPlace(c.topRows(rank));
390 dst.topRows(rank) = c.topRows(rank);
391 dst.bottomRows(
rows()-rank).setZero();
393 dst.applyOnTheLeft(householderQ().setLength(rank).
template conjugateIf<!Conjugate>() );
403 template<
typename MatrixType>
406 check_template_parameters();
412 m_hCoeffs.resize(size);
418 m_isInitialized =
true;
425 template<
typename Derived>
HouseholderQR & compute(const EigenBase< InputType > &matrix)
#define EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)
SolverStorage StorageKind
static void run(MatrixQR &mat, HCoeffs &hCoeffs, Index maxBlockSize=32, typename MatrixQR::Scalar *tempData=0)
SolverBase< HouseholderQR > Base
void adjoint(const MatrixType &m)
HouseholderQR(Index rows, Index cols)
Default Constructor with memory preallocation.
void apply_block_householder_on_the_left(MatrixType &mat, const VectorsType &vectors, const CoeffsType &hCoeffs, bool forward)
internal::traits< HouseholderQR< TransposeTypeWithSameStorageOrder > >::Scalar Scalar
void _solve_impl(const RhsType &rhs, DstType &dst) const
const MatrixType & matrixQR() const
void householder_qr_inplace_unblocked(MatrixQR &mat, HCoeffs &hCoeffs, typename MatrixQR::Scalar *tempData=0)
Matrix< Scalar, RowsAtCompileTime, RowsAtCompileTime,(MatrixType::Flags &RowMajorBit) ? RowMajor :ColMajor, MaxRowsAtCompileTime, MaxRowsAtCompileTime > MatrixQType
static void check_template_parameters()
MatrixType::RealScalar absDeterminant() const
Namespace containing all symbols from the Eigen library.
Eigen::Index Index
The interface type of indices.
Sequence of Householder reflections acting on subspaces with decreasing size.
void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(Index rows, Index cols)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
HouseholderQR(EigenBase< InputType > &matrix)
Constructs a QR factorization from a given matrix.
MatrixType::RealScalar logAbsDeterminant() const
const HouseholderQR< PlainObject > householderQr() const
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
HouseholderSequenceType householderQ() const
NumTraits< Scalar >::Real RealScalar
internal::plain_row_type< MatrixType >::type RowVectorType
CleanedUpDerType< DerType >::type() min(const AutoDiffScalar< DerType > &x, const T &y)
EIGEN_CONSTEXPR Index size(const T &x)
Expression of a fixed-size or dynamic-size block.
Householder QR decomposition of a matrix.
internal::plain_diag_type< MatrixType >::type HCoeffsType
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Pseudo expression representing a solving operation.
Generic expression where a coefficient-wise unary operator is applied to an expression.
HouseholderQR()
Default Constructor.
EIGEN_DONT_INLINE void compute(Solver &solver, const MatrixType &A)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
HouseholderSequence< MatrixType, typename internal::remove_all< typename HCoeffsType::ConjugateReturnType >::type > HouseholderSequenceType
A base class for matrix decomposition and solvers.
EIGEN_DEVICE_FUNC Derived & derived()
Base class for all dense matrices, vectors, and expressions.
HouseholderQR(const EigenBase< InputType > &matrix)
Constructs a QR factorization from a given matrix.
const HCoeffsType & hCoeffs() const