Public Types | Public Member Functions | Protected Types | Friends
DisplacementBase< Derived > Class Template Reference

Base class describing a rigid Displacement or a 3D Frame position. More...

#include <Displacement.h>

Inheritance diagram for DisplacementBase< Derived >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Base::BaseType BaseType
typedef Base::PlainObject PlainObject
typedef LieGroup< Quaternion
< Scalar > > 
Rotation3D
typedef internal::traits
< Derived >::Scalar 
Scalar
typedef Matrix< Scalar, 3, 1 > Vector3

Public Member Functions

template<typename NewScalarType >
internal::cast_return_type
< Derived, Displacement
< NewScalarType > >::type 
cast () const
Map< Rotation3DgetRotation ()
const Map< const Rotation3DgetRotation () const
Map< Vector3getTranslation ()
const Map< const Vector3getTranslation () const
EIGEN_STRONG_INLINE
DisplacementBase
operator= (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 ()

Protected Types

typedef LieGroupBase< Array
< Scalar, 7, 1 >, Derived > 
Base

Friends

template<class OtherDerived >
std::ostream & operator<< (std::ostream &os, const DisplacementBase< OtherDerived > &d)

Detailed Description

template<class Derived>
class DisplacementBase< Derived >

Base class describing a rigid Displacement or a 3D Frame position.

Template Parameters:
Derivedthe derived class holding the coefficients which are of type Array<Scalar, 7, 1> or Map<Array<Scalar, 7, 1> >

This class abstracts the underlying mathematical definition and add some accessors. It uses an Array internally to store its coefficients.

Definition at line 28 of file Displacement.h.


Member Typedef Documentation

template<class Derived>
typedef LieGroupBase<Array<Scalar, 7, 1>, Derived> DisplacementBase< Derived >::Base [protected]

The inherited class

Reimplemented in Map< Displacement< _Scalar >, MapOptions, StrideType >, Displacement< _Scalar >, and Displacement< Scalar >.

Definition at line 34 of file Displacement.h.

template<class Derived>
typedef Base::BaseType DisplacementBase< Derived >::BaseType

The wrapped class (Array<Scalar, 7, 1>

Reimplemented from LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, Derived >.

Definition at line 40 of file Displacement.h.

template<class Derived>
typedef Base::PlainObject DisplacementBase< Derived >::PlainObject

The plain object returned, while using Map<Displacement >

Reimplemented from LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, Derived >.

Definition at line 42 of file Displacement.h.

template<class Derived>
typedef LieGroup<Quaternion<Scalar> > DisplacementBase< Derived >::Rotation3D

The type of the rotation part

Definition at line 47 of file Displacement.h.

template<class Derived>
typedef internal::traits<Derived>::Scalar DisplacementBase< Derived >::Scalar
template<class Derived>
typedef Matrix<Scalar, 3, 1> DisplacementBase< Derived >::Vector3

The type of the translation part

Definition at line 45 of file Displacement.h.


Member Function Documentation

template<class Derived>
template<typename NewScalarType >
internal::cast_return_type<Derived, Displacement<NewScalarType> >::type DisplacementBase< Derived >::cast ( ) const [inline]
Returns:
*this with scalar type casted to NewScalarType

Note that if NewScalarType is equal to the current scalar type of *this then this function smartly returns a const reference to *this.

Definition at line 100 of file Displacement.h.

template<class Derived>
Map<Rotation3D> DisplacementBase< Derived >::getRotation ( ) [inline]

The accessor to the rotation part

Definition at line 50 of file Displacement.h.

template<class Derived>
const Map<const Rotation3D> DisplacementBase< Derived >::getRotation ( ) const [inline]

The read-only accessor to the rotation part

Definition at line 52 of file Displacement.h.

template<class Derived>
Map<Vector3> DisplacementBase< Derived >::getTranslation ( ) [inline]

The accessor to the translation part

Definition at line 54 of file Displacement.h.

template<class Derived>
const Map<const Vector3> DisplacementBase< Derived >::getTranslation ( ) const [inline]

The read-only accessor to the translation part

Definition at line 56 of file Displacement.h.

template<class Derived>
EIGEN_STRONG_INLINE DisplacementBase& DisplacementBase< Derived >::operator= ( const typename Base::PlainObject g) [inline]

Definition at line 106 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::qw ( ) const [inline]
Returns:
the qw coefficient

Definition at line 72 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::qw ( ) [inline]
Returns:
a reference to the qw coefficient

Definition at line 87 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::qx ( ) const [inline]
Returns:
the qx coefficient

Definition at line 66 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::qx ( ) [inline]
Returns:
a reference to the qx coefficient

Definition at line 81 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::qy ( ) const [inline]
Returns:
the qy coefficient

Definition at line 68 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::qy ( ) [inline]
Returns:
a reference to the qy coefficient

Definition at line 83 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::qz ( ) const [inline]
Returns:
the qz coefficient

Definition at line 70 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::qz ( ) [inline]
Returns:
a reference to the qz coefficient

Definition at line 85 of file Displacement.h.

template<class Derived>
void DisplacementBase< Derived >::setRandom ( ) [inline]

Definition at line 89 of file Displacement.h.

template<class Derived >
Matrix< typename internal::traits< Derived >::Scalar, 4, 4 > DisplacementBase< Derived >::toHomogeneousMatrix ( ) const

Definition at line 119 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::x ( ) const [inline]
Returns:
the x coefficient

Definition at line 60 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::x ( ) [inline]
Returns:
a reference to the x coefficient

Definition at line 75 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::y ( ) const [inline]
Returns:
the y coefficient

Definition at line 62 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::y ( ) [inline]
Returns:
a reference to the y coefficient

Definition at line 77 of file Displacement.h.

template<class Derived>
Scalar DisplacementBase< Derived >::z ( ) const [inline]
Returns:
the z coefficient

Definition at line 64 of file Displacement.h.

template<class Derived>
Scalar& DisplacementBase< Derived >::z ( ) [inline]
Returns:
a reference to the z coefficient

Definition at line 79 of file Displacement.h.


Friends And Related Function Documentation

template<class Derived>
template<class OtherDerived >
std::ostream& operator<< ( std::ostream &  os,
const DisplacementBase< OtherDerived > &  d 
) [friend]

Outputs to the given stream : order : w x y z (it's different from the storage order)


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


lgsm
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:26:30