Public Member Functions | Public Attributes | Friends | List of all members
KDL::JntArray Class Reference

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)
 
JntArrayoperator= (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)
 

Detailed Description

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).
class MyTask : public RTT::TaskContext
{
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.

Constructor & Destructor Documentation

◆ JntArray() [1/3]

KDL::JntArray::JntArray ( )

Construct with no data array

Postcondition
NULL == data
0 == rows()
Warning
use of an object constructed like this, without a resize() first, may result in program exit! See class documentation.

Definition at line 26 of file jntarray.cpp.

◆ JntArray() [2/3]

KDL::JntArray::JntArray ( unsigned int  size)
explicit

Constructor of the joint array

Parameters
sizesize of the array, this cannot be changed afterwards.
Precondition
0 < size
Postcondition
NULL != data
0 < rows()
all elements in data have 0 value

Definition at line 30 of file jntarray.cpp.

◆ JntArray() [3/3]

KDL::JntArray::JntArray ( const JntArray arg)

Copy constructor

Note
Will correctly copy an empty object

Definition at line 37 of file jntarray.cpp.

◆ ~JntArray()

KDL::JntArray::~JntArray ( )

Definition at line 49 of file jntarray.cpp.

Member Function Documentation

◆ columns()

unsigned int KDL::JntArray::columns ( ) const

Returns the number of columns of the array, always 1.

Definition at line 75 of file jntarray.cpp.

◆ operator()() [1/2]

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.

Returns
the joint value at position i, starting from 0
Precondition
0 != size (ie non-default constructor or resize() called)

Definition at line 58 of file jntarray.cpp.

◆ operator()() [2/2]

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.

Returns
reference to the joint value at position i,starting from zero.
Precondition
0 != size (ie non-default constructor or resize() called)

Definition at line 64 of file jntarray.cpp.

◆ operator=()

JntArray & KDL::JntArray::operator= ( const JntArray arg)

Definition at line 42 of file jntarray.cpp.

◆ resize()

void KDL::JntArray::resize ( unsigned int  newSize)

Resize the array

Warning
This causes a dynamic allocation (and potentially also a dynamic deallocation). This will negatively affect real-time performance!
Postcondition
newSize == rows()
NULL != data
all elements in data have 0 value

Definition at line 53 of file jntarray.cpp.

◆ rows()

unsigned int KDL::JntArray::rows ( ) const

Returns the number of rows (size) of the array

Definition at line 70 of file jntarray.cpp.

Friends And Related Function Documentation

◆ Add

void Add ( const JntArray src1,
const JntArray src2,
JntArray dest 
)
friend

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.

Parameters
src1A
src2B
destC

Definition at line 80 of file jntarray.cpp.

◆ Divide

void Divide ( const JntArray src,
const double &  factor,
JntArray dest 
)
friend

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.

Parameters
srcA
factorb
destC

Definition at line 95 of file jntarray.cpp.

◆ Equal

bool Equal ( const JntArray src1,
const JntArray src2,
double  eps 
)
friend

Function to check if two arrays are the same with a precision of eps

Parameters
src1
src2
epsdefault: epsilon
Returns
true if each element of src1 is within eps of the same element in src2, or if both src1 and src2 have no data (ie 0==rows())

Definition at line 111 of file jntarray.cpp.

◆ Multiply

void Multiply ( const JntArray src,
const double &  factor,
JntArray dest 
)
friend

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.

Parameters
srcA
factorb
destC

Definition at line 90 of file jntarray.cpp.

◆ MultiplyJacobian

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

Parameters
jacJ
srcq
destt
Postcondition
dest==Twist::Zero() if 0==src.rows() (ie src is empty)

Definition at line 100 of file jntarray.cpp.

◆ operator==

bool operator== ( const JntArray src1,
const JntArray src2 
)
friend

Definition at line 118 of file jntarray.cpp.

◆ SetToZero

void SetToZero ( JntArray array)
friend

Function to set all the values of the array to 0

Parameters
array

Definition at line 106 of file jntarray.cpp.

◆ Subtract

void Subtract ( const JntArray src1,
const JntArray src2,
JntArray dest 
)
friend

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.

Parameters
src1A
src2B
destC

Definition at line 85 of file jntarray.cpp.

Member Data Documentation

◆ data

Eigen::VectorXd KDL::JntArray::data

Definition at line 72 of file jntarray.hpp.


The documentation for this class was generated from the following files:


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:15