11 #ifndef EIGEN_PERMUTATIONMATRIX_H 12 #define EIGEN_PERMUTATIONMATRIX_H 45 template<
typename Derived>
52 #ifndef EIGEN_PARSED_BY_DOXYGEN 55 Flags = Traits::Flags,
56 RowsAtCompileTime = Traits::RowsAtCompileTime,
57 ColsAtCompileTime = Traits::ColsAtCompileTime,
58 MaxRowsAtCompileTime = Traits::MaxRowsAtCompileTime,
59 MaxColsAtCompileTime = Traits::MaxColsAtCompileTime
73 template<
typename OtherDerived>
81 template<
typename OtherDerived>
86 applyTranspositionOnTheRight(k,tr.
coeff(k));
99 #ifndef EIGEN_PARSED_BY_DOXYGEN 100 template<
typename DenseDerived>
119 const IndicesType&
indices()
const {
return derived().indices(); }
121 IndicesType&
indices() {
return derived().indices(); }
127 indices().resize(newSize);
133 StorageIndex
n = StorageIndex(
size());
134 for(StorageIndex
i = 0;
i <
n; ++
i)
135 indices().coeffRef(
i) =
i;
160 if(indices().coeff(k) ==
i) indices().coeffRef(k) = StorageIndex(j);
161 else if(indices().coeff(k) == j) indices().coeffRef(k) = StorageIndex(i);
177 std::swap(indices().coeffRef(i), indices().coeffRef(j));
197 #ifndef EIGEN_PARSED_BY_DOXYGEN 199 template<
typename OtherDerived>
204 template<
typename Lhs,
typename Rhs>
208 for (
Index i=0;
i<
rows();++
i) indices().coeffRef(
i) = lhs.indices().coeff(rhs.indices().coeff(
i));
218 template<
typename Other>
226 template<
typename Other>
234 template<
typename Other>
friend 252 while(r<n && mask[r]) r++;
258 for(
Index k=indices().coeff(k0); k!=k0; k=indices().coeff(k))
272 template<
int SizeAtCompileTime,
int MaxSizeAtCompileTime,
typename _StorageIndex>
274 :
traits<Matrix<_StorageIndex,SizeAtCompileTime,SizeAtCompileTime,0,MaxSizeAtCompileTime,MaxSizeAtCompileTime> >
296 template<
int SizeAtCompileTime,
int MaxSizeAtCompileTime,
typename _StorageIndex>
305 #ifndef EIGEN_PARSED_BY_DOXYGEN 321 template<
typename OtherDerived>
323 : m_indices(other.indices()) {}
332 template<
typename Other>
337 template<
typename Other>
339 : m_indices(tr.
size())
345 template<
typename Other>
353 template<
typename Other>
356 return Base::operator=(tr.
derived());
360 const IndicesType&
indices()
const {
return m_indices; }
367 #ifndef EIGEN_PARSED_BY_DOXYGEN 368 template<
typename Other>
370 : m_indices(other.derived().nestedExpression().
size())
373 StorageIndex
end = StorageIndex(m_indices.size());
374 for (StorageIndex
i=0;
i<
end;++
i)
375 m_indices.coeffRef(other.derived().nestedExpression().indices().
coeff(
i)) =
i;
377 template<
typename Lhs,
typename Rhs>
379 : m_indices(lhs.indices().
size())
381 Base::assignProduct(lhs,rhs);
392 template<
int SizeAtCompileTime,
int MaxSizeAtCompileTime,
typename _StorageIndex,
int _PacketAccess>
394 :
traits<Matrix<_StorageIndex,SizeAtCompileTime,SizeAtCompileTime,0,MaxSizeAtCompileTime,MaxSizeAtCompileTime> >
403 template<
int SizeAtCompileTime,
int MaxSizeAtCompileTime,
typename _StorageIndex,
int _PacketAccess>
405 :
public PermutationBase<Map<PermutationMatrix<SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex>,_PacketAccess> >
411 #ifndef EIGEN_PARSED_BY_DOXYGEN 416 inline Map(
const StorageIndex* indicesPtr)
417 : m_indices(indicesPtr)
421 : m_indices(indicesPtr,size)
425 template<
typename Other>
427 {
return Base::operator=(other.
derived()); }
430 template<
typename Other>
432 {
return Base::operator=(tr.
derived()); }
434 #ifndef EIGEN_PARSED_BY_DOXYGEN 440 m_indices = other.m_indices;
446 const IndicesType&
indices()
const {
return m_indices; }
457 template<
typename _IndicesType>
465 RowsAtCompileTime = _IndicesType::SizeAtCompileTime,
466 ColsAtCompileTime = _IndicesType::SizeAtCompileTime,
467 MaxRowsAtCompileTime = IndicesType::MaxSizeAtCompileTime,
468 MaxColsAtCompileTime = IndicesType::MaxSizeAtCompileTime,
485 template<
typename _IndicesType>
492 #ifndef EIGEN_PARSED_BY_DOXYGEN 512 template<
typename MatrixDerived,
typename PermutationDerived>
519 (matrix.derived(), permutation.
derived());
524 template<
typename PermutationDerived,
typename MatrixDerived>
531 (permutation.
derived(), matrix.derived());
535 template<
typename PermutationType>
537 :
public EigenBase<Inverse<PermutationType> >
547 #ifndef EIGEN_PARSED_BY_DOXYGEN 550 RowsAtCompileTime = PermTraits::RowsAtCompileTime,
551 ColsAtCompileTime = PermTraits::ColsAtCompileTime,
552 MaxRowsAtCompileTime = PermTraits::MaxRowsAtCompileTime,
553 MaxColsAtCompileTime = PermTraits::MaxColsAtCompileTime
557 #ifndef EIGEN_PARSED_BY_DOXYGEN 558 template<
typename DenseDerived>
562 for (
Index i=0;
i<derived().rows();++
i)
568 PlainPermutationType
eval()
const {
return derived(); }
574 template<
typename OtherDerived>
friend 583 template<
typename OtherDerived>
591 template<
typename Derived>
605 #endif // EIGEN_PERMUTATIONMATRIX_H friend const Product< OtherDerived, InverseType, AliasFreeProduct > operator*(const MatrixBase< OtherDerived > &matrix, const InverseType &trPerm)
Map & operator=(const PermutationBase< Other > &other)
void assignProduct(const Lhs &lhs, const Rhs &rhs)
EIGEN_DEVICE_FUNC Derived & setZero()
PermutationMatrix(const InverseImpl< Other, PermutationStorage > &other)
Expression of the product of two arbitrary matrices or vectors.
PermutationStorage StorageKind
PlainPermutationType operator*(const PermutationBase< Other > &other) const
PermutationMatrix(const MatrixBase< Other > &indices)
friend PlainPermutationType operator*(const InverseImpl< Other, PermutationStorage > &other, const PermutationBase &perm)
IndicesType::Nested m_indices
PlainPermutationType eval() const
Traits::IndicesType IndicesType
InverseReturnType inverse() const
EIGEN_DEVICE_FUNC Index size() const
A matrix or vector expression mapping an existing array of data.
PlainPermutationType operator*(const InverseImpl< Other, PermutationStorage > &other) const
PermutationType::PlainPermutationType PlainPermutationType
DenseMatrixType toDenseMatrix() const
EIGEN_DEVICE_FUNC Index cols() const
PermutationBase< Map > Base
DenseMatrixType toDenseMatrix() const
EIGEN_DEVICE_FUNC Index rows() const
Traits::StorageIndex StorageIndex
Derived & applyTranspositionOnTheRight(Index i, Index j)
void assignTranspose(const PermutationBase< OtherDerived > &other)
internal::traits< PermutationMatrix > Traits
Namespace containing all symbols from the Eigen library.
PermutationType::DenseMatrixType DenseMatrixType
Map(const StorageIndex *indicesPtr)
Holds information about the various numeric (i.e. scalar) types allowed by Eigen. ...
Map< const Matrix< _StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1 >, _PacketAccess > IndicesType
Derived & operator=(const PermutationBase< OtherDerived > &other)
Eigen::Index Index
The interface type of indices.
PermutationMatrix & operator=(const PermutationBase< Other > &other)
const PermutationMatrix & Nested
Base class for permutations.
EIGEN_DEVICE_FUNC const StorageIndex & coeff(Index i) const
PermutationBase< PermutationMatrix > Base
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
Matrix< _StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1 > IndicesType
Scalar coeff(Index row, Index col) const
Expression of the inverse of another expression.
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
Traits::IndicesType IndicesType
PermutationMatrix & operator=(const TranspositionsBase< Other > &tr)
const PermutationWrapper< const Derived > asPermutation() const
const IndicesType & indices() const
_StorageIndex StorageIndex
Derived & operator=(const TranspositionsBase< OtherDerived > &tr)
void evalTo(MatrixBase< DenseDerived > &other) const
PermutationStorage StorageKind
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Matrix< StorageIndex, RowsAtCompileTime, ColsAtCompileTime, 0, MaxRowsAtCompileTime, MaxColsAtCompileTime > DenseMatrixType
_IndicesType::Scalar StorageIndex
PermutationMatrix< IndicesType::SizeAtCompileTime, IndicesType::MaxSizeAtCompileTime, StorageIndex > PlainPermutationType
idx_t idx_t idx_t idx_t idx_t * perm
EIGEN_DEVICE_FUNC Index size() const
EigenBase< Derived > Base
CwiseUnaryOp< internal::scalar_inverse_op< Scalar >, const Derived > InverseReturnType
Class to view a vector of integers as a permutation matrix.
static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorUInt128< uint64_t, uint64_t > operator*(const TensorUInt128< HL, LL > &lhs, const TensorUInt128< HR, LR > &rhs)
const IndicesType & indices() const
internal::traits< Map > Traits
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
PermutationMatrix(const TranspositionsBase< Other > &tr)
EIGEN_CONSTEXPR Index size(const T &x)
#define EIGEN_DEVICE_FUNC
internal::traits< PermutationWrapper > Traits
PlainPermutationType PlainObject
PermutationWrapper(const IndicesType &indices)
Derived & applyTranspositionOnTheLeft(Index i, Index j)
internal::traits< Derived > Traits
PermutationMatrix(Index size)
Map & operator=(const TranspositionsBase< Other > &tr)
static EIGEN_DEPRECATED const end_t end
InverseReturnType transpose() const
internal::traits< PermutationType > PermTraits
_StorageIndex StorageIndex
PermutationMatrix(internal::PermPermProduct_t, const Lhs &lhs, const Rhs &rhs)
const Product< InverseType, OtherDerived, AliasFreeProduct > operator*(const MatrixBase< OtherDerived > &matrix) const
const internal::remove_all< typename IndicesType::Nested >::type & indices() const
Traits::StorageIndex StorageIndex
PermutationStorage StorageKind
IndicesType::Scalar StorageIndex
#define eigen_internal_assert(x)
Traits::IndicesType IndicesType
void setIdentity(Index newSize)
Inverse< PermutationType > InverseType
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.
void resize(Index newSize)
Index determinant() const
EIGEN_DEVICE_FUNC Derived & derived()
Base class for all dense matrices, vectors, and expressions.
Map(const StorageIndex *indicesPtr, Index size)
EIGEN_DEVICE_FUNC Derived & derived()
PermutationMatrix(const PermutationBase< OtherDerived > &other)
Inverse< Derived > InverseReturnType
void evalTo(MatrixBase< DenseDerived > &other) const
const IndicesType & indices() const
Traits::IndicesType IndicesType
Map & operator=(const Map &other)
PermutationBase< PermutationWrapper > Base