|
Blender V5.0
|
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 |
| index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist | |
| 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 |
| 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. | |
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) |
| do not use operator == because the definition of Equal(.,.) is slightly different. It compares whether the 2 arguments are equal in an eps-interval | |
| 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.
Referenced by Equal, and operator+=().
Definition at line 688 of file frames.hpp.
|
inline |
index-based access to components, first vel(0..2), then rot(3..5)
Definition at line 347 of file frames.hpp.
References angle(), and Rotation.
Referenced by operator[](), and operator[]().
|
inline |
index-based access to components, first vel(0..2), then rot(3..5) For use with a const Twist
Definition at line 356 of file frames.hpp.
References angle().
Definition at line 340 of file frames.hpp.
Definition at line 333 of file frames.hpp.
|
inline |
Definition at line 704 of file frames.hpp.
References operator()().
|
inline |
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 323 of file frames.hpp.
References i, rhs, and Rotation.
Referenced by KDL::Jacobian::changeRefPoint, iTaSC::ConstraintSet::closeLoop(), KDL::TreeJntToJacSolver::JntToJac(), KDL::Segment::twist(), KDL::Segment::twist(), and KDL::Segment::twist().
|
inline |
|
inlinestatic |
Definition at line 311 of file frames.hpp.
References Rotation.
Referenced by KDL::Joint::twist().
Definition at line 1053 of file frames.hpp.
References i.
Definition at line 1057 of file frames.hpp.
References rhs.
|
friend |
The literal inequality operator!=().
Definition at line 1380 of file frames.hpp.
Definition at line 366 of file frames.hpp.
Definition at line 371 of file frames.hpp.
Definition at line 382 of file frames.hpp.
Definition at line 393 of file frames.hpp.
References eps, and KDL::epsilon.
Definition at line 387 of file frames.hpp.
Definition at line 376 of file frames.hpp.
The literal equality operator==(), also identical.
Definition at line 1371 of file frames.hpp.
|
friend |
Definition at line 745 of file frames.hpp.
References Rotation.
Referenced by Equal, operator()(), operator*, operator*, operator+=(), operator-=(), RefPoint(), Rotation, and Zero().
|
friend |
Definition at line 1108 of file frames.hpp.
| Vector KDL::Twist::rot |
The rotational velocity of that point.
Definition at line 682 of file frames.hpp.
Referenced by iTaSC::Armature::getMaxEndEffectorChange(), Twist(), and Twist().
| Vector KDL::Twist::vel |
The velocity of that point.
Definition at line 681 of file frames.hpp.
Referenced by iTaSC::Armature::getMaxEndEffectorChange(), Twist(), and Twist().