Go to the documentation of this file.
11 #ifndef EIGEN_PERMUTATIONMATRIX_H
12 #define EIGEN_PERMUTATIONMATRIX_H
45 template<
typename Derived>
52 #ifndef EIGEN_PARSED_BY_DOXYGEN
73 template<
typename OtherDerived>
81 template<
typename OtherDerived>
99 #ifndef EIGEN_PARSED_BY_DOXYGEN
100 template<
typename DenseDerived>
197 #ifndef EIGEN_PARSED_BY_DOXYGEN
199 template<
typename OtherDerived>
204 template<
typename Lhs,
typename Rhs>
218 template<
typename Other>
226 template<
typename Other>
234 template<
typename Other>
friend
252 while(r<
n && mask[r]) r++;
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>
332 template<
typename Other>
337 template<
typename Other>
345 template<
typename Other>
353 template<
typename Other>
367 #ifndef EIGEN_PARSED_BY_DOXYGEN
368 template<
typename Other>
375 m_indices.coeffRef(
other.derived().nestedExpression().indices().coeff(
i)) =
i;
377 template<
typename Lhs,
typename 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
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;
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>
524 template<
typename PermutationDerived,
typename MatrixDerived>
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)
574 template<
typename OtherDerived>
friend
583 template<
typename OtherDerived>
591 template<
typename Derived>
605 #endif // EIGEN_PERMUTATIONMATRIX_H
PermutationStorage StorageKind
Expression of the inverse of another expression.
idx_t idx_t idx_t idx_t idx_t * perm
Inverse< PermutationType > InverseType
#define EIGEN_DEVICE_FUNC
Namespace containing all symbols from the Eigen library.
EIGEN_DEVICE_FUNC Index cols() const
EIGEN_DEVICE_FUNC Derived & derived()
PermutationStorage StorageKind
Matrix< _StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1 > IndicesType
const friend Product< OtherDerived, InverseType, AliasFreeProduct > operator*(const MatrixBase< OtherDerived > &matrix, const InverseType &trPerm)
const Product< InverseType, OtherDerived, AliasFreeProduct > operator*(const MatrixBase< OtherDerived > &matrix) const
PermutationMatrix(internal::PermPermProduct_t, const Lhs &lhs, const Rhs &rhs)
Eigen::Index Index
The interface type of indices.
const IndicesType & indices() const
PermutationMatrix< IndicesType::SizeAtCompileTime, IndicesType::MaxSizeAtCompileTime, StorageIndex > PlainPermutationType
Matrix< StorageIndex, RowsAtCompileTime, ColsAtCompileTime, 0, MaxRowsAtCompileTime, MaxColsAtCompileTime > DenseMatrixType
Traits::StorageIndex StorageIndex
InverseReturnType transpose() const
EIGEN_DEVICE_FUNC Index rows() const
PermutationMatrix(const TranspositionsBase< Other > &tr)
Map & operator=(const PermutationBase< Other > &other)
IndicesType::Scalar StorageIndex
Traits::IndicesType IndicesType
void resize(Index newSize)
internal::traits< Map > Traits
Map & operator=(const TranspositionsBase< Other > &tr)
const IndicesType & indices() const
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
void setIdentity(Index newSize)
DenseMatrixType toDenseMatrix() const
Traits::StorageIndex StorageIndex
const EIGEN_DEVICE_FUNC Product< MatrixDerived, PermutationDerived, AliasFreeProduct > operator*(const MatrixBase< MatrixDerived > &matrix, const PermutationBase< PermutationDerived > &permutation)
#define eigen_internal_assert(x)
EigenBase< Derived > Base
const PermutationWrapper< const Derived > asPermutation() const
PermutationBase< PermutationWrapper > Base
Derived & operator=(const PermutationBase< OtherDerived > &other)
Derived & applyTranspositionOnTheLeft(Index i, Index j)
PermutationWrapper(const IndicesType &indices)
Class to view a vector of integers as a permutation matrix.
PermutationBase< Map > Base
PlainPermutationType eval() const
void evalTo(MatrixBase< DenseDerived > &other) const
const EIGEN_DEVICE_FUNC StorageIndex & coeff(Index i) const
PermutationType::PlainPermutationType PlainPermutationType
Traits::IndicesType IndicesType
EIGEN_DEVICE_FUNC Index size() const
EIGEN_DEVICE_FUNC Derived & derived()
const IndicesType & indices() const
void swap(GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &a, GeographicLib::NearestNeighbor< dist_t, pos_t, distfun_t > &b)
Map< const Matrix< _StorageIndex, SizeAtCompileTime, 1, 0, MaxSizeAtCompileTime, 1 >, _PacketAccess > IndicesType
PermutationMatrix & operator=(const TranspositionsBase< Other > &tr)
PlainPermutationType operator*(const InverseImpl< Other, PermutationStorage > &other) const
void assignTranspose(const PermutationBase< OtherDerived > &other)
void evalTo(MatrixBase< DenseDerived > &other) const
Expression of the product of two arbitrary matrices or vectors.
InverseReturnType inverse() const
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar & coeffRef(Index rowId, Index colId)
_StorageIndex StorageIndex
A matrix or vector expression mapping an existing array of data.
internal::traits< PermutationType > PermTraits
Map(const StorageIndex *indicesPtr, Index size)
DenseMatrixType toDenseMatrix() const
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
void assignProduct(const Lhs &lhs, const Rhs &rhs)
Index determinant() const
const internal::remove_all< typename IndicesType::Nested >::type & indices() const
PermutationStorage StorageKind
PermutationMatrix(Index size)
EIGEN_DEVICE_FUNC Index size() const
PermutationMatrix(const InverseImpl< Other, PermutationStorage > &other)
internal::traits< Derived > Traits
PermutationMatrix & operator=(const PermutationBase< Other > &other)
Base class for permutations.
PlainPermutationType operator*(const PermutationBase< Other > &other) const
PermutationBase< PermutationMatrix > Base
friend PlainPermutationType operator*(const InverseImpl< Other, PermutationStorage > &other, const PermutationBase &perm)
_StorageIndex StorageIndex
ProductLieGroup< Point2, Pose2 > Product
Map(const StorageIndex *indicesPtr)
IndicesType::Nested m_indices
The matrix class, also used for vectors and row-vectors.
Derived & applyTranspositionOnTheRight(Index i, Index j)
Base class for all dense matrices, vectors, and expressions.
static const EIGEN_DEPRECATED end_t end
EIGEN_DEVICE_FUNC PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > & derived()
Traits::IndicesType IndicesType
const typedef PermutationMatrix & Nested
internal::traits< PermutationMatrix > Traits
Holds information about the various numeric (i.e. scalar) types allowed by Eigen.
PlainPermutationType PlainObject
Map & operator=(const Map &other)
PermutationMatrix(const MatrixBase< Other > &indices)
Derived & operator=(const TranspositionsBase< OtherDerived > &tr)
internal::traits< PermutationWrapper > Traits
_IndicesType::Scalar StorageIndex
PermutationMatrix(const PermutationBase< OtherDerived > &other)
PermutationType::DenseMatrixType DenseMatrixType
Traits::IndicesType IndicesType
Inverse< Derived > InverseReturnType
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:34:21