This class represents an fixed size array containing joint values of a KDL::Chain. More...
#include <jntarray.hpp>
Public Member Functions | |
| unsigned int | columns () const |
| JntArray () | |
| JntArray (unsigned int size) | |
| JntArray (const JntArray &arg) | |
| double | operator() (unsigned int i, unsigned int j=0) const |
| double & | operator() (unsigned int i, unsigned int j=0) |
| JntArray & | operator= (const JntArray &arg) |
| void | resize (unsigned int newSize) |
| unsigned int | rows () const |
| ~JntArray () | |
Public Attributes | |
| Eigen::VectorXd | data |
Friends | |
| void | Add (const JntArray &src1, const JntArray &src2, JntArray &dest) |
| void | Divide (const JntArray &src, const double &factor, JntArray &dest) |
| bool | Equal (const JntArray &src1, const JntArray &src2, double eps) |
| void | Multiply (const JntArray &src, const double &factor, JntArray &dest) |
| void | MultiplyJacobian (const Jacobian &jac, const JntArray &src, Twist &dest) |
| bool | operator== (const JntArray &src1, const JntArray &src2) |
| void | SetToZero (JntArray &array) |
| void | Subtract (const JntArray &src1, const JntArray &src2, JntArray &dest) |
This class represents an fixed size array containing joint values of a KDL::Chain.
class MyTask : public RTT::TaskContext { JntArray j; MyTask() {} // invokes j's default constructor bool configureHook() { unsigned int size = some_property.rvalue(); j.resize(size) ... } void updateHook() { use j here } };
Definition at line 69 of file jntarray.hpp.
Construct with _no_ data array
Definition at line 28 of file jntarray.cpp.
| KDL::JntArray::JntArray | ( | unsigned int | size | ) | [explicit] |
Constructor of the joint array
| size | size of the array, this cannot be changed afterwards. |
Definition at line 32 of file jntarray.cpp.
| KDL::JntArray::JntArray | ( | const JntArray & | arg | ) |
Copy constructor
Definition at line 39 of file jntarray.cpp.
Definition at line 51 of file jntarray.cpp.
| unsigned int KDL::JntArray::columns | ( | ) | const |
Returns the number of columns of the array, always 1.
Definition at line 77 of file jntarray.cpp.
| double KDL::JntArray::operator() | ( | unsigned int | i, |
| unsigned int | j = 0 |
||
| ) | const |
get_item operator for the joint array, if a second value is given it should be zero, since a JntArray resembles a column.
Definition at line 60 of file jntarray.cpp.
| double & KDL::JntArray::operator() | ( | unsigned int | i, |
| unsigned int | j = 0 |
||
| ) |
set_item operator, again if a second value is given it should be zero.
Definition at line 66 of file jntarray.cpp.
Definition at line 44 of file jntarray.cpp.
| void KDL::JntArray::resize | ( | unsigned int | newSize | ) |
Resize the array
Definition at line 55 of file jntarray.cpp.
| unsigned int KDL::JntArray::rows | ( | ) | const |
Returns the number of rows (size) of the array
Definition at line 72 of file jntarray.cpp.
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 82 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 97 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 113 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 92 of file jntarray.cpp.
| void MultiplyJacobian | ( | const Jacobian & | jac, |
| const JntArray & | src, | ||
| Twist & | dest | ||
| ) | [friend] |
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 102 of file jntarray.cpp.
Definition at line 120 of file jntarray.cpp.
Function to set all the values of the array to 0
| array |
Definition at line 108 of file jntarray.cpp.
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 87 of file jntarray.cpp.
| Eigen::VectorXd KDL::JntArray::data |
Definition at line 72 of file jntarray.hpp.