KDL
1.4.0
|
represents a frame transformation in 3D space (rotation + translation) More...
#include <src/frames.hpp>
Public Member Functions | |
Frame (const Rotation &R, const Vector &V) | |
Frame (const Vector &V) | |
The rotation matrix defaults to identity. More... | |
Frame (const Rotation &R) | |
The position matrix defaults to zero. More... | |
Frame () | |
Frame (const Frame &arg) | |
The copy constructor. Normal copy by value semantics. More... | |
void | Make4x4 (double *d) |
Reads data from an double array. More... | |
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. More... | |
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. More... | |
Frame | Inverse () const |
Gives back inverse transformation of a Frame. 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... | |
Twist | Inverse (const Twist &arg) const |
The same as p2=R.Inverse()*p but more efficient. More... | |
Frame & | operator= (const Frame &arg) |
Normal copy-by-value semantics. More... | |
Vector | operator* (const Vector &arg) const |
Transformation of the base to which the vector is expressed. More... | |
Wrench | operator* (const Wrench &arg) const |
Transformation of both the force reference point and of the base to which the wrench is expressed. More... | |
Twist | operator* (const Twist &arg) const |
Transformation of both the velocity reference point and of the base to which the twist is expressed. More... | |
void | Integrate (const Twist &t_this, double frequency) |
The twist <t_this> is expressed wrt the current frame. More... | |
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 More... | |
Rotation | M |
Orientation of the Frame. More... | |
Friends | |
Frame | operator* (const Frame &lhs, const Frame &rhs) |
Composition of two frames. More... | |
bool | Equal (const Frame &a, const Frame &b, double eps) |
do not use operator == because the definition of Equal(.,.) is slightly different. More... | |
bool | operator== (const Frame &a, const Frame &b) |
The literal equality operator==(), also identical. More... | |
bool | operator!= (const Frame &a, const Frame &b) |
The literal inequality operator!=(). 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.
|
inlineexplicit |
The rotation matrix defaults to identity.
|
inlineexplicit |
The position matrix defaults to zero.
|
inline |
References KDL::Vector::Frame, and KDL::Vector::operator()().
Referenced by DH(), and DH_Craig1989().
|
inline |
The copy constructor. Normal copy by value semantics.
|
static |
References Frame().
Referenced by KDL::operator>>().
|
static |
References Frame().
|
inlinestatic |
Referenced by KDL::ChainIkSolverPos_LMA::compute_fwdpos(), KDL::ChainIdSolver_Vereshchagin::initial_upwards_sweep(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), KDL::Joint::pose(), KDL::TreeIkSolverPos_NR_JL::TreeIkSolverPos_NR_JL(), and KDL::TreeIkSolverPos_Online::TreeIkSolverPos_Online().
|
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.
|
inline |
Gives back inverse transformation of a Frame.
Referenced by KDL::ChainIdSolver_Vereshchagin::final_upwards_sweep(), KDL::Tree::getChain(), KDL::ChainIdSolver_Vereshchagin::initial_upwards_sweep(), KDL::operator*(), and KDL::Segment::setFrameToTip().
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.
|
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.
|
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
do not use operator == because the definition of Equal(.,.) is slightly different.
It compares whether the 2 arguments are equal in an eps-interval
Referenced by KDL::Equal(), and KDL::operator==().
The literal inequality operator!=().
The literal equality operator==(), also identical.
Rotation KDL::Frame::M |
Orientation of the Frame.
Referenced by KDL::Path_Circle::Acc(), KDL::Path_RoundedComposite::Add(), KDL::Path_Circle::Clone(), KDL::ChainIdSolver_Vereshchagin::downwards_sweep(), KDL::Tree::getChain(), KDL::ChainIdSolver_Vereshchagin::initial_upwards_sweep(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::Joint::Joint(), Make4x4(), KDL::operator*(), KDL::operator<<(), KDL::operator>>(), KDL::Path_Circle::Path_Circle(), KDL::Path_Line::Path_Line(), KDL::Joint::pose(), KDL::Segment::twist(), KDL::Path_Circle::Vel(), and KDL::Path_Circle::Write().
Vector KDL::Frame::p |
origine of the Frame
Referenced by KDL::Path_RoundedComposite::Add(), KDL::Path_Circle::Clone(), KDL::ChainIkSolverPos_LMA::compute_jacobian(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::Joint::Joint(), Make4x4(), KDL::operator*(), KDL::operator<<(), KDL::operator>>(), KDL::Path_Circle::Path_Circle(), KDL::Segment::twist(), and KDL::Path_Circle::Write().