Public Member Functions | Static Public Member Functions | Private Member Functions | Friends | List of all members
gtsam::Symmetric< N > Class Template Reference

Symmetric group. More...

Inheritance diagram for gtsam::Symmetric< N >:
Inheritance graph
[legend]

Public Member Functions

bool equals (const Symmetric< N > &other, double tol=0) const
 
Symmetric inverse () const
 
Symmetric operator* (const Symmetric &other) const
 
bool operator== (const Symmetric &other) const
 
void print (const std::string &s="") const
 
 Symmetric ()
 

Static Public Member Functions

static Symmetric Identity ()
 
static Symmetric Transposition (int i, int j)
 

Private Member Functions

 Symmetric (const Eigen::PermutationMatrix< N > &P)
 
- Private Member Functions inherited from Eigen::PermutationMatrix< N >
const IndicesTypeindices () const
 
IndicesTypeindices ()
 
PermutationMatrixoperator= (const PermutationBase< Other > &other)
 
PermutationMatrixoperator= (const TranspositionsBase< Other > &tr)
 
 PermutationMatrix ()
 
 PermutationMatrix (Index size)
 
 PermutationMatrix (const PermutationBase< OtherDerived > &other)
 
 PermutationMatrix (const MatrixBase< Other > &indices)
 
 PermutationMatrix (const TranspositionsBase< Other > &tr)
 
 PermutationMatrix (const InverseImpl< Other, PermutationStorage > &other)
 
 PermutationMatrix (internal::PermPermProduct_t, const Lhs &lhs, const Rhs &rhs)
 
- Private Member Functions inherited from Eigen::PermutationBase< PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > >
PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > & applyTranspositionOnTheLeft (Index i, Index j)
 
PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > & applyTranspositionOnTheRight (Index i, Index j)
 
EIGEN_DEVICE_FUNC Index cols () const
 
Index determinant () const
 
void evalTo (MatrixBase< DenseDerived > &other) const
 
const IndicesTypeindices () const
 
IndicesTypeindices ()
 
InverseReturnType inverse () const
 
PlainPermutationType operator* (const PermutationBase< Other > &other) const
 
PlainPermutationType operator* (const InverseImpl< Other, PermutationStorage > &other) const
 
PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > & operator= (const PermutationBase< OtherDerived > &other)
 
PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > & operator= (const TranspositionsBase< OtherDerived > &tr)
 
void resize (Index newSize)
 
EIGEN_DEVICE_FUNC Index rows () const
 
void setIdentity ()
 
void setIdentity (Index newSize)
 
EIGEN_DEVICE_FUNC Index size () const
 
DenseMatrixType toDenseMatrix () const
 
InverseReturnType transpose () const
 
void assignProduct (const Lhs &lhs, const Rhs &rhs)
 
void assignTranspose (const PermutationBase< OtherDerived > &other)
 
- Private Member Functions inherited from Eigen::EigenBase< Derived >
template<typename Dest >
EIGEN_DEVICE_FUNC void addTo (Dest &dst) const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void applyThisOnTheLeft (Dest &dst) const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void applyThisOnTheRight (Dest &dst) const
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC Derived & const_cast_derived () const
 
EIGEN_DEVICE_FUNC const Derived & const_derived () const
 
EIGEN_DEVICE_FUNC Derived & derived ()
 
EIGEN_DEVICE_FUNC const Derived & derived () const
 
template<typename Dest >
EIGEN_DEVICE_FUNC void evalTo (Dest &dst) const
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows () const EIGEN_NOEXCEPT
 
EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index size () const EIGEN_NOEXCEPT
 
template<typename Dest >
EIGEN_DEVICE_FUNC void subTo (Dest &dst) const
 

Friends

std::ostream & operator<< (std::ostream &os, const Symmetric &m)
 

Additional Inherited Members

- Private Types inherited from Eigen::PermutationMatrix< N >
typedef Traits::IndicesType IndicesType
 
typedef const PermutationMatrixNested
 
typedef Traits::StorageIndex StorageIndex
 
- Private Types inherited from Eigen::PermutationBase< PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > >
enum  
 
typedef Matrix< StorageIndex, RowsAtCompileTime, ColsAtCompileTime, 0, MaxRowsAtCompileTime, MaxColsAtCompileTimeDenseMatrixType
 
typedef Traits::IndicesType IndicesType
 
typedef Inverse< PermutationMatrix< SizeAtCompileTime, MaxSizeAtCompileTime, _StorageIndex > > InverseReturnType
 
typedef PlainPermutationType PlainObject
 
typedef PermutationMatrix< IndicesType::SizeAtCompileTime, IndicesType::MaxSizeAtCompileTime, StorageIndexPlainPermutationType
 
typedef void Scalar
 
typedef Traits::StorageIndex StorageIndex
 
- Private Types inherited from Eigen::EigenBase< Derived >
typedef Eigen::Index Index
 The interface type of indices. More...
 
typedef internal::traits< Derived >::StorageKind StorageKind
 
- Private Attributes inherited from Eigen::PermutationMatrix< N >
IndicesType m_indices
 

Detailed Description

template<int N>
class gtsam::Symmetric< N >

Symmetric group.

Definition at line 27 of file testGroup.cpp.

Constructor & Destructor Documentation

◆ Symmetric() [1/2]

template<int N>
gtsam::Symmetric< N >::Symmetric ( const Eigen::PermutationMatrix< N > &  P)
inlineprivate

Definition at line 28 of file testGroup.cpp.

◆ Symmetric() [2/2]

template<int N>
gtsam::Symmetric< N >::Symmetric ( )
inline

Definition at line 33 of file testGroup.cpp.

Member Function Documentation

◆ equals()

template<int N>
bool gtsam::Symmetric< N >::equals ( const Symmetric< N > &  other,
double  tol = 0 
) const
inline

Definition at line 60 of file testGroup.cpp.

◆ Identity()

template<int N>
static Symmetric gtsam::Symmetric< N >::Identity ( )
inlinestatic

Definition at line 32 of file testGroup.cpp.

◆ inverse()

template<int N>
Symmetric gtsam::Symmetric< N >::inverse ( ) const
inline

Definition at line 49 of file testGroup.cpp.

◆ operator*()

template<int N>
Symmetric gtsam::Symmetric< N >::operator* ( const Symmetric< N > &  other) const
inline

Definition at line 40 of file testGroup.cpp.

◆ operator==()

template<int N>
bool gtsam::Symmetric< N >::operator== ( const Symmetric< N > &  other) const
inline

Definition at line 43 of file testGroup.cpp.

◆ print()

template<int N>
void gtsam::Symmetric< N >::print ( const std::string &  s = "") const
inline

Definition at line 57 of file testGroup.cpp.

◆ Transposition()

template<int N>
static Symmetric gtsam::Symmetric< N >::Transposition ( int  i,
int  j 
)
inlinestatic

Definition at line 36 of file testGroup.cpp.

Friends And Related Function Documentation

◆ operator<<

template<int N>
std::ostream& operator<< ( std::ostream &  os,
const Symmetric< N > &  m 
)
friend

Definition at line 52 of file testGroup.cpp.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:47:12