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 Frame &arg)
 The copy constructor. Normal copy by value semantics.
 Frame ()
 Frame (const Rotation &R)
 The position matrix defaults to zero.
 Frame (const Vector &V)
 The rotation matrix defaults to identity.
 Frame (const Rotation &R, const Vector &V)
void Integrate (const Twist &t_this, double frequency)
 The twist <t_this> is expressed wrt the current frame.
Twist Inverse (const Twist &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.
Vector Inverse (const Vector &arg) const
 The same as p2=R.Inverse()*p but more efficient.
Frame Inverse () const
 Gives back inverse transformation of a Frame.
void Make4x4 (double *d)
 Reads data from an double array.
double operator() (int i, int j) const
 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 operator() (int i, int j)
 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.
Twist operator* (const Twist &arg) const
 Transformation of both the velocity reference point and of the base to which the twist is expressed.
Wrench operator* (const Wrench &arg) const
 Transformation of both the force reference point and of the base to which the wrench is expressed.
Vector operator* (const Vector &arg) const
 Transformation of the base to which the vector is expressed.
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=epsilon)
 do not use operator == because the definition of Equal(.,.
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 518 of file frames.hpp.


Constructor & Destructor Documentation

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

Definition at line 395 of file frames.inl.

References M, and p.

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

The rotation matrix defaults to identity.

Definition at line 389 of file frames.inl.

References Identity(), M, and p.

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

The position matrix defaults to zero.

Definition at line 383 of file frames.inl.

References M, p, and KDL::Vector::Zero().

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

Definition at line 532 of file frames.hpp.

Referenced by DH(), DH_Craig1989(), Identity(), Integrate(), and Inverse().

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

The copy constructor. Normal copy by value semantics.

Definition at line 430 of file frames.inl.


Member Function Documentation

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

Definition at line 67 of file frames.cpp.

References KDL::cos(), Frame(), and KDL::sin().

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

Definition at line 50 of file frames.cpp.

References KDL::cos(), Frame(), and KDL::sin().

Frame KDL::Frame::Identity (  )  [inline, static]
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.

Definition at line 614 of file frames.inl.

References KDL::epsilon, Frame(), M, KDL::Vector::Norm(), p, KDL::Rotation::Rot(), KDL::Twist::rot, and KDL::Twist::vel.

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

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

Definition at line 277 of file frames.inl.

References KDL::Rotation::Inverse(), M, p, KDL::Twist::rot, and KDL::Twist::vel.

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

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

Definition at line 160 of file frames.inl.

References KDL::Wrench::force, KDL::Rotation::Inverse(), M, p, and KDL::Wrench::torque.

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

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

Definition at line 412 of file frames.inl.

References KDL::Rotation::Inverse(), M, and p.

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

Gives back inverse transformation of a Frame.

Definition at line 417 of file frames.inl.

References Frame(), KDL::Rotation::Inverse(), M, and p.

Referenced by KDL::Tree::getChain(), KDL::operator*(), and KDL::Vector2::Set3DPlane().

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

Reads data from an double array.

Definition at line 36 of file frames.cpp.

References M, and p.

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.

Definition at line 673 of file frames.inl.

References FRAMES_CHECKI, M, and p.

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.

Definition at line 657 of file frames.inl.

References FRAMES_CHECKI, M, and p.

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

Definition at line 269 of file frames.inl.

References draftTools::p, KDL::Twist::rot, and KDL::Twist::vel.

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

Definition at line 151 of file frames.inl.

References KDL::Wrench::force, draftTools::p, and KDL::Wrench::torque.

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

Transformation of the base to which the vector is expressed.

Definition at line 407 of file frames.inl.

References M, and p.

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

Normal copy-by-value semantics.

Definition at line 423 of file frames.inl.

References M, and p.


Friends And Related Function Documentation

bool Equal ( const Frame a,
const Frame b,
double  eps = epsilon 
) [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


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

Generated on Wed Nov 23 19:02:17 2011 for FreeCAD by  doxygen 1.6.1