Public Types | Public Member Functions | Protected Types | Protected Attributes | List of all members
Displacement< _Scalar > Class Template Reference

Class describing a rigid Displacement or a 3D Frame position. More...

#include <Displacement.h>

Inheritance diagram for Displacement< _Scalar >:
Inheritance graph
[legend]

Public Types

typedef internal::traits< Displacement >::Coefficients Coefficients
 
typedef _Scalar Scalar
 
- Public Types inherited from DisplacementBase< Displacement< _Scalar > >
typedef Base::BaseType BaseType
 
typedef Base::PlainObject PlainObject
 
typedef LieGroup< Quaternion< Scalar > > Rotation3D
 
typedef internal::traits< Displacement< _Scalar > >::Scalar Scalar
 
typedef Matrix< Scalar, 3, 1 > Vector3
 
- Public Types inherited from LieGroupBase< Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 >, Displacement< _Scalar > >
typedef Displacement< _Scalar >::AdjointMatrix AdjointMatrix
 
typedef Displacement< _Scalar >::Algebra Algebra
 
typedef Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 > BaseType
 
typedef Displacement< _Scalar >::CoAlgebra CoAlgebra
 
typedef Displacement< _Scalar >::Coefficients Coefficients
 
typedef internal::traits< Displacement< _Scalar > >::PlainObject PlainObject
 
typedef internal::traits< Displacement< _Scalar > >::Scalar Scalar
 

Public Member Functions

 Displacement ()
 
 Displacement (const Displacement &other)
 
template<typename Derived >
 Displacement (const DisplacementBase< Derived > &other)
 
 Displacement (const Array< Scalar, 7, 1 > &g)
 
template<typename Derived >
 Displacement (const MatrixBase< Derived > &other)
 
EIGEN_STRONG_INLINE Displacement (Scalar x, Scalar y, Scalar z, Scalar qw=(Scalar) 1.0, Scalar qx=(Scalar) 0.0, Scalar qy=(Scalar) 0.0, Scalar qz=(Scalar) 0.0)
 
EIGEN_STRONG_INLINE Displacement (const typename Base::Vector3 &v, const typename Base::Rotation3D &r)
 
Coefficientsget ()
 
const Coefficientsget () const
 
- Public Member Functions inherited from DisplacementBase< Displacement< _Scalar > >
internal::cast_return_type< Displacement< _Scalar >, Displacement< NewScalarType > >::type cast () const
 
Map< Rotation3DgetRotation ()
 
const Map< const Rotation3DgetRotation () const
 
Map< Vector3getTranslation ()
 
const Map< const Vector3getTranslation () const
 
EIGEN_STRONG_INLINE DisplacementBaseoperator= (const typename Base::PlainObject &g)
 
Scalar qw () const
 
Scalarqw ()
 
Scalar qx () const
 
Scalarqx ()
 
Scalar qy () const
 
Scalarqy ()
 
Scalar qz () const
 
Scalarqz ()
 
void setRandom ()
 
Matrix< Scalar, 4, 4 > toHomogeneousMatrix () const
 
Scalar x () const
 
Scalarx ()
 
Scalar y () const
 
Scalary ()
 
Scalar z () const
 
Scalarz ()
 
- Public Member Functions inherited from LieGroupBase< Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 >, Displacement< _Scalar > >
AdjointMatrix adjoint (void) const
 
Algebra adjoint (const Algebra &) const
 
CoAlgebra adjointTr (const CoAlgebra &) const
 
const Displacement< _Scalar > & derived () const
 
Displacement< _Scalar > & derived ()
 
Coefficientsget ()
 
const Coefficientsget () const
 
PlainObject inverse () const
 
Algebra log (const Scalar precision=1e-6) const
 
PlainObject operator* (const LieGroupBase< Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 >, OtherDerived > &other) const
 
LieGroupBaseoperator= (const LieGroupBase< Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 >, OtherDerived > &)
 

Protected Types

typedef DisplacementBase< Displacement< Scalar > > Base
 
- Protected Types inherited from DisplacementBase< Displacement< _Scalar > >
typedef LieGroupBase< Array< Scalar, 7, 1 >, Displacement< _Scalar > > Base
 

Protected Attributes

Coefficients m_coeffs
 

Additional Inherited Members

- Static Public Member Functions inherited from LieGroupBase< Array< internal::traits< Displacement< _Scalar > >::Scalar, 7, 1 >, Displacement< _Scalar > >
static PlainObject Identity ()
 

Detailed Description

template<typename _Scalar>
class Displacement< _Scalar >

Class describing a rigid Displacement or a 3D Frame position.

Template Parameters
_Scalarthe type of the underlying array

This class add some specific constructors

See also
The methods are defined in LieGroupBase and DisplacementBase

Definition at line 159 of file Displacement.h.

Member Typedef Documentation

template<typename _Scalar>
typedef DisplacementBase<Displacement<Scalar> > Displacement< _Scalar >::Base
protected

The inherited class

Definition at line 165 of file Displacement.h.

template<typename _Scalar>
typedef internal::traits<Displacement>::Coefficients Displacement< _Scalar >::Coefficients

the stored coefficients

Definition at line 168 of file Displacement.h.

template<typename _Scalar>
typedef _Scalar Displacement< _Scalar >::Scalar

The coefficients type

Definition at line 162 of file Displacement.h.

Constructor & Destructor Documentation

template<typename _Scalar>
Displacement< _Scalar >::Displacement ( )
inline

Default constructor

Definition at line 173 of file Displacement.h.

template<typename _Scalar>
Displacement< _Scalar >::Displacement ( const Displacement< _Scalar > &  other)
inline

Copy constructor

Definition at line 175 of file Displacement.h.

template<typename _Scalar>
template<typename Derived >
Displacement< _Scalar >::Displacement ( const DisplacementBase< Derived > &  other)
inline

Pseudo-copy constructor

Definition at line 179 of file Displacement.h.

template<typename _Scalar>
Displacement< _Scalar >::Displacement ( const Array< Scalar, 7, 1 > &  g)
inline

Copy constructor using the wrapped class

Definition at line 181 of file Displacement.h.

template<typename _Scalar>
template<typename Derived >
Displacement< _Scalar >::Displacement ( const MatrixBase< Derived > &  other)
inlineexplicit

Definition at line 183 of file Displacement.h.

template<typename _Scalar>
EIGEN_STRONG_INLINE Displacement< _Scalar >::Displacement ( Scalar  x,
Scalar  y,
Scalar  z,
Scalar  qw = (Scalar)1.0,
Scalar  qx = (Scalar)0.0,
Scalar  qy = (Scalar)0.0,
Scalar  qz = (Scalar)0.0 
)
inline

Constructs and initializes the displacement with $R^3$ first then $SO(3)$

Warning
Note the order of the arguments: R^3 first then qw (scalar part) while internally the coefficients are stored in the following order: [qx, qy, qz, qw x y z]

Definition at line 190 of file Displacement.h.

template<typename _Scalar>
EIGEN_STRONG_INLINE Displacement< _Scalar >::Displacement ( const typename Base::Vector3 v,
const typename Base::Rotation3D r 
)
inline

Constructs a element of SE(3) from an element of SO(3) r and R^3 v

Definition at line 203 of file Displacement.h.

Member Function Documentation

template<typename _Scalar>
Coefficients& Displacement< _Scalar >::get ( )
inline
Returns
The stored coefficients

Definition at line 209 of file Displacement.h.

template<typename _Scalar>
const Coefficients& Displacement< _Scalar >::get ( ) const
inline
Returns
The read-only access to the stored coefficients

Definition at line 211 of file Displacement.h.

Member Data Documentation

template<typename _Scalar>
Coefficients Displacement< _Scalar >::m_coeffs
protected

The wrapped coefficients

Definition at line 215 of file Displacement.h.


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


lgsm
Author(s): Roberto Martín-Martín
autogenerated on Mon Jun 10 2019 14:05:58