Blender
V3.3
|
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. More... | |
Frame (const Rotation &R) | |
The position matrix defaults to zero. More... | |
void | setValue (float *oglmat) |
void | getValue (float *oglmat) const |
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) |
double | operator() (int i, int j) const |
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 |
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 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) |
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.
Definition at line 526 of file frames.hpp.
Definition at line 409 of file frames.inl.
|
inlineexplicit |
The rotation matrix defaults to identity.
Definition at line 403 of file frames.inl.
|
inlineexplicit |
The position matrix defaults to zero.
Definition at line 397 of file frames.inl.
|
inline |
Definition at line 543 of file frames.hpp.
Referenced by DH(), DH_Craig1989(), Identity(), and Integrate().
|
inline |
The copy constructor. Normal copy by value semantics.
Definition at line 444 of file frames.inl.
Definition at line 70 of file frames.cpp.
References Freestyle::a, KDL::cos(), Frame(), KDL::sin(), and usdtokens::st().
Referenced by KDL::operator>>().
Definition at line 53 of file frames.cpp.
References Freestyle::a, KDL::cos(), Frame(), KDL::sin(), and usdtokens::st().
Definition at line 732 of file frames.inl.
References KDL::Vector::data, float(), KDL::Rotation::getValue(), M, and p.
Referenced by base_callback(), and execute_scene().
|
inlinestatic |
Definition at line 719 of file frames.inl.
References Frame(), KDL::Rotation::Identity(), and KDL::Vector::Zero().
Referenced by KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), KDL::Joint::pose(), and iTaSC::WorldObject::WorldObject().
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 628 of file frames.inl.
References KDL::epsilon, Frame(), M, KDL::Vector::Norm(), p, KDL::Rotation::Rot(), KDL::Twist::rot, and KDL::Twist::vel.
Referenced by iTaSC::MovingFrame::updateKinematics().
|
inline |
Gives back inverse transformation of a Frame.
Definition at line 431 of file frames.inl.
References M.
Referenced by iTaSC::ConstraintSet::closeLoop(), iTaSC::Distance::closeLoop(), and KDL::Vector2::Set3DPlane().
The same as p2=R.Inverse()*p but more efficient.
Definition at line 302 of file frames.inl.
References M, KDL::Twist::rot, and KDL::Twist::vel.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 426 of file frames.inl.
References M.
The same as p2=R.Inverse()*p but more efficient.
Definition at line 185 of file frames.inl.
References KDL::Wrench::force, M, and KDL::Wrench::torque.
|
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 686 of file frames.inl.
References FRAMES_CHECKI, M, and p.
|
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 702 of file frames.inl.
References FRAMES_CHECKI, M, and p.
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 294 of file frames.inl.
References M, KDL::Twist::rot, and KDL::Twist::vel.
Transformation of the base to which the vector is expressed.
Definition at line 421 of file frames.inl.
References M.
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 176 of file frames.inl.
References KDL::Wrench::force, M, and KDL::Wrench::torque.
Definition at line 724 of file frames.inl.
References KDL::Vector::data, M, p, and KDL::Rotation::setValue().
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
The literal inequality operator!=().
The literal equality operator==(), also identical.
Rotation KDL::Frame::M |
Orientation of the Frame.
Definition at line 529 of file frames.hpp.
Referenced by base_callback(), convert_tree(), getValue(), Integrate(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), Make4x4(), operator()(), KDL::FrameAcc::operator=(), operator=(), KDL::FrameVel::operator=(), setValue(), KDL::Segment::twist(), and iTaSC::MovingFrame::updateKinematics().
Vector KDL::Frame::p |
origine of the Frame
Definition at line 528 of file frames.hpp.
Referenced by base_callback(), iTaSC::ConstraintSet::closeLoop(), convert_tree(), execute_scene(), iTaSC::Armature::finalize(), getValue(), Integrate(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), Make4x4(), operator()(), KDL::FrameAcc::operator=(), operator=(), KDL::FrameVel::operator=(), setValue(), KDL::Segment::twist(), iTaSC::Distance::updateJacobian(), and iTaSC::MovingFrame::updateJacobian().