KDL
1.4.0
|
represents both translational and rotational velocities. More...
#include <src/frames.hpp>
Public Member Functions | |
Twist () | |
The default constructor initialises to Zero via the constructor of Vector. More... | |
Twist (const Vector &_vel, const Vector &_rot) | |
Twist & | operator-= (const Twist &arg) |
Twist & | operator+= (const Twist &arg) |
double & | operator() (int i) |
index-based access to components, first vel(0..2), then rot(3..5) More... | |
double | operator() (int i) const |
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist More... | |
double | operator[] (int index) const |
double & | operator[] (int index) |
void | ReverseSign () |
Reverses the sign of the twist. More... | |
Twist | RefPoint (const Vector &v_base_AB) const |
Changes the reference point of the twist. More... | |
Static Public Member Functions | |
static Twist | Zero () |
Public Attributes | |
Vector | vel |
The velocity of that point. More... | |
Vector | rot |
The rotational velocity of that point. More... | |
Friends | |
class | Rotation |
class | Frame |
Twist | operator* (const Twist &lhs, double rhs) |
Twist | operator* (double lhs, const Twist &rhs) |
Twist | operator/ (const Twist &lhs, double rhs) |
Twist | operator+ (const Twist &lhs, const Twist &rhs) |
Twist | operator- (const Twist &lhs, const Twist &rhs) |
Twist | operator- (const Twist &arg) |
double | dot (const Twist &lhs, const Wrench &rhs) |
double | dot (const Wrench &rhs, const Twist &lhs) |
void | SetToZero (Twist &v) |
Twist | operator* (const Twist &lhs, const Twist &rhs) |
Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point. More... | |
Wrench | operator* (const Twist &lhs, const Wrench &rhs) |
Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point. More... | |
bool | Equal (const Twist &a, const Twist &b, double eps) |
do not use operator == because the definition of Equal(.,.) is slightly different. More... | |
bool | operator== (const Twist &a, const Twist &b) |
The literal equality operator==(), also identical. More... | |
bool | operator!= (const Twist &a, const Twist &b) |
The literal inequality operator!=(). More... | |
represents both translational and rotational velocities.
This class represents a twist. A twist is the combination of translational velocity and rotational velocity applied at one point.
|
inline |
The default constructor initialises to Zero via the constructor of Vector.
References KDL::Vector::operator()(), KDL::Vector::operator+=(), and KDL::Vector::operator-=().
|
inline |
index-based access to components, first vel(0..2), then rot(3..5)
|
inline |
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist
|
inline |
|
inline |
Changes the reference point of the twist.
The vector v_base_AB is expressed in the same base as the twist The vector v_base_AB is a vector from the old point to the new point.
Complexity : 6M+6A
Referenced by KDL::Jacobian::changeRefPoint(), KDL::changeRefPoint(), KDL::TreeJntToJacSolver::JntToJac(), and KDL::Segment::twist().
|
inline |
Reverses the sign of the twist.
|
inlinestatic |
Referenced by KDL::Trajectory_Stationary::Acc(), KDL::Path_Point::Acc(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::TreeIkSolverPos_NR_JL::TreeIkSolverPos_NR_JL(), KDL::TreeIkSolverPos_Online::TreeIkSolverPos_Online(), KDL::Joint::twist(), KDL::Trajectory_Stationary::Vel(), and KDL::Path_Point::Vel().
do not use operator == because the definition of Equal(.,.) is slightly different.
It compares whether the 2 arguments are equal in an eps-interval
|
friend |
The literal inequality operator!=().
Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point.
Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point.
The literal equality operator==(), also identical.
|
friend |
|
friend |
Vector KDL::Twist::rot |
The rotational velocity of that point.
Referenced by KDL::ChainIdSolver_Vereshchagin::constraint_calculation(), KDL::ChainIdSolver_Vereshchagin::downwards_sweep(), KDL::TreeIkSolverPos_Online::enforceCartVelLimits(), KDL::ChainJntToJacDotSolver::getPartialDerivativeBodyFixed(), KDL::ChainJntToJacDotSolver::getPartialDerivativeHybrid(), KDL::ChainJntToJacDotSolver::getPartialDerivativeInertial(), KDL::operator*(), KDL::operator<<(), KDL::operator>>(), KDL::Path_Line::Path_Line(), KDL::Jacobian::setColumn(), and KDL::Twist_to_Eigen().
Vector KDL::Twist::vel |
The velocity of that point.
Referenced by KDL::ChainIdSolver_Vereshchagin::constraint_calculation(), KDL::ChainIdSolver_Vereshchagin::downwards_sweep(), KDL::TreeIkSolverPos_Online::enforceCartVelLimits(), KDL::ChainJntToJacDotSolver::getPartialDerivativeBodyFixed(), KDL::ChainJntToJacDotSolver::getPartialDerivativeHybrid(), KDL::ChainJntToJacDotSolver::getPartialDerivativeInertial(), KDL::operator*(), KDL::operator<<(), KDL::operator>>(), KDL::Path_Line::Path_Line(), KDL::Jacobian::setColumn(), and KDL::Twist_to_Eigen().