kinematics-dynamics
Public Types | Public Member Functions | Private Attributes | List of all members
roboticslab::MatrixExponential Class Reference

Abstraction of a term in a product of exponentials (POE) formula. More...

#include <MatrixExponential.hpp>

Public Types

enum  motion { ROTATION , TRANSLATION }
 Lists available screw motion types. More...
 

Public Member Functions

 MatrixExponential (motion motionType, const KDL::Vector &axis, const KDL::Vector &origin=KDL::Vector::Zero())
 Constructor. More...
 
KDL::Frame asFrame (double theta) const
 Evaluates this term for the given magnitude of the screw. More...
 
motion getMotionType () const
 Retrieves the motion type of this screw. More...
 
const KDL::Vector & getAxis () const
 Screw axis. More...
 
const KDL::Vector & getOrigin () const
 A point along the screw axis. More...
 
void changeBase (const KDL::Frame &H_new_old)
 Refers the internal coordinates of this screw to a different base. More...
 
MatrixExponential cloneWithBase (const KDL::Frame &H_new_old) const
 Clones this instance and refers the internal coordinates of the screw to a different base. More...
 

Private Attributes

motion motionType
 
KDL::Vector axis
 
KDL::Vector origin
 

Detailed Description

See also
PoeExpression

Member Enumeration Documentation

◆ motion

Enumerator
ROTATION 

Revolute joint (zero-pitch twist).

TRANSLATION 

Prismatic joint (infinite-pitch twist).

Constructor & Destructor Documentation

◆ MatrixExponential()

MatrixExponential::MatrixExponential ( motion  motionType,
const KDL::Vector &  axis,
const KDL::Vector &  origin = KDL::Vector::Zero() 
)
Parameters
motionTypeScrew motion type as defined in motion.
axisScrew axis.
originA point along the screw axis (defaults to (0, 0, 0), ignored in prismatic joints).

Member Function Documentation

◆ asFrame()

KDL::Frame MatrixExponential::asFrame ( double  theta) const
Parameters
thetaInput magnitude this screw should be computed at.
Returns
Resulting homogeneous transformation matrix.

◆ changeBase()

void MatrixExponential::changeBase ( const KDL::Frame &  H_new_old)
Parameters
H_new_oldTransformation between the new and the old base frame.
See also
cloneWithBase

◆ cloneWithBase()

MatrixExponential MatrixExponential::cloneWithBase ( const KDL::Frame &  H_new_old) const
Parameters
H_new_oldTransformation between the new and the old base frame.
Returns
An instance referred to the new frame.
See also
changeBase

◆ getAxis()

const KDL::Vector& roboticslab::MatrixExponential::getAxis ( ) const
inline
Returns
A vector representing the direction of the screw axis.

◆ getMotionType()

motion roboticslab::MatrixExponential::getMotionType ( ) const
inline
Returns
A motion type this term has been registered with.

◆ getOrigin()

const KDL::Vector& roboticslab::MatrixExponential::getOrigin ( ) const
inline
Returns
A vector representing the position of some point along the screw axis.

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