11 #ifndef EIGEN_PARTIALLU_H 12 #define EIGEN_PARTIALLU_H 30 template<
typename T,
typename Derived>
36 template<
typename T,
typename Derived>
77 :
public SolverBase<PartialPivLU<_MatrixType> >
87 MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,
88 MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime
117 template<
typename InputType>
127 template<
typename InputType>
130 template<
typename InputType>
145 eigen_assert(m_isInitialized &&
"PartialPivLU is not initialized.");
153 eigen_assert(m_isInitialized &&
"PartialPivLU is not initialized.");
157 #ifdef EIGEN_PARSED_BY_DOXYGEN 175 template<
typename Rhs>
185 eigen_assert(m_isInitialized &&
"PartialPivLU is not initialized.");
198 eigen_assert(m_isInitialized &&
"PartialPivLU is not initialized.");
217 MatrixType reconstructedMatrix()
const;
222 #ifndef EIGEN_PARSED_BY_DOXYGEN 223 template<
typename RhsType,
typename DstType>
234 dst = permutationP() * rhs;
237 m_lu.template triangularView<UnitLower>().solveInPlace(dst);
240 m_lu.template triangularView<Upper>().solveInPlace(dst);
243 template<
bool Conjugate,
typename RhsType,
typename DstType>
256 dst = m_lu.template triangularView<Upper>().transpose()
257 .template conjugateIf<Conjugate>().solve(rhs);
259 m_lu.template triangularView<UnitLower>().transpose()
260 .template conjugateIf<Conjugate>().solveInPlace(dst);
262 dst = permutationP().transpose() * dst;
283 template<
typename MatrixType>
287 m_rowsTranspositions(),
290 m_isInitialized(false)
294 template<
typename MatrixType>
298 m_rowsTranspositions(size),
301 m_isInitialized(false)
305 template<
typename MatrixType>
306 template<
typename InputType>
308 : m_lu(matrix.
rows(),matrix.
cols()),
310 m_rowsTranspositions(matrix.
rows()),
313 m_isInitialized(false)
318 template<
typename MatrixType>
319 template<
typename InputType>
321 : m_lu(matrix.derived()),
323 m_rowsTranspositions(matrix.
rows()),
326 m_isInitialized(false)
334 template<
typename Scalar,
int StorageOrder,
typename PivIndex,
int SizeAtCompileTime=Dynamic>
337 static const int UnBlockedBound = 16;
338 static const bool UnBlockedAtCompileTime = SizeAtCompileTime!=
Dynamic && SizeAtCompileTime<=UnBlockedBound;
339 static const int ActualSizeAtCompileTime = UnBlockedAtCompileTime ? SizeAtCompileTime :
Dynamic;
341 static const int RRows = SizeAtCompileTime==2 ? 1 :
Dynamic;
342 static const int RCols = SizeAtCompileTime==2 ? 1 :
Dynamic;
361 typedef typename Scoring::result_type Score;
367 const Index endk = UnBlockedAtCompileTime ? size-1 :
size;
368 nb_transpositions = 0;
369 Index first_zero_pivot = -1;
370 for(
Index k = 0; k < endk; ++k)
372 int rrows = internal::convert_index<int>(rows-k-1);
373 int rcols = internal::convert_index<int>(cols-k-1);
375 Index row_of_biggest_in_col;
376 Score biggest_in_corner
377 = lu.col(k).tail(rows-k).unaryExpr(Scoring()).maxCoeff(&row_of_biggest_in_col);
378 row_of_biggest_in_col += k;
380 row_transpositions[k] = PivIndex(row_of_biggest_in_col);
382 if(biggest_in_corner != Score(0))
384 if(k != row_of_biggest_in_col)
386 lu.row(k).swap(lu.row(row_of_biggest_in_col));
390 lu.col(k).tail(fix<RRows>(rrows)) /= lu.coeff(k,k);
392 else if(first_zero_pivot==-1)
396 first_zero_pivot = k;
400 lu.bottomRightCorner(fix<RRows>(rrows),fix<RCols>(rcols)).noalias() -= lu.col(k).tail(fix<RRows>(rrows)) * lu.row(k).tail(fix<RCols>(rcols));
404 if(UnBlockedAtCompileTime)
407 row_transpositions[k] = PivIndex(k);
408 if (Scoring()(
lu(k, k)) == Score(0) && first_zero_pivot == -1)
409 first_zero_pivot = k;
412 return first_zero_pivot;
432 MatrixTypeRef
lu = MatrixType::Map(lu_data,rows, cols,
OuterStride<>(luStride));
437 if(UnBlockedAtCompileTime || size<=UnBlockedBound)
439 return unblocked_lu(lu, row_transpositions, nb_transpositions);
447 blockSize = (blockSize/16)*16;
451 nb_transpositions = 0;
452 Index first_zero_pivot = -1;
456 Index trows = rows - k - bs;
457 Index tsize = size - k - bs;
463 BlockType A_0 = lu.block(0,0,rows,k);
464 BlockType A_2 = lu.block(0,k+bs,rows,tsize);
465 BlockType
A11 = lu.block(k,k,bs,bs);
466 BlockType A12 = lu.block(k,k+bs,bs,tsize);
467 BlockType
A21 = lu.block(k+bs,k,trows,bs);
468 BlockType
A22 = lu.block(k+bs,k+bs,trows,tsize);
470 PivIndex nb_transpositions_in_panel;
473 Index ret = blocked_lu(trows+bs, bs, &lu.coeffRef(k,k), luStride,
474 row_transpositions+k, nb_transpositions_in_panel, 16);
475 if(ret>=0 && first_zero_pivot==-1)
476 first_zero_pivot = k+
ret;
478 nb_transpositions += nb_transpositions_in_panel;
482 Index piv = (row_transpositions[
i] += internal::convert_index<PivIndex>(k));
483 A_0.row(
i).swap(A_0.row(piv));
490 A_2.row(
i).swap(A_2.row(row_transpositions[
i]));
493 A11.template triangularView<UnitLower>().solveInPlace(A12);
495 A22.noalias() -= A21 * A12;
498 return first_zero_pivot;
504 template<
typename MatrixType,
typename TranspositionType>
508 if (lu.rows() == 0 || lu.cols() == 0) {
509 nb_transpositions = 0;
513 eigen_assert(row_transpositions.size() < 2 || (&row_transpositions.coeffRef(1)-&row_transpositions.coeffRef(0)) == 1);
517 typename TranspositionType::StorageIndex,
519 ::blocked_lu(lu.rows(), lu.cols(), &lu.coeffRef(0,0), lu.outerStride(), &row_transpositions.coeffRef(0),
nb_transpositions);
524 template<
typename MatrixType>
527 check_template_parameters();
533 m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff();
537 eigen_assert(m_lu.rows() == m_lu.cols() &&
"PartialPivLU is only for square (and moreover invertible) matrices");
540 m_rowsTranspositions.resize(size);
544 m_det_p = (nb_transpositions%2) ? -1 : 1;
546 m_p = m_rowsTranspositions;
548 m_isInitialized =
true;
551 template<
typename MatrixType>
554 eigen_assert(m_isInitialized &&
"PartialPivLU is not initialized.");
555 return Scalar(m_det_p) * m_lu.diagonal().prod();
561 template<
typename MatrixType>
564 eigen_assert(m_isInitialized &&
"LU is not initialized.");
566 MatrixType res = m_lu.template triangularView<UnitLower>().toDenseMatrix()
567 * m_lu.template triangularView<Upper>();
570 res = m_p.inverse() *
res;
580 template<
typename DstXprType,
typename MatrixType>
600 template<
typename Derived>
615 template<
typename Derived>
624 #endif // EIGEN_PARTIALLU_H EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
#define EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)
Base::PlainObject PlainObject
MatrixType::RealScalar RealScalar
MatrixType::PlainObject PlainObject
PartialPivLU & compute(const EigenBase< InputType > &matrix)
PartialPivLU()
Default Constructor.
const MatrixType & matrixLU() const
internal::traits< PartialPivLU< Matrix< Scalar, Dynamic, Dynamic > > >::Scalar Scalar
PartialPivLU< MatrixType > LuType
static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op< typename DstXprType::Scalar, typename LuType::Scalar > &)
void determinant(const MatrixType &m)
LU decomposition of a matrix with partial pivoting, and related features.
Namespace containing all symbols from the Eigen library.
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Transpositions< RowsAtCompileTime, MaxRowsAtCompileTime > TranspositionType
Ref< MatrixType > MatrixTypeRef
Decomposition::RealScalar rcond_estimate_helper(typename Decomposition::RealScalar matrix_norm, const Decomposition &dec)
Reciprocal condition number estimator.
Eigen::Index Index
The interface type of indices.
const unsigned int RowMajorBit
#define EIGEN_SIZE_MIN_PREFER_FIXED(a, b)
Matrix< Scalar, ActualSizeAtCompileTime, ActualSizeAtCompileTime, StorageOrder > MatrixType
EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
Ref< Matrix< Scalar, Dynamic, Dynamic, StorageOrder > > BlockType
Expression of the inverse of another expression.
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
EIGEN_DEVICE_FUNC void _solve_impl(const RhsType &rhs, DstType &dst) const
void partial_lu_inplace(MatrixType &lu, TranspositionType &row_transpositions, typename TranspositionType::StorageIndex &nb_transpositions)
SolverBase< PartialPivLU > Base
static void check_template_parameters()
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
#define EIGEN_STATIC_ASSERT_NON_INTEGER(TYPE)
const Inverse< PartialPivLU > inverse() const
cout<< "Here is the matrix m:"<< endl<< m<< endl;Eigen::FullPivLU< Matrix5x3 > lu(m)
NumTraits< Scalar >::Real RealScalar
A matrix or vector expression mapping an existing expression.
IndicesType::Scalar StorageIndex
EIGEN_CONSTEXPR Index size(const T &x)
#define EIGEN_DEVICE_FUNC
PermutationMatrix< RowsAtCompileTime, MaxRowsAtCompileTime > PermutationType
traits< _MatrixType > BaseTraits
SolverStorage StorageKind
const PermutationType & permutationP() const
TranspositionType m_rowsTranspositions
internal::nested_eval< T, 1 >::type eval(const T &xpr)
Inverse< LuType > SrcXprType
Pseudo expression representing a solving operation.
static Index blocked_lu(Index rows, Index cols, Scalar *lu_data, Index luStride, PivIndex *row_transpositions, PivIndex &nb_transpositions, Index maxBlockSize=256)
static Index unblocked_lu(MatrixTypeRef &lu, PivIndex *row_transpositions, PivIndex &nb_transpositions)
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.
Convenience specialization of Stride to specify only an outer stride See class Map for some examples...
A base class for matrix decomposition and solvers.
NumTraits< Scalar >::Real RealScalar
EIGEN_DEVICE_FUNC Derived & derived()
Base class for all dense matrices, vectors, and expressions.
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
EIGEN_DEVICE_FUNC const XprTypeNestedCleaned & nestedExpression() const
EIGEN_DEVICE_FUNC void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const