Blender
V3.3
|
#include <jntarray.hpp>
Public Member Functions | |
JntArray () | |
JntArray (unsigned int size) | |
JntArray (const JntArray &arg) | |
~JntArray () | |
void | resize (unsigned int newSize) |
JntArray & | operator= (const JntArray &arg) |
double | operator[] (unsigned int i) const |
double & | operator[] (unsigned int i) |
double * | operator() (unsigned int i) |
unsigned int | rows () const |
unsigned int | columns () const |
Friends | |
void | Add (const JntArray &src1, const JntArray &src2, JntArray &dest) |
void | Subtract (const JntArray &src1, const JntArray &src2, JntArray &dest) |
void | Multiply (const JntArray &src, const double &factor, JntArray &dest) |
void | Divide (const JntArray &src, const double &factor, JntArray &dest) |
void | MultiplyJacobian (const Jacobian &jac, const JntArray &src, Twist &dest) |
void | SetToZero (JntArray &array) |
bool | Equal (const JntArray &src1, const JntArray &src2, double eps) |
bool | operator== (const JntArray &src1, const JntArray &src2) |
@brief This class represents an fixed size array containing joint values of a KDL::Chain. \warning An object constructed with the default constructor provides a valid, but inert, object. Many of the member functions will do the correct thing and have no affect on this object, but some member functions can _NOT_ deal with an inert/empty object. These functions will assert() and exit the program instead. The intended use case for the default constructor (in an RTT/OCL setting) is outlined in code below - the default constructor plus the resize() function allow use of JntArray objects whose size is set within a configureHook() call (typically based on a size determined from a property).
Definition at line 67 of file jntarray.hpp.
KDL::JntArray::JntArray | ( | ) |
Construct with no data array
Definition at line 29 of file jntarray.cpp.
KDL::JntArray::JntArray | ( | unsigned int | size | ) |
Constructor of the joint array
size | size of the array, this cannot be changed afterwards. |
Definition at line 35 of file jntarray.cpp.
References SetToZero.
KDL::JntArray::JntArray | ( | const JntArray & | arg | ) |
Copy constructor
Definition at line 44 of file jntarray.cpp.
References NULL.
KDL::JntArray::~JntArray | ( | ) |
Definition at line 61 of file jntarray.cpp.
unsigned int KDL::JntArray::columns | ( | ) | const |
Returns the number of columns of the array, always 1.
Definition at line 98 of file jntarray.cpp.
double * KDL::JntArray::operator() | ( | unsigned int | i | ) |
access operator for the joint array. Use pointer here to allow access to sequential joint angles (required for ndof joints)
Definition at line 86 of file jntarray.cpp.
References NULL.
Definition at line 52 of file jntarray.cpp.
double & KDL::JntArray::operator[] | ( | unsigned int | i | ) |
set_item operator
Definition at line 80 of file jntarray.cpp.
double KDL::JntArray::operator[] | ( | unsigned int | i | ) | const |
get_item operator for the joint array
Definition at line 74 of file jntarray.cpp.
void KDL::JntArray::resize | ( | unsigned int | newSize | ) |
Resize the array
Definition at line 66 of file jntarray.cpp.
References SetToZero.
Referenced by convert_channels(), and iTaSC::Armature::finalize().
unsigned int KDL::JntArray::rows | ( | ) | const |
Returns the number of rows (size) of the array
Definition at line 93 of file jntarray.cpp.
Referenced by iTaSC::Armature::initCache(), KDL::JntArrayAcc::JntArrayAcc(), KDL::JntArrayVel::JntArrayVel(), KDL::TreeFkSolverPos_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::TreeJntToJacSolver::JntToJac(), iTaSC::Armature::setJointArray(), iTaSC::Armature::updateControlOutput(), and iTaSC::Armature::updateKinematics().
Function to add two joint arrays, all the arguments must have the same size: A + B = C. This function is aliasing-safe, A or B can be the same array as C.
src1 | A |
src2 | B |
dest | C |
Definition at line 103 of file jntarray.cpp.
Function to divide all the array values with a scalar factor: A/b=C. This function is aliasing-safe, A can be the same array as C.
src | A |
factor | b |
dest | C |
Definition at line 124 of file jntarray.cpp.
Function to check if two arrays are the same with a precision of eps
src1 | |
src2 | |
eps | default: epsilon |
Definition at line 146 of file jntarray.cpp.
Function to multiply all the array values with a scalar factor: A*b=C. This function is aliasing-safe, A can be the same array as C.
src | A |
factor | b |
dest | C |
Definition at line 117 of file jntarray.cpp.
Function to multiply a KDL::Jacobian with a KDL::JntArray to get a KDL::Twist, it should not be used to calculate the forward velocity kinematics, the solver classes are built for this purpose. J*q = t
jac | J |
src | q |
dest | t |
Definition at line 131 of file jntarray.cpp.
Definition at line 155 of file jntarray.cpp.
Function to set all the values of the array to 0
array |
Definition at line 140 of file jntarray.cpp.
Referenced by JntArray(), and resize().
Function to subtract two joint arrays, all the arguments must have the same size: A - B = C. This function is aliasing-safe, A or B can be the same array as C.
src1 | A |
src2 | B |
dest | C |
Definition at line 110 of file jntarray.cpp.