Public Member Functions | Static Public Member Functions | Public Attributes | Friends
KDL::Frame Class Reference

represents a frame transformation in 3D space (rotation + translation) More...

#include <frames.hpp>

List of all members.

Public Member Functions

 Frame (const Rotation &R, const Vector &V)
 Frame (const Vector &V)
 The rotation matrix defaults to identity.
 Frame (const Rotation &R)
 The position matrix defaults to zero.
 Frame ()
 Frame (const Frame &arg)
 The copy constructor. Normal copy by value semantics.
void Integrate (const Twist &t_this, double frequency)
Frame Inverse () const
 Gives back inverse transformation of a Frame.
Vector Inverse (const Vector &arg) const
 The same as p2=R.Inverse()*p but more efficient.
Wrench Inverse (const Wrench &arg) const
 The same as p2=R.Inverse()*p but more efficient.
Twist Inverse (const Twist &arg) const
 The same as p2=R.Inverse()*p but more efficient.
void Make4x4 (double *d)
 Reads data from an double array.
double operator() (int i, int j)
double operator() (int i, int j) const
Vector operator* (const Vector &arg) const
Wrench operator* (const Wrench &arg) const
Twist operator* (const Twist &arg) const
Frameoperator= (const Frame &arg)
 Normal copy-by-value semantics.

Static Public Member Functions

static Frame DH (double a, double alpha, double d, double theta)
static Frame DH_Craig1989 (double a, double alpha, double d, double theta)
static Frame Identity ()

Public Attributes

Rotation M
 Orientation of the Frame.
Vector p
 origine of the Frame

Friends

bool Equal (const Frame &a, const Frame &b, double eps)
bool operator!= (const Frame &a, const Frame &b)
 The literal inequality operator!=().
Frame operator* (const Frame &lhs, const Frame &rhs)
 Composition of two frames.
bool operator== (const Frame &a, const Frame &b)
 The literal equality operator==(), also identical.

Detailed Description

represents a frame transformation in 3D space (rotation + translation)

if V2 = Frame*V1 (V2 expressed in frame A, V1 expressed in frame B) then V2 = Frame.M*V1+Frame.p

Frame.M contains columns that represent the axes of frame B wrt frame A Frame.p contains the origin of frame B expressed in frame A.

Definition at line 570 of file frames.hpp.


Constructor & Destructor Documentation

KDL::Frame::Frame ( const Rotation R,
const Vector V 
) [inline]
KDL::Frame::Frame ( const Vector V) [inline, explicit]

The rotation matrix defaults to identity.

KDL::Frame::Frame ( const Rotation R) [inline, explicit]

The position matrix defaults to zero.

KDL::Frame::Frame ( ) [inline]

Definition at line 584 of file frames.hpp.

KDL::Frame::Frame ( const Frame arg) [inline]

The copy constructor. Normal copy by value semantics.


Member Function Documentation

Frame KDL::Frame::DH ( double  a,
double  alpha,
double  d,
double  theta 
) [static]

Definition at line 70 of file frames.cpp.

Frame KDL::Frame::DH_Craig1989 ( double  a,
double  alpha,
double  d,
double  theta 
) [static]

Definition at line 53 of file frames.cpp.

static Frame KDL::Frame::Identity ( ) [inline, static]
Returns:
the identity transformation Frame(Rotation::Identity(),Vector::Zero()).
void KDL::Frame::Integrate ( const Twist t_this,
double  frequency 
) [inline]

The twist <t_this> is expressed wrt the current frame. This frame is integrated into an updated frame with <samplefrequency>. Very simple first order integration rule.

Frame KDL::Frame::Inverse ( ) const [inline]

Gives back inverse transformation of a Frame.

Vector KDL::Frame::Inverse ( const Vector arg) const [inline]

The same as p2=R.Inverse()*p but more efficient.

Wrench KDL::Frame::Inverse ( const Wrench arg) const [inline]

The same as p2=R.Inverse()*p but more efficient.

Twist KDL::Frame::Inverse ( const Twist arg) const [inline]

The same as p2=R.Inverse()*p but more efficient.

void KDL::Frame::Make4x4 ( double *  d)

Reads data from an double array.

Definition at line 39 of file frames.cpp.

double KDL::Frame::operator() ( int  i,
int  j 
) [inline]

Treats a frame as a 4x4 matrix and returns element i,j Access to elements 0..3,0..3, bounds are checked when NDEBUG is not set

double KDL::Frame::operator() ( int  i,
int  j 
) const [inline]

Treats a frame as a 4x4 matrix and returns element i,j Access to elements 0..3,0..3, bounds are checked when NDEBUG is not set

Vector KDL::Frame::operator* ( const Vector arg) const [inline]

Transformation of the base to which the vector is expressed.

Wrench KDL::Frame::operator* ( const Wrench arg) const [inline]

Transformation of both the force reference point and of the base to which the wrench is expressed. look at Rotation*Wrench operator for a transformation of only the base to which the twist is expressed.

Complexity : 24M+18A

Twist KDL::Frame::operator* ( const Twist arg) const [inline]

Transformation of both the velocity reference point and of the base to which the twist is expressed. look at Rotation*Twist for a transformation of only the base to which the twist is expressed.

Complexity : 24M+18A

Frame& KDL::Frame::operator= ( const Frame arg) [inline]

Normal copy-by-value semantics.


Friends And Related Function Documentation

bool Equal ( const Frame a,
const Frame b,
double  eps 
) [friend]

do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval

bool operator!= ( const Frame a,
const Frame b 
) [friend]

The literal inequality operator!=().

Frame operator* ( const Frame lhs,
const Frame rhs 
) [friend]

Composition of two frames.

bool operator== ( const Frame a,
const Frame b 
) [friend]

The literal equality operator==(), also identical.


Member Data Documentation

Orientation of the Frame.

Definition at line 573 of file frames.hpp.

origine of the Frame

Definition at line 572 of file frames.hpp.


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


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:29