Go to the documentation of this file.
11 #ifndef EIGEN_INCOMPLETE_LUT_H
12 #define EIGEN_INCOMPLETE_LUT_H
28 template <
typename VectorV,
typename VectorI>
41 if (ncut < first || ncut >
last )
return 0;
57 if (mid > ncut)
last = mid - 1;
58 else if (mid < ncut )
first = mid + 1;
59 }
while (mid != ncut );
98 template <
typename _Scalar,
typename _StorageIndex =
int>
124 template<
typename MatrixType>
148 template<
typename MatrixType>
151 template<
typename MatrixType>
159 template<
typename MatrixType>
170 template<
typename Rhs,
typename Dest>
174 x =
m_lu.template triangularView<UnitLower>().solve(
x);
175 x =
m_lu.template triangularView<Upper>().solve(
x);
205 template<
typename Scalar,
typename StorageIndex>
208 this->m_droptol = droptol;
215 template<
typename Scalar,
typename StorageIndex>
218 this->m_fillfactor = fillfactor;
221 template <
typename Scalar,
typename StorageIndex>
222 template<
typename _MatrixType>
236 m_Pinv = m_P.inverse();
237 m_analysisIsOk =
true;
238 m_factorizationIsOk =
false;
239 m_isInitialized =
true;
242 template <
typename Scalar,
typename StorageIndex>
243 template<
typename _MatrixType>
251 eigen_assert((amat.rows() == amat.cols()) &&
"The factorization should be done on a square matrix");
260 eigen_assert(m_analysisIsOk &&
"You must first call analyzePattern()");
262 mat = amat.twistedBy(m_Pinv);
270 Index fill_in = (amat.nonZeros()*m_fillfactor)/
n + 1;
271 if (fill_in >
n) fill_in =
n;
274 Index nnzL = fill_in/2;
276 m_lu.reserve(
n * (nnzL + nnzU + 1));
279 for (
Index ii = 0; ii <
n; ii++)
285 ju(ii) = convert_index<StorageIndex>(ii);
287 jr(ii) = convert_index<StorageIndex>(ii);
293 Index k = j_it.index();
297 ju(sizel) = convert_index<StorageIndex>(k);
298 u(sizel) = j_it.value();
299 jr(k) = convert_index<StorageIndex>(sizel);
304 u(ii) = j_it.value();
309 Index jpos = ii + sizeu;
310 ju(jpos) = convert_index<StorageIndex>(k);
311 u(jpos) = j_it.value();
312 jr(k) = convert_index<StorageIndex>(jpos);
325 rownorm =
sqrt(rownorm);
335 Index minrow = ju.segment(jj,sizel-jj).minCoeff(&k);
337 if (minrow != ju(jj))
342 jr(minrow) = convert_index<StorageIndex>(jj);
343 jr(
j) = convert_index<StorageIndex>(k);
351 while (ki_it && ki_it.index() < minrow) ++ki_it;
353 Scalar fact = u(jj) / ki_it.value();
356 if(
abs(fact) <= m_droptol)
364 for (; ki_it; ++ki_it)
384 ju(newpos) = convert_index<StorageIndex>(
j);
386 jr(
j) = convert_index<StorageIndex>(newpos);
393 ju(
len) = convert_index<StorageIndex>(minrow);
400 for(
Index k = 0; k <sizeu; k++) jr(ju(ii+k)) = -1;
414 m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);
419 u(ii) =
sqrt(m_droptol) * rownorm;
420 m_lu.insertBackByOuterInnerUnordered(ii, ii) = u(ii);
425 for(
Index k = 1; k < sizeu; k++)
427 if(
abs(u(ii+k)) > m_droptol * rownorm )
430 u(ii +
len) = u(ii + k);
431 ju(ii +
len) = ju(ii + k);
441 for(
Index k = ii + 1; k < ii +
len; k++)
442 m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);
445 m_lu.makeCompressed();
447 m_factorizationIsOk =
true;
453 #endif // EIGEN_INCOMPLETE_LUT_H
Incomplete LU factorization with dual-threshold strategy.
Namespace containing all symbols from the Eigen library.
MatrixXd mat1(size, size)
VectorBlock< Derived > SegmentReturnType
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
void _solve_impl(const Rhs &b, Dest &x) const
SparseMatrix< Scalar, RowMajor, StorageIndex > FactorType
_StorageIndex StorageIndex
void analyzePattern(const MatrixType &amat)
EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
NumTraits< Scalar >::Real RealScalar
Matrix< Scalar, Dynamic, 1 > Vector
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
#define eigen_internal_assert(x)
IncompleteLUT & compute(const MatrixType &amat)
void setFillfactor(int fillfactor)
void setDroptol(const RealScalar &droptol)
IncompleteLUT(const MatrixType &mat, const RealScalar &droptol=NumTraits< Scalar >::dummy_precision(), int fillfactor=10)
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
EIGEN_CONSTEXPR Index first(const T &x) EIGEN_NOEXCEPT
void factorize(const MatrixType &amat)
ComputationInfo info() const
Reports whether previous computation was successful.
EIGEN_DEVICE_FUNC IndexDest convert_index(const IndexSrc &idx)
static enum @1096 ordering
NumTraits< Scalar >::Real RealScalar
A base class for sparse solvers.
EIGEN_DEVICE_FUNC bool abs2(bool x)
Base::InnerIterator InnerIterator
SparseSolverBase< IncompleteLUT > Base
PermutationMatrix< Dynamic, Dynamic, StorageIndex > m_Pinv
void swap(scoped_array< T > &a, scoped_array< T > &b)
Index QuickSplit(VectorV &row, VectorI &ind, Index ncut)
bool operator()(const Index &row, const Index &col, const Scalar &) const
EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
Matrix< StorageIndex, Dynamic, 1 > VectorI
size_t len(handle h)
Get the length of a Python object.
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
const Product< Lhs, Rhs > prod(const Lhs &lhs, const Rhs &rhs)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
Jet< T, N > sqrt(const Jet< T, N > &f)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
PermutationMatrix< Dynamic, Dynamic, StorageIndex > m_P
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:27