hpp-fcl  2.4.1
HPP fork of FCL -- The Flexible Collision Library
hpp::fcl::Transform3f Class Reference

Simple transform class used locally by InterpMotion. More...

#include <hpp/fcl/math/transform.h>

Public Member Functions

 Transform3f ()
 Default transform is no movement. More...
 
template<typename Matrixx3Like , typename Vector3Like >
 Transform3f (const Eigen::MatrixBase< Matrixx3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
 Construct transform from rotation and translation. More...
 
template<typename Vector3Like >
 Transform3f (const Quaternion3f &q_, const Eigen::MatrixBase< Vector3Like > &T_)
 Construct transform from rotation and translation. More...
 
 Transform3f (const Matrix3f &R_)
 Construct transform from rotation. More...
 
 Transform3f (const Quaternion3f &q_)
 Construct transform from rotation. More...
 
 Transform3f (const Vec3f &T_)
 Construct transform from translation. More...
 
 Transform3f (const Transform3f &tf)
 Construct transform from other transform. More...
 
Transform3foperator= (const Transform3f &tf)
 operator = More...
 
const Vec3fgetTranslation () const
 get translation More...
 
const Vec3ftranslation () const
 get translation More...
 
Vec3ftranslation ()
 get translation More...
 
const Matrix3fgetRotation () const
 get rotation More...
 
const Matrix3frotation () const
 get rotation More...
 
Matrix3frotation ()
 get rotation More...
 
Quaternion3f getQuatRotation () const
 get quaternion More...
 
template<typename Matrix3Like , typename Vector3Like >
void setTransform (const Eigen::MatrixBase< Matrix3Like > &R_, const Eigen::MatrixBase< Vector3Like > &T_)
 set transform from rotation and translation More...
 
void setTransform (const Quaternion3f &q_, const Vec3f &T_)
 set transform from rotation and translation More...
 
template<typename Derived >
void setRotation (const Eigen::MatrixBase< Derived > &R_)
 set transform from rotation More...
 
template<typename Derived >
void setTranslation (const Eigen::MatrixBase< Derived > &T_)
 set transform from translation More...
 
void setQuatRotation (const Quaternion3f &q_)
 set transform from rotation More...
 
template<typename Derived >
Vec3f transform (const Eigen::MatrixBase< Derived > &v) const
 transform a given vector by the transform More...
 
Transform3finverseInPlace ()
 inverse transform More...
 
Transform3f inverse ()
 inverse transform More...
 
Transform3f inverseTimes (const Transform3f &other) const
 inverse the transform and multiply with another More...
 
const Transform3foperator*= (const Transform3f &other)
 multiply with another transform More...
 
Transform3f operator* (const Transform3f &other) const
 multiply with another transform More...
 
bool isIdentity (const FCL_REAL &prec=Eigen::NumTraits< FCL_REAL >::dummy_precision()) const
 check whether the transform is identity More...
 
void setIdentity ()
 set the transform to be identity transform More...
 
bool operator== (const Transform3f &other) const
 
bool operator!= (const Transform3f &other) const
 

Static Public Member Functions

static Transform3f Identity ()
 

Detailed Description

Simple transform class used locally by InterpMotion.

Constructor & Destructor Documentation

◆ Transform3f() [1/7]

hpp::fcl::Transform3f::Transform3f ( )
inline

Default transform is no movement.

◆ Transform3f() [2/7]

template<typename Matrixx3Like , typename Vector3Like >
hpp::fcl::Transform3f::Transform3f ( const Eigen::MatrixBase< Matrixx3Like > &  R_,
const Eigen::MatrixBase< Vector3Like > &  T_ 
)
inline

Construct transform from rotation and translation.

◆ Transform3f() [3/7]

template<typename Vector3Like >
hpp::fcl::Transform3f::Transform3f ( const Quaternion3f q_,
const Eigen::MatrixBase< Vector3Like > &  T_ 
)
inline

Construct transform from rotation and translation.

◆ Transform3f() [4/7]

hpp::fcl::Transform3f::Transform3f ( const Matrix3f R_)
inline

Construct transform from rotation.

◆ Transform3f() [5/7]

hpp::fcl::Transform3f::Transform3f ( const Quaternion3f q_)
inline

Construct transform from rotation.

◆ Transform3f() [6/7]

hpp::fcl::Transform3f::Transform3f ( const Vec3f T_)
inline

Construct transform from translation.

◆ Transform3f() [7/7]

hpp::fcl::Transform3f::Transform3f ( const Transform3f tf)
inline

Construct transform from other transform.

Member Function Documentation

◆ getQuatRotation()

Quaternion3f hpp::fcl::Transform3f::getQuatRotation ( ) const
inline

get quaternion

◆ getRotation()

const Matrix3f& hpp::fcl::Transform3f::getRotation ( ) const
inline

get rotation

◆ getTranslation()

const Vec3f& hpp::fcl::Transform3f::getTranslation ( ) const
inline

get translation

◆ Identity()

static Transform3f hpp::fcl::Transform3f::Identity ( )
inlinestatic

◆ inverse()

Transform3f hpp::fcl::Transform3f::inverse ( )
inline

inverse transform

◆ inverseInPlace()

Transform3f& hpp::fcl::Transform3f::inverseInPlace ( )
inline

inverse transform

◆ inverseTimes()

Transform3f hpp::fcl::Transform3f::inverseTimes ( const Transform3f other) const
inline

inverse the transform and multiply with another

◆ isIdentity()

bool hpp::fcl::Transform3f::isIdentity ( const FCL_REAL prec = Eigen::NumTraits<FCL_REAL>::dummy_precision()) const
inline

check whether the transform is identity

◆ operator!=()

bool hpp::fcl::Transform3f::operator!= ( const Transform3f other) const
inline

◆ operator*()

Transform3f hpp::fcl::Transform3f::operator* ( const Transform3f other) const
inline

multiply with another transform

◆ operator*=()

const Transform3f& hpp::fcl::Transform3f::operator*= ( const Transform3f other)
inline

multiply with another transform

◆ operator=()

Transform3f& hpp::fcl::Transform3f::operator= ( const Transform3f tf)
inline

operator =

◆ operator==()

bool hpp::fcl::Transform3f::operator== ( const Transform3f other) const
inline

◆ rotation() [1/2]

Matrix3f& hpp::fcl::Transform3f::rotation ( )
inline

get rotation

◆ rotation() [2/2]

const Matrix3f& hpp::fcl::Transform3f::rotation ( ) const
inline

get rotation

◆ setIdentity()

void hpp::fcl::Transform3f::setIdentity ( )
inline

set the transform to be identity transform

◆ setQuatRotation()

void hpp::fcl::Transform3f::setQuatRotation ( const Quaternion3f q_)
inline

set transform from rotation

◆ setRotation()

template<typename Derived >
void hpp::fcl::Transform3f::setRotation ( const Eigen::MatrixBase< Derived > &  R_)
inline

set transform from rotation

◆ setTransform() [1/2]

template<typename Matrix3Like , typename Vector3Like >
void hpp::fcl::Transform3f::setTransform ( const Eigen::MatrixBase< Matrix3Like > &  R_,
const Eigen::MatrixBase< Vector3Like > &  T_ 
)
inline

set transform from rotation and translation

◆ setTransform() [2/2]

void hpp::fcl::Transform3f::setTransform ( const Quaternion3f q_,
const Vec3f T_ 
)
inline

set transform from rotation and translation

◆ setTranslation()

template<typename Derived >
void hpp::fcl::Transform3f::setTranslation ( const Eigen::MatrixBase< Derived > &  T_)
inline

set transform from translation

◆ transform()

template<typename Derived >
Vec3f hpp::fcl::Transform3f::transform ( const Eigen::MatrixBase< Derived > &  v) const
inline

transform a given vector by the transform

◆ translation() [1/2]

Vec3f& hpp::fcl::Transform3f::translation ( )
inline

get translation

◆ translation() [2/2]

const Vec3f& hpp::fcl::Transform3f::translation ( ) const
inline

get translation


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