Base class describing a rigid Displacement or a 3D Frame position. More...
#include <Displacement.h>
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 Types inherited from LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, Derived > | |
typedef Derived::AdjointMatrix | AdjointMatrix |
typedef Derived::Algebra | Algebra |
typedef Array< internal::traits< Derived >::Scalar, 7, 1 > | BaseType |
typedef Derived::CoAlgebra | CoAlgebra |
typedef Derived::Coefficients | Coefficients |
typedef internal::traits< Derived >::PlainObject | PlainObject |
typedef internal::traits< Derived >::Scalar | Scalar |
Public Member Functions | |
template<typename NewScalarType > | |
internal::cast_return_type< Derived, Displacement< NewScalarType > >::type | cast () const |
Map< Rotation3D > | getRotation () |
const Map< const Rotation3D > | getRotation () const |
Map< Vector3 > | getTranslation () |
const Map< const Vector3 > | getTranslation () const |
EIGEN_STRONG_INLINE DisplacementBase & | operator= (const typename Base::PlainObject &g) |
Scalar | qw () const |
Scalar & | qw () |
Scalar | qx () const |
Scalar & | qx () |
Scalar | qy () const |
Scalar & | qy () |
Scalar | qz () const |
Scalar & | qz () |
void | setRandom () |
Matrix< Scalar, 4, 4 > | toHomogeneousMatrix () const |
Scalar | x () const |
Scalar & | x () |
Scalar | y () const |
Scalar & | y () |
Scalar | z () const |
Scalar & | z () |
Public Member Functions inherited from LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, Derived > | |
AdjointMatrix | adjoint (void) const |
Algebra | adjoint (const Algebra &) const |
CoAlgebra | adjointTr (const CoAlgebra &) const |
const Derived & | derived () const |
Derived & | derived () |
Coefficients & | get () |
const Coefficients & | get () const |
PlainObject | inverse () const |
Algebra | log (const Scalar precision=1e-6) const |
PlainObject | operator* (const LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, OtherDerived > &other) const |
LieGroupBase & | operator= (const LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, OtherDerived > &) |
Protected Types | |
typedef LieGroupBase< Array< Scalar, 7, 1 >, Derived > | Base |
Friends | |
template<class OtherDerived > | |
std::ostream & | operator<< (std::ostream &os, const DisplacementBase< OtherDerived > &d) |
Additional Inherited Members | |
Static Public Member Functions inherited from LieGroupBase< Array< internal::traits< Derived >::Scalar, 7, 1 >, Derived > | |
static PlainObject | Identity () |
Base class describing a rigid Displacement or a 3D Frame position.
Derived | the 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.
|
protected |
The inherited class
Definition at line 34 of file Displacement.h.
typedef Base::BaseType DisplacementBase< Derived >::BaseType |
The wrapped class (Array<Scalar, 7, 1>
Definition at line 40 of file Displacement.h.
typedef Base::PlainObject DisplacementBase< Derived >::PlainObject |
The plain object returned, while using Map<Displacement >
Definition at line 42 of file Displacement.h.
typedef LieGroup<Quaternion<Scalar> > DisplacementBase< Derived >::Rotation3D |
The type of the rotation part
Definition at line 47 of file Displacement.h.
typedef internal::traits<Derived>::Scalar DisplacementBase< Derived >::Scalar |
The coefficients type
Definition at line 31 of file Displacement.h.
typedef Matrix<Scalar, 3, 1> DisplacementBase< Derived >::Vector3 |
The type of the translation part
Definition at line 45 of file Displacement.h.
|
inline |
*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.
|
inline |
The accessor to the rotation part
Definition at line 50 of file Displacement.h.
|
inline |
The read-only accessor to the rotation part
Definition at line 52 of file Displacement.h.
|
inline |
The accessor to the translation part
Definition at line 54 of file Displacement.h.
|
inline |
The read-only accessor to the translation part
Definition at line 56 of file Displacement.h.
|
inline |
Definition at line 106 of file Displacement.h.
|
inline |
qw
coefficient Definition at line 72 of file Displacement.h.
|
inline |
qw
coefficient Definition at line 87 of file Displacement.h.
|
inline |
qx
coefficient Definition at line 66 of file Displacement.h.
|
inline |
qx
coefficient Definition at line 81 of file Displacement.h.
|
inline |
qy
coefficient Definition at line 68 of file Displacement.h.
|
inline |
qy
coefficient Definition at line 83 of file Displacement.h.
|
inline |
qz
coefficient Definition at line 70 of file Displacement.h.
|
inline |
qz
coefficient Definition at line 85 of file Displacement.h.
|
inline |
Definition at line 89 of file Displacement.h.
Matrix< typename internal::traits< Derived >::Scalar, 4, 4 > DisplacementBase< Derived >::toHomogeneousMatrix | ( | ) | const |
Definition at line 119 of file Displacement.h.
|
inline |
x
coefficient Definition at line 60 of file Displacement.h.
|
inline |
x
coefficient Definition at line 75 of file Displacement.h.
|
inline |
y
coefficient Definition at line 62 of file Displacement.h.
|
inline |
y
coefficient Definition at line 77 of file Displacement.h.
|
inline |
z
coefficient Definition at line 64 of file Displacement.h.
|
inline |
z
coefficient Definition at line 79 of file Displacement.h.
|
friend |
Outputs to the given stream : order : w x y z (it's different from the storage order)