orocos_kdl
|
represents a frame transformation in 3D space (rotation + translation) More...
#include <frames.hpp>
Public Member Functions | |
Frame () | |
Frame (const Frame &arg) | |
The copy constructor. Normal copy by value semantics. More... | |
Frame (const Rotation &R) | |
The position matrix defaults to zero. More... | |
Frame (const Rotation &R, const Vector &V) | |
Frame (const Vector &V) | |
The rotation matrix defaults to identity. More... | |
void | Integrate (const Twist &t_this, double frequency) |
Frame | Inverse () const |
Gives back inverse transformation of a Frame. More... | |
Twist | Inverse (const Twist &arg) const |
The same as p2=R.Inverse()*p but more efficient. More... | |
Vector | Inverse (const Vector &arg) const |
The same as p2=R.Inverse()*p but more efficient. More... | |
Wrench | Inverse (const Wrench &arg) const |
The same as p2=R.Inverse()*p but more efficient. More... | |
void | Make4x4 (double *d) |
Reads data from an double array. More... | |
double | operator() (int i, int j) |
double | operator() (int i, int j) const |
Twist | operator* (const Twist &arg) const |
Vector | operator* (const Vector &arg) const |
Wrench | operator* (const Wrench &arg) const |
Frame & | operator= (const Frame &arg) |
Normal copy-by-value semantics. More... | |
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. More... | |
Vector | p |
origine of the Frame More... | |
Friends | |
bool | Equal (const Frame &a, const Frame &b, double eps) |
bool | operator!= (const Frame &a, const Frame &b) |
The literal inequality operator!=(). More... | |
Frame | operator* (const Frame &lhs, const Frame &rhs) |
Composition of two frames. More... | |
bool | operator== (const Frame &a, const Frame &b) |
The literal equality operator==(), also identical. More... | |
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 572 of file frames.hpp.
Definition at line 400 of file frames.inl.
|
inlineexplicit |
The rotation matrix defaults to identity.
Definition at line 394 of file frames.inl.
|
inlineexplicit |
The position matrix defaults to zero.
Definition at line 388 of file frames.inl.
|
inline |
Definition at line 586 of file frames.hpp.
|
inline |
The copy constructor. Normal copy by value semantics.
Definition at line 435 of file frames.inl.
|
static |
Definition at line 95 of file frames.cpp.
|
static |
Definition at line 78 of file frames.cpp.
|
inlinestatic |
Definition at line 700 of file frames.inl.
|
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 624 of file frames.inl.
|
inline |
Gives back inverse transformation of a Frame.
Definition at line 422 of file frames.inl.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 282 of file frames.inl.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 417 of file frames.inl.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 165 of file frames.inl.
void KDL::Frame::Make4x4 | ( | double * | d | ) |
Reads data from an double array.
Definition at line 64 of file frames.cpp.
|
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 667 of file frames.inl.
|
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 683 of file frames.inl.
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 274 of file frames.inl.
Transformation of the base to which the vector is expressed.
Definition at line 412 of file frames.inl.
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 156 of file frames.inl.
Normal copy-by-value semantics.
Definition at line 428 of file frames.inl.
do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval
The literal inequality operator!=().
The literal equality operator==(), also identical.
Rotation KDL::Frame::M |
Orientation of the Frame.
Definition at line 575 of file frames.hpp.
Vector KDL::Frame::p |
origine of the Frame
Definition at line 574 of file frames.hpp.