Go to the documentation of this file.
10 #ifndef EIGEN_SPARSEMATRIX_H
11 #define EIGEN_SPARSEMATRIX_H
46 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
63 template<
typename _Scalar,
int _Options,
typename _StorageIndex,
int DiagIndex>
77 ColsAtCompileTime = 1,
79 MaxColsAtCompileTime = 1,
84 template<
typename _Scalar,
int _Options,
typename _StorageIndex,
int DiagIndex>
86 :
public traits<Diagonal<SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >
95 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
102 template<
typename,
typename,
typename,
typename,
typename>
108 using Base::operator+=;
109 using Base::operator-=;
118 using Base::IsRowMajor;
217 eigen_assert(
end>=start &&
"you probably called coeffRef on a non finalized matrix");
270 #ifdef EIGEN_PARSED_BY_DOXYGEN
283 template<
class SizesType>
284 inline void reserve(
const SizesType& reserveSizes);
286 template<
class SizesType>
287 inline void reserve(
const SizesType& reserveSizes,
const typename SizesType::value_type& enableif =
291 SizesType::value_type())
296 #endif // EIGEN_PARSED_BY_DOXYGEN
298 template<
class SizesType>
303 Index totalReserveSize = 0;
311 StorageIndex count = 0;
314 newOuterIndex[
j] = count;
316 totalReserveSize += reserveSizes[
j];
322 StorageIndex innerNNZ = previousOuterIndex -
m_outerIndex[
j];
339 StorageIndex* newOuterIndex =
static_cast<StorageIndex*
>(std::malloc((
m_outerSize+1)*
sizeof(StorageIndex)));
342 StorageIndex count = 0;
345 newOuterIndex[
j] = count;
347 StorageIndex toReserve = std::max<StorageIndex>(reserveSizes[
j], alreadyReserved);
368 std::free(newOuterIndex);
429 StorageIndex
size = internal::convert_index<StorageIndex>(
m_data.
size());
445 template<
typename InputIterators>
448 template<
typename InputIterators,
typename DupFunctor>
449 void setFromTriplets(
const InputIterators& begin,
const InputIterators&
end, DupFunctor dup_func);
453 template<
typename DupFunctor>
489 oldStart = nextOldStart;
522 template<
typename KeepFunc>
523 void prune(
const KeepFunc& keep = KeepFunc())
559 if (this->
rows() == rows && this->
cols() == cols)
return;
572 StorageIndex *newInnerNonZeros =
static_cast<StorageIndex*
>(std::realloc(
m_innerNonZeros, (
m_outerSize + outerChange) *
sizeof(StorageIndex)));
579 else if (innerChange < 0)
604 if (outerChange == 0)
607 StorageIndex *newOuterIndex =
static_cast<StorageIndex*
>(std::realloc(
m_outerIndex, (
m_outerSize + outerChange + 1) *
sizeof(StorageIndex)));
680 template<
typename OtherDerived>
685 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
689 *
this =
other.derived();
692 #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
700 template<
typename OtherDerived,
unsigned int UpLo>
705 Base::operator=(
other);
713 *
this =
other.derived();
717 template<
typename OtherDerived>
727 template<
typename OtherDerived>
732 *
this =
other.derived();
761 if (
other.isRValue())
765 else if(
this!=&
other)
767 #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
771 if(
other.isCompressed())
778 Base::operator=(
other);
784 #ifndef EIGEN_PARSED_BY_DOXYGEN
785 template<
typename OtherDerived>
787 {
return Base::operator=(
other.derived()); }
789 template<
typename Lhs,
typename Rhs>
791 #endif // EIGEN_PARSED_BY_DOXYGEN
793 template<
typename OtherDerived>
799 s <<
"Nonzero entries:\n";
802 for (Index i=0; i<m.nonZeros(); ++i)
803 s <<
"(" << m.m_data.value(i) <<
"," << m.m_data.index(i) <<
") ";
807 for (Index i=0; i<m.outerSize(); ++i)
809 Index p = m.m_outerIndex[i];
810 Index pe = m.m_outerIndex[i]+m.m_innerNonZeros[i];
813 s <<
"(" << m.m_data.value(k) <<
"," << m.m_data.index(k) <<
") ";
815 for (; k<m.m_outerIndex[i+1]; ++k) {
822 s <<
"Outer pointers:\n";
824 s <<
m.m_outerIndex[
i] <<
" ";
826 s <<
" $" << std::endl;
827 if(!
m.isCompressed())
829 s <<
"Inner non zeros:\n";
830 for (Index i=0; i<m.outerSize(); ++i) {
831 s << m.m_innerNonZeros[i] <<
" ";
833 s <<
" $" << std::endl;
837 s << static_cast<const SparseMatrixBase<SparseMatrix>&>(
m);
844 std::free(m_outerIndex);
845 std::free(m_innerNonZeros);
851 # ifdef EIGEN_SPARSEMATRIX_PLUGIN
852 # include EIGEN_SPARSEMATRIX_PLUGIN
857 template<
typename Other>
863 std::free(m_innerNonZeros);
900 eigen_assert(m_innerNonZeros[outer]<=(m_outerIndex[outer+1] - m_outerIndex[outer]));
902 Index p = m_outerIndex[outer] + m_innerNonZeros[outer]++;
926 template<
typename DiagXpr,
typename Func>
934 if((this->
rows()!=n) || (this->
cols()!=n))
938 if(m_data.
size()==0 || overwrite)
942 this->resizeNonZeros(
n);
951 bool isComp = isCompressed();
953 std::vector<IndexPosPair> newEntries;
963 assignFunc.assignCoeff(m_data.
value(
p), diaEval.coeff(
i));
965 else if((!isComp) && m_innerNonZeros[
i] < (m_outerIndex[
i+1]-m_outerIndex[
i]))
969 m_innerNonZeros[
i]++;
971 m_data.
index(
p) = StorageIndex(
i);
972 assignFunc.assignCoeff(m_data.
value(
p), diaEval.coeff(
i));
977 newEntries.push_back(IndexPosPair(
i,
p));
987 for(
Index k=0; k<n_entries;++k)
989 Index i = newEntries[k].i;
990 Index p = newEntries[k].p;
994 m_outerIndex[
j+1] += k;
996 m_innerNonZeros[
i]++;
1000 newData.
index(
p+k) = StorageIndex(
i);
1001 assignFunc.assignCoeff(newData.
value(
p+k), diaEval.coeff(
i));
1006 for(
Index j=prev_i+1;
j<=m_outerSize;++
j)
1007 m_outerIndex[
j] += n_entries;
1009 m_data.
swap(newData);
1034 template<
typename InputIterator,
typename SparseMatrixType,
typename DupFunctor>
1037 enum { IsRowMajor = SparseMatrixType::IsRowMajor };
1039 typedef typename SparseMatrixType::StorageIndex StorageIndex;
1045 typename SparseMatrixType::IndexVector wi(trMat.
outerSize());
1047 for(InputIterator it(begin); it!=
end; ++it)
1049 eigen_assert(it->row()>=0 && it->row()<
mat.rows() && it->col()>=0 && it->col()<
mat.cols());
1050 wi(IsRowMajor ? it->col() : it->row())++;
1055 for(InputIterator it(begin); it!=
end; ++it)
1106 template<
typename Scalar,
int _Options,
typename _StorageIndex>
1107 template<
typename InputIterators>
1122 template<
typename Scalar,
int _Options,
typename _StorageIndex>
1123 template<
typename InputIterators,
typename DupFunctor>
1126 internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,_Options,_StorageIndex>, DupFunctor>(begin,
end, *
this, dup_func);
1130 template<
typename Scalar,
int _Options,
typename _StorageIndex>
1131 template<
typename DupFunctor>
1138 StorageIndex count = 0;
1142 StorageIndex start = count;
1143 Index oldEnd = m_outerIndex[
j]+m_innerNonZeros[
j];
1144 for(
Index k=m_outerIndex[
j]; k<oldEnd; ++k)
1160 m_outerIndex[
j] = start;
1162 m_outerIndex[m_outerSize] = count;
1165 std::free(m_innerNonZeros);
1166 m_innerNonZeros = 0;
1167 m_data.
resize(m_outerIndex[m_outerSize]);
1170 template<
typename Scalar,
int _Options,
typename _StorageIndex>
1171 template<
typename OtherDerived>
1175 YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)
1177 #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
1182 if (needToTranspose)
1184 #ifdef EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN
1194 OtherCopy otherCopy(
other.derived());
1195 OtherCopyEval otherCopyEval(otherCopy);
1202 for (
Index j=0;
j<otherCopy.outerSize(); ++
j)
1203 for (
typename OtherCopyEval::InnerIterator it(otherCopyEval,
j); it; ++it)
1207 StorageIndex count = 0;
1213 positions[
j] = count;
1220 for (StorageIndex
j=0;
j<otherCopy.outerSize(); ++
j)
1222 for (
typename OtherCopyEval::InnerIterator it(otherCopyEval,
j); it; ++it)
1224 Index pos = positions[it.index()]++;
1234 if(
other.isRValue())
1236 initAssignment(
other.derived());
1239 return Base::operator=(
other.derived());
1243 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
1257 m_data.
reserve(2*m_innerSize);
1260 m_innerNonZeros =
static_cast<StorageIndex*
>(std::malloc(m_outerSize *
sizeof(StorageIndex)));
1263 memset(m_innerNonZeros, 0, (m_outerSize)*
sizeof(StorageIndex));
1268 for(
Index j=1;
j<=m_outerSize; ++
j)
1269 m_outerIndex[
j] =
end;
1274 m_innerNonZeros =
static_cast<StorageIndex*
>(std::malloc(m_outerSize *
sizeof(StorageIndex)));
1277 m_innerNonZeros[
j] = m_outerIndex[
j+1]-m_outerIndex[
j];
1286 if(m_outerIndex[outer]==data_end)
1294 while(
j>=0 && m_innerNonZeros[
j]==0)
1295 m_outerIndex[
j--] =
p;
1298 ++m_innerNonZeros[outer];
1309 for(
Index k=outer+1; k<=m_outerSize; ++k)
1310 if(m_outerIndex[k]==data_end)
1311 m_outerIndex[k] = new_end;
1318 if(m_outerIndex[outer+1]==data_end && m_outerIndex[outer]+m_innerNonZeros[outer]==m_data.
size())
1323 ++m_innerNonZeros[outer];
1334 for(
Index k=outer+1; k<=m_outerSize; ++k)
1335 if(m_outerIndex[k]==data_end)
1336 m_outerIndex[k] = new_end;
1340 Index startId = m_outerIndex[outer];
1341 Index p = m_outerIndex[outer]+m_innerNonZeros[outer]-1;
1342 while ( (
p > startId) && (m_data.
index(
p-1) > inner) )
1360 return insertUncompressed(
row,
col);
1363 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
1371 Index room = m_outerIndex[outer+1] - m_outerIndex[outer];
1372 StorageIndex innerNNZ = m_innerNonZeros[outer];
1376 reserve(SingletonVector(outer,std::max<StorageIndex>(2,innerNNZ)));
1379 Index startId = m_outerIndex[outer];
1380 Index p = startId + m_innerNonZeros[outer];
1381 while ( (
p > startId) && (m_data.
index(
p-1) > inner) )
1387 eigen_assert((
p<=startId || m_data.
index(
p-1)!=inner) &&
"you cannot insert an element that already exists, you must call coeffRef to this end");
1389 m_innerNonZeros[outer]++;
1395 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
1403 Index previousOuter = outer;
1404 if (m_outerIndex[outer+1]==0)
1407 while (previousOuter>=0 && m_outerIndex[previousOuter]==0)
1412 m_outerIndex[outer+1] = m_outerIndex[outer];
1418 bool isLastVec = (!(previousOuter==-1 && m_data.
size()!=0))
1424 ++m_outerIndex[outer+1];
1426 double reallocRatio = 1;
1430 if (m_data.
size()==0)
1439 double nnzEstimate = double(m_outerIndex[outer])*double(m_outerSize)/double(outer+1);
1440 reallocRatio = (nnzEstimate-double(m_data.
size()))/
double(m_data.
size());
1451 if (previousOuter==-1)
1455 for (
Index k=0; k<=(outer+1); ++k)
1456 m_outerIndex[k] = 0;
1458 while(m_outerIndex[k]==0)
1459 m_outerIndex[k++] = 1;
1460 while (k<=m_outerSize && m_outerIndex[k]!=0)
1461 m_outerIndex[k++]++;
1464 k = m_outerIndex[k]-1;
1477 while (
j<=m_outerSize && m_outerIndex[
j]!=0)
1478 m_outerIndex[
j++]++;
1481 Index k = m_outerIndex[
j]-1;
1491 while ( (
p > startId) && (m_data.
index(
p-1) > inner) )
1504 template<
typename _Scalar,
int _Options,
typename _StorageIndex>
1506 :
evaluator<SparseCompressedBase<SparseMatrix<_Scalar,_Options,_StorageIndex> > >
1518 #endif // EIGEN_SPARSEMATRIX_H
void resize(Index rows, Index cols)
void initAssignment(const Other &other)
Diagonal< const SparseMatrix > ConstDiagonalReturnType
void assignDiagonal(const DiagXpr diagXpr, const Func &assignFunc)
Namespace containing all symbols from the Eigen library.
A versatible sparse matrix representation.
_StorageIndex StorageIndex
StorageIndex * outerIndexPtr()
StorageIndex * m_outerIndex
SparseMatrix & operator=(const SparseMatrix &other)
void prune(const Scalar &reference, const RealScalar &epsilon=NumTraits< RealScalar >::dummy_precision())
void append(const Scalar &v, Index i)
StorageIndex & index(Index i)
friend std::ostream & operator<<(std::ostream &s, const SparseMatrix &m)
remove_reference< MatrixTypeNested >::type _MatrixTypeNested
#define EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN
void swap(CompressedStorage &other)
Base::ScalarVector ScalarVector
void moveChunk(Index from, Index to, Index chunkSize)
const unsigned int RowMajorBit
evaluator< SparseCompressedBase< SparseMatrix< _Scalar, _Options, _StorageIndex > > > Base
bool isCompressed() const
const unsigned int CompressedAccessBit
Index allocatedSize() const
General-purpose arrays with easy API for coefficient-wise operations.
IndexPosPair(Index a_i, Index a_p)
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void call_assignment_no_alias(Dst &dst, const Src &src, const Func &func)
EIGEN_DEVICE_FUNC bool isMuchSmallerThan(const Scalar &x, const OtherScalar &y, const typename NumTraits< Scalar >::Real &precision=NumTraits< Scalar >::dummy_precision())
void reserveInnerVectors(const SizesType &reserveSizes)
void startVec(Index outer)
#define eigen_internal_assert(x)
SparseMatrix(const SparseSelfAdjointView< OtherDerived, UpLo > &other)
Base::IndexVector IndexVector
SparseCompressedBase< SparseMatrix > Base
#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN
Common base class for sparse [compressed]-{row|column}-storage format.
const ConstDiagonalReturnType diagonal() const
#define EIGEN_SPARSE_PUBLIC_INTERFACE(Derived)
const Scalar * valuePtr() const
Index searchLowerIndex(Index key) const
MappedSparseMatrix< Scalar, Flags > Map
#define EIGEN_UNUSED_VARIABLE(var)
const StorageIndex * innerIndexPtr() const
EIGEN_DEVICE_FUNC void throw_std_bad_alloc()
const unsigned int LvalueBit
SparseMatrix< _Scalar, _Options, _StorageIndex > SparseMatrixType
evaluator(const SparseMatrixType &mat)
internal::enable_if< internal::valid_indexed_view_overload< RowIndices, ColIndices >::value &&internal::traits< typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::ReturnAsIndexedView, typename EIGEN_INDEXED_VIEW_METHOD_TYPE< RowIndices, ColIndices >::type >::type operator()(const RowIndices &rowIndices, const ColIndices &colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST
Derived & operator=(const Derived &other)
Expression of a diagonal/subdiagonal/superdiagonal in a matrix.
SparseMatrix< _Scalar, _Options, _StorageIndex > MatrixType
SingletonVector(Index i, Index v)
#define EIGEN_STRONG_INLINE
const StorageIndex * indexPtr() const
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
Expression of the product of two arbitrary matrices or vectors.
SparseMatrix(const SparseMatrix &other)
void swap(SparseMatrix &other)
const StorageIndex * innerNonZeroPtr() const
EIGEN_STRONG_INLINE Scalar & insertBackUncompressed(Index row, Index col)
Scalar coeff(Index row, Index col) const
A matrix or vector expression mapping an existing array of data.
_StorageIndex StorageIndex
Scalar & insertBackByOuterInner(Index outer, Index inner)
EIGEN_DEVICE_FUNC IndexDest convert_index(const IndexSrc &idx)
void reserve(Index reserveSize)
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
void resize(Index size, double reserveSizeFactor=0)
const Scalar * valuePtr() const
Scalar & insertBackByOuterInnerUnordered(Index outer, Index inner)
const StorageIndex * outerIndexPtr() const
static void check_template_parameters()
NumTraits< Scalar >::Real RealScalar
Scalar atInRange(Index start, Index end, Index key, const Scalar &defaultValue=Scalar(0)) const
StorageIndex * innerNonZeroPtr()
SparseMatrix(const SparseMatrixBase< OtherDerived > &other)
const Storage & data() const
Diagonal< SparseMatrix > DiagonalReturnType
SparseMatrix(Index rows, Index cols)
Base::InnerIterator InnerIterator
#define EIGEN_STATIC_ASSERT(CONDITION, MSG)
default_prunning_func(const Scalar &ref, const RealScalar &eps)
Scalar & insert(Index row, Index col)
#define EIGEN_DBG_SPARSE(X)
void collapseDuplicates(DupFunctor dup_func=DupFunctor())
void setFromTriplets(const InputIterators &begin, const InputIterators &end)
StorageIndex operator[](Index i) const
SparseMatrix & operator=(const EigenBase< OtherDerived > &other)
Reference counting helper.
ref_selector< MatrixType >::type MatrixTypeNested
SparseMatrix(const ReturnByValue< OtherDerived > &other)
Copy constructor with in-place evaluation.
Array< int, Dynamic, 1 > v
Base class of any sparse matrices or sparse expressions.
Scalar & insertBack(Index row, Index col)
void reserve(const SizesType &reserveSizes, const typename SizesType::value_type &enableif=typename SizesType::value_type())
void conservativeResize(Index rows, Index cols)
Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.
Scalar & insertByOuterInner(Index j, Index i)
StorageIndex * m_innerNonZeros
EIGEN_DEVICE_FUNC void smart_copy(const T *start, const T *end, T *target)
void prune(const KeepFunc &keep=KeepFunc())
const int InnerRandomAccessPattern
static const EIGEN_DEPRECATED end_t end
Scalar & coeffRef(Index row, Index col)
DiagonalReturnType diagonal()
int EIGEN_BLAS_FUNC() swap(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)
const unsigned int NestByRefBit
StorageIndex * innerIndexPtr()
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
SparseMatrix(const DiagonalBase< OtherDerived > &other)
Copy constructor with in-place evaluation.
void resizeNonZeros(Index size)
Base::ReverseInnerIterator ReverseInnerIterator
internal::CompressedStorage< Scalar, StorageIndex > Storage
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
void set_from_triplets(const InputIterator &begin, const InputIterator &end, SparseMatrixType &mat, DupFunctor dup_func)
#define EIGEN_DONT_INLINE
SparseMatrix< Scalar,(Flags &~RowMajorBit)|(IsRowMajor?RowMajorBit:0)> TransposedSparseMatrix
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:36:00