|
Blender V4.3
|
represents both translational and rotational velocities. More...
#include <frames.hpp>
Public Member Functions | |
| Twist () | |
| The default constructor initialises to Zero via the constructor of Vector. | |
| 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) | |
| double | operator() (int i) const |
| double | operator[] (int index) const |
| double & | operator[] (int index) |
| void | ReverseSign () |
| Reverses the sign of the twist. | |
| Twist | RefPoint (const Vector &v_base_AB) const |
Static Public Member Functions | |
| static Twist | Zero () |
Public Attributes | |
| Vector | vel |
| The velocity of that point. | |
| Vector | rot |
| The rotational velocity of that point. | |
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) |
| bool | Equal (const Twist &a, const Twist &b, double eps=epsilon) |
| bool | operator== (const Twist &a, const Twist &b) |
| The literal equality operator==(), also identical. | |
| bool | operator!= (const Twist &a, const Twist &b) |
| The literal inequality operator!=(). | |
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.
Definition at line 679 of file frames.hpp.
|
inline |
The default constructor initialises to Zero via the constructor of Vector.
Definition at line 686 of file frames.hpp.
Definition at line 688 of file frames.hpp.
index-based access to components, first vel(0..2), then rot(3..5)
Definition at line 346 of file frames.inl.
References rot.
Referenced by operator[](), and operator[]().
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist
Definition at line 355 of file frames.inl.
References rot.
Definition at line 339 of file frames.inl.
Definition at line 332 of file frames.inl.
Definition at line 704 of file frames.hpp.
References operator()().
Definition at line 699 of file frames.hpp.
References operator()().
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
Definition at line 322 of file frames.inl.
References rot.
Referenced by iTaSC::ConstraintSet::closeLoop(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), KDL::Segment::twist(), KDL::Segment::twist(), and KDL::Segment::twist().
|
inline |
|
inlinestatic |
Definition at line 310 of file frames.inl.
Referenced by KDL::Joint::twist(), and iTaSC::MovingFrame::updateCoordinates().
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 |
Definition at line 746 of file frames.hpp.
The literal inequality operator!=().
The literal equality operator==(), also identical.
|
friend |
Definition at line 745 of file frames.hpp.
|
friend |
| Vector KDL::Twist::rot |
The rotational velocity of that point.
Definition at line 682 of file frames.hpp.
Referenced by KDL::Frame::Integrate(), KDL::Frame::Inverse(), KDL::FrameAcc::Inverse(), KDL::FrameVel::Inverse(), KDL::Rotation::Inverse(), KDL::RotationAcc::Inverse(), KDL::RotationVel::Inverse(), KDL::Frame::operator*(), KDL::FrameAcc::operator*(), KDL::FrameVel::operator*(), KDL::RotationAcc::operator*(), KDL::RotationVel::operator*(), operator+=(), and operator-=().
| Vector KDL::Twist::vel |
The velocity of that point.
Definition at line 681 of file frames.hpp.
Referenced by KDL::Frame::Integrate(), KDL::Frame::Inverse(), KDL::FrameAcc::Inverse(), KDL::FrameVel::Inverse(), KDL::Rotation::Inverse(), KDL::RotationAcc::Inverse(), KDL::RotationVel::Inverse(), KDL::Frame::operator*(), KDL::FrameAcc::operator*(), KDL::FrameVel::operator*(), KDL::RotationAcc::operator*(), KDL::RotationVel::operator*(), operator+=(), and operator-=().