geolib2
Public Member Functions | Static Public Member Functions | Public Attributes | Friends | List of all members
geo::Transform3T< T > Class Template Reference

#include <math_types.h>

Public Member Functions

const Mat3T< T > & getBasis () const
 
const Vec3T< T > & getOrigin () const
 
QuaternionT< T > getQuaternion () const
 
void getRPY (double &roll, double &pitch, double &yaw) const
 
double getYaw () const
 
Transform3T inverse () const
 
Transform3T inverseTimes (const Transform3T &tr) const
 
bool operator!= (const Transform3T &tr) const
 
Transform3T operator* (const Transform3T &tr) const
 
Vec3T< T > operator* (const Vec3T< T > &v) const
 
Transform3Toperator= (const Transform3T &tr)
 
bool operator== (const Transform3T &tr) const
 
Transform2T< T > projectTo2d () const
 Drops displacement and rotation fo the 3rd coordinate. More...
 
void setBasis (const Mat3T< T > &r)
 
void setOrigin (const Vec3T< T > &v)
 
void setRPY (double roll, double pitch, double yaw)
 
 Transform3T ()
 
 Transform3T (const Mat3T< T > &r, const Vec3T< T > &v)
 
 Transform3T (const Transform3T &tr)=default
 
 Transform3T (T x, T y, T z, T roll=0, T pitch=0, T yaw=0)
 
 ~Transform3T ()
 

Static Public Member Functions

static Transform3T identity ()
 

Public Attributes

Mat3T< T > R
 
Vec3T< T > t
 

Friends

std::ostreamoperator<< (std::ostream &out, const Transform3T &t)
 

Detailed Description

template<typename T>
class geo::Transform3T< T >

Definition at line 19 of file math_types.h.

Constructor & Destructor Documentation

◆ Transform3T() [1/4]

template<typename T >
geo::Transform3T< T >::Transform3T ( )
inline

Definition at line 690 of file math_types.h.

◆ Transform3T() [2/4]

template<typename T >
geo::Transform3T< T >::Transform3T ( const Transform3T< T > &  tr)
default

◆ Transform3T() [3/4]

template<typename T >
geo::Transform3T< T >::Transform3T ( x,
y,
z,
roll = 0,
pitch = 0,
yaw = 0 
)
inline

Definition at line 693 of file math_types.h.

◆ Transform3T() [4/4]

template<typename T >
geo::Transform3T< T >::Transform3T ( const Mat3T< T > &  r,
const Vec3T< T > &  v 
)
inline

Definition at line 697 of file math_types.h.

◆ ~Transform3T()

template<typename T >
geo::Transform3T< T >::~Transform3T ( )
inline

Definition at line 699 of file math_types.h.

Member Function Documentation

◆ getBasis()

template<typename T >
const Mat3T<T>& geo::Transform3T< T >::getBasis ( ) const
inline

Definition at line 740 of file math_types.h.

◆ getOrigin()

template<typename T >
const Vec3T<T>& geo::Transform3T< T >::getOrigin ( ) const
inline

Definition at line 730 of file math_types.h.

◆ getQuaternion()

template<typename T >
QuaternionT<T> geo::Transform3T< T >::getQuaternion ( ) const
inline

Definition at line 734 of file math_types.h.

◆ getRPY()

template<typename T >
void geo::Transform3T< T >::getRPY ( double &  roll,
double &  pitch,
double &  yaw 
) const
inline

Definition at line 756 of file math_types.h.

◆ getYaw()

template<typename T >
double geo::Transform3T< T >::getYaw ( ) const
inline

Definition at line 772 of file math_types.h.

◆ identity()

template<typename T >
static Transform3T geo::Transform3T< T >::identity ( )
inlinestatic

Definition at line 778 of file math_types.h.

◆ inverse()

template<typename T >
Transform3T geo::Transform3T< T >::inverse ( ) const
inline

Definition at line 747 of file math_types.h.

◆ inverseTimes()

template<typename T >
Transform3T geo::Transform3T< T >::inverseTimes ( const Transform3T< T > &  tr) const
inline

Definition at line 725 of file math_types.h.

◆ operator!=()

template<typename T >
bool geo::Transform3T< T >::operator!= ( const Transform3T< T > &  tr) const
inline

Definition at line 713 of file math_types.h.

◆ operator*() [1/2]

template<typename T >
Transform3T geo::Transform3T< T >::operator* ( const Transform3T< T > &  tr) const
inline

Definition at line 721 of file math_types.h.

◆ operator*() [2/2]

template<typename T >
Vec3T<T> geo::Transform3T< T >::operator* ( const Vec3T< T > &  v) const
inline

Definition at line 717 of file math_types.h.

◆ operator=()

template<typename T >
Transform3T& geo::Transform3T< T >::operator= ( const Transform3T< T > &  tr)
inline

Definition at line 701 of file math_types.h.

◆ operator==()

template<typename T >
bool geo::Transform3T< T >::operator== ( const Transform3T< T > &  tr) const
inline

Definition at line 709 of file math_types.h.

◆ projectTo2d()

template<typename T >
Transform2T<T> geo::Transform3T< T >::projectTo2d ( ) const
inline

Drops displacement and rotation fo the 3rd coordinate.

Returns
Transform in 2D

Definition at line 784 of file math_types.h.

◆ setBasis()

template<typename T >
void geo::Transform3T< T >::setBasis ( const Mat3T< T > &  r)
inline

Definition at line 745 of file math_types.h.

◆ setOrigin()

template<typename T >
void geo::Transform3T< T >::setOrigin ( const Vec3T< T > &  v)
inline

Definition at line 744 of file math_types.h.

◆ setRPY()

template<typename T >
void geo::Transform3T< T >::setRPY ( double  roll,
double  pitch,
double  yaw 
)
inline

Definition at line 752 of file math_types.h.

Friends And Related Function Documentation

◆ operator<<

template<typename T >
std::ostream& operator<< ( std::ostream out,
const Transform3T< T > &  t 
)
friend

Definition at line 788 of file math_types.h.

Member Data Documentation

◆ R

template<typename T >
Mat3T<T> geo::Transform3T< T >::R

Definition at line 793 of file math_types.h.

◆ t

template<typename T >
Vec3T<T> geo::Transform3T< T >::t

Definition at line 794 of file math_types.h.


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