Blender V2.61 - r43446
|
represents a frame transformation in 3D space (rotation + translation) More...
#include <frames.hpp>
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. | |
void | setValue (float *oglmat) |
void | getValue (float *oglmat) const |
Frame () | |
Frame (const Frame &arg) | |
The copy constructor. Normal copy by value semantics. | |
void | Make4x4 (double *d) |
Reads data from an double array. | |
double | operator() (int i, int j) |
double | operator() (int i, int j) const |
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. | |
Frame & | operator= (const Frame &arg) |
Normal copy-by-value semantics. | |
Vector | operator* (const Vector &arg) const |
Wrench | operator* (const Wrench &arg) const |
Twist | operator* (const Twist &arg) const |
void | Integrate (const Twist &t_this, double frequency) |
Static Public Member Functions | |
static Frame | Identity () |
static Frame | DH_Craig1989 (double a, double alpha, double d, double theta) |
static Frame | DH (double a, double alpha, double d, double theta) |
Public Attributes | |
Vector | p |
origine of the Frame | |
Rotation | M |
Orientation of the Frame. | |
Friends | |
Frame | operator* (const Frame &lhs, const Frame &rhs) |
Composition of two frames. | |
bool | Equal (const Frame &a, const Frame &b, double eps=epsilon) |
bool | operator== (const Frame &a, const Frame &b) |
The literal equality operator==(), also identical. | |
bool | operator!= (const Frame &a, const Frame &b) |
The literal inequality operator!=(). |
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 524 of file frames.hpp.
Frame::Frame | ( | const Vector & | V | ) | [inline, explicit] |
The rotation matrix defaults to identity.
Definition at line 395 of file frames.inl.
Frame::Frame | ( | const Rotation & | R | ) | [inline, explicit] |
The position matrix defaults to zero.
Definition at line 389 of file frames.inl.
KDL::Frame::Frame | ( | ) | [inline] |
Definition at line 541 of file frames.hpp.
Referenced by DH(), DH_Craig1989(), and KDL::Frame2::Integrate().
Frame::Frame | ( | const Frame & | arg | ) | [inline] |
The copy constructor. Normal copy by value semantics.
Definition at line 436 of file frames.inl.
Frame KDL::Frame::DH | ( | double | a, |
double | alpha, | ||
double | d, | ||
double | theta | ||
) | [static] |
Definition at line 70 of file frames.cpp.
References KDL::cos(), Frame(), Rotation(), and KDL::sin().
Frame KDL::Frame::DH_Craig1989 | ( | double | a, |
double | alpha, | ||
double | d, | ||
double | theta | ||
) | [static] |
Definition at line 53 of file frames.cpp.
References KDL::cos(), Frame(), Rotation(), and KDL::sin().
void KDL::Frame::getValue | ( | float * | oglmat | ) | const [inline] |
Referenced by base_callback(), and execute_scene().
static Frame KDL::Frame::Identity | ( | ) | [inline, static] |
Referenced by KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), KDL::Joint::pose(), and iTaSC::WorldObject::WorldObject().
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.
Referenced by iTaSC::MovingFrame::updateKinematics().
The same as p2=R.Inverse()*p but more efficient.
The same as p2=R.Inverse()*p but more efficient.
The same as p2=R.Inverse()*p but more efficient.
Frame KDL::Frame::Inverse | ( | ) | const [inline] |
Gives back inverse transformation of a Frame.
Referenced by iTaSC::Distance::closeLoop(), and KDL::Vector2::Set3DPlane().
void KDL::Frame::Make4x4 | ( | double * | d | ) |
double 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 678 of file frames.inl.
References FRAMES_CHECKI, 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
Transformation of the base to which the vector is expressed.
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
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
void KDL::Frame::setValue | ( | float * | oglmat | ) | [inline] |
Referenced by base_callback(), and target_callback().
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.
Orientation of the Frame.
Definition at line 527 of file frames.hpp.
Referenced by base_callback(), convert_tree(), KDL::Frame2::Integrate(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), Make4x4(), operator()(), KDL::Segment::twist(), and iTaSC::MovingFrame::updateKinematics().
origine of the Frame
Definition at line 526 of file frames.hpp.
Referenced by base_callback(), convert_tree(), execute_scene(), KDL::Frame2::Integrate(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), Make4x4(), operator()(), KDL::Segment::twist(), iTaSC::MovingFrame::updateJacobian(), and iTaSC::Distance::updateJacobian().