$search
represents a frame transformation in 3D space (rotation + translation) More...
#include <frames.hpp>
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) |
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 |
double | operator() (int i, int j) |
Twist | operator* (const Twist &arg) const |
Wrench | operator* (const Wrench &arg) const |
Vector | operator* (const Vector &arg) const |
Frame & | operator= (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) |
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. |
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 561 of file frames.hpp.
Definition at line 401 of file frames.cpp.
KDL::Frame::Frame | ( | const Vector & | V | ) | [inline, explicit] |
The rotation matrix defaults to identity.
Definition at line 395 of file frames.cpp.
KDL::Frame::Frame | ( | const Rotation & | R | ) | [inline, explicit] |
The position matrix defaults to zero.
Definition at line 389 of file frames.cpp.
KDL::Frame::Frame | ( | ) | [inline] |
Definition at line 575 of file frames.hpp.
KDL::Frame::Frame | ( | const Frame & | arg | ) | [inline] |
The copy constructor. Normal copy by value semantics.
Definition at line 436 of file frames.cpp.
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.
Frame KDL::Frame::Identity | ( | ) | [inline, static] |
Definition at line 696 of file frames.cpp.
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 620 of file frames.cpp.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 283 of file frames.cpp.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 166 of file frames.cpp.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 418 of file frames.cpp.
Frame KDL::Frame::Inverse | ( | ) | const [inline] |
Gives back inverse transformation of a Frame.
Definition at line 423 of file frames.cpp.
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 | |||
) | 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 679 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
Definition at line 663 of file frames.cpp.
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 275 of file frames.cpp.
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 157 of file frames.cpp.
Transformation of the base to which the vector is expressed.
Definition at line 413 of file frames.cpp.
Normal copy-by-value semantics.
Definition at line 429 of file frames.cpp.
do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval
Definition at line 1033 of file frames.cpp.
The literal inequality operator!=().
Definition at line 1278 of file frames.cpp.
Composition of two frames.
Definition at line 407 of file frames.cpp.
The literal equality operator==(), also identical.
Definition at line 1269 of file frames.cpp.
Orientation of the Frame.
Definition at line 564 of file frames.hpp.
origine of the Frame
Definition at line 563 of file frames.hpp.