KDL 1.5.1
|
#include <src/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. | |
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. | |
Twist | operator* (const Twist &arg) const |
Transformation of both the velocity reference point and of 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. | |
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) |
do not use operator == because the definition of Equal(.,.) is slightly different. | |
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!=(). | |
\brief 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 |
Referenced by DH(), DH_Craig1989(), Identity(), and Integrate().
|
inline |
The copy constructor. Normal copy by value semantics.
|
static |
References Frame().
Referenced by KDL::operator>>().
|
static |
References Frame().
|
inlinestatic |
References Frame(), KDL::Rotation::Identity(), and KDL::Vector::Zero().
Referenced by KDL::ChainIkSolverPos_LMA::compute_fwdpos(), KDL::ChainHdSolver_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.
References Frame(), M, KDL::Vector::Norm(), p, KDL::Rotation::Rot(), KDL::Twist::rot, and KDL::Twist::vel.
|
inline |
Gives back inverse transformation of a Frame.
Referenced by KDL::ChainHdSolver_Vereshchagin::final_upwards_sweep(), KDL::Tree::getChain(), KDL::ChainHdSolver_Vereshchagin::initial_upwards_sweep(), KDL::Vector2::Set3DPlane(), and KDL::Segment::setFrameToTip().
The same as p2=R.Inverse()*p but more efficient.
References KDL::Twist::rot, and KDL::Twist::vel.
The same as p2=R.Inverse()*p but more efficient.
The same as p2=R.Inverse()*p but more efficient.
References KDL::Wrench::force, and KDL::Wrench::torque.
|
inline |
|
inline |
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
References KDL::Twist::rot, and KDL::Twist::vel.
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
References KDL::Wrench::force, and KDL::Wrench::torque.
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.
Referenced by KDL::Path_Circle::Acc(), KDL::Path_RoundedComposite::Add(), KDL::Path_Circle::Clone(), KDL::ChainHdSolver_Vereshchagin::downwards_sweep(), KDL::Tree::getChain(), KDL::ChainHdSolver_Vereshchagin::initial_upwards_sweep(), Integrate(), KDL::ChainExternalWrenchEstimator::JntToExtWrench(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::ChainDynParam::JntToMass(), KDL::Joint::Joint(), KDL::Joint::Joint(), Make4x4(), operator()(), operator()(), KDL::operator<<(), KDL::FrameAcc::operator=(), operator=(), KDL::FrameVel::operator=(), KDL::operator>>(), KDL::Path_Circle::Path_Circle(), KDL::Path_Line::Path_Line(), 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(), Integrate(), KDL::TreeJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::Joint::Joint(), KDL::Joint::Joint(), Make4x4(), operator()(), operator()(), KDL::operator<<(), KDL::FrameAcc::operator=(), operator=(), KDL::FrameVel::operator=(), KDL::operator>>(), KDL::Path_Circle::Path_Circle(), KDL::Segment::twist(), and KDL::Path_Circle::Write().