|
Blender V5.0
|
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) |
| 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) 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. | |
| 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 |
| Transformation of the base to which the vector 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. look at Rotation*Wrench operator for a transformation of only the base to which the twist is expressed. | |
| Twist | operator* (const Twist &arg) const |
| 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. | |
| void | Integrate (const Twist &t_this, double frequency) |
| 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. | |
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) |
| 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) |
| 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 526 of file frames.hpp.
Definition at line 410 of file frames.hpp.
References beta().
Referenced by DH(), and DH_Craig1989().
|
inlineexplicit |
The rotation matrix defaults to identity.
Definition at line 404 of file frames.hpp.
|
inlineexplicit |
The position matrix defaults to zero.
Definition at line 398 of file frames.hpp.
|
inline |
Definition at line 543 of file frames.hpp.
Referenced by DH(), and DH_Craig1989().
|
inline |
The copy constructor. Normal copy by value semantics.
Definition at line 445 of file frames.hpp.
|
static |
Definition at line 70 of file frames.cpp.
References cos, Frame(), Frame(), and sin.
Referenced by KDL::operator>>().
|
static |
|
inline |
Definition at line 733 of file frames.hpp.
Referenced by base_callback(), and execute_scene().
|
inlinestatic |
Definition at line 720 of file frames.hpp.
Referenced by KDL::Segment::Chain, KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Joint::pose().
|
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 629 of file frames.hpp.
|
inline |
Gives back inverse transformation of a Frame.
Definition at line 432 of file frames.hpp.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 303 of file frames.hpp.
References KDL::Rotation::Identity().
The same as p2=R.Inverse()*p but more efficient.
Definition at line 427 of file frames.hpp.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 186 of file frames.hpp.
| void Frame::Make4x4 | ( | double * | d | ) |
|
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 687 of file frames.hpp.
|
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 703 of file frames.hpp.
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 295 of file frames.hpp.
Transformation of the base to which the vector is expressed.
Definition at line 422 of file frames.hpp.
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 177 of file frames.hpp.
Normal copy-by-value semantics.
Definition at line 438 of file frames.hpp.
|
inline |
Definition at line 725 of file frames.hpp.
Referenced by base_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
Definition at line 1076 of file frames.hpp.
References KDL::epsilon.
The literal inequality operator!=().
Definition at line 1353 of file frames.hpp.
Composition of two frames.
Definition at line 416 of file frames.hpp.
The literal equality operator==(), also identical.
Definition at line 1344 of file frames.hpp.
| Rotation KDL::Frame::M |
Orientation of the Frame.
Definition at line 529 of file frames.hpp.
Referenced by base_callback(), convert_tree(), KDL::TreeJntToJacSolver::JntToJac(), Make4x4(), and KDL::Segment::twist().
| Vector KDL::Frame::p |
origine of the Frame
Definition at line 528 of file frames.hpp.
Referenced by base_callback(), convert_tree(), execute_scene(), iTaSC::Armature::finalize(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), Make4x4(), and KDL::Segment::twist().