kinematics-dynamics
Public Member Functions | Static Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes | List of all members
roboticslab::ChainFkSolverPos_ST Class Reference

FK solver using Screw Theory. More...

#include <ChainFkSolverPos_ST.hpp>

Inheritance diagram for roboticslab::ChainFkSolverPos_ST:

Public Member Functions

int JntToCart (const KDL::JntArray &q_in, KDL::Frame &p_out, int segmentNr=-1) override
 Perform FK on the selected segment. More...
 
int JntToCart (const KDL::JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1) override
 Perform FK on the selected segments (unsupported) More...
 
void updateInternalDataStructures () override
 Update the internal data structures. More...
 
const char * strError (const int error) const override
 Return a description of the last error. More...
 

Static Public Member Functions

static KDL::ChainFkSolverPos * create (const KDL::Chain &chain)
 Create an instance of ChainFkSolverPos_ST. More...
 

Static Public Attributes

static const int E_OPERATION_NOT_SUPPORTED = -100
 Return code, operation not supported.
 
static const int E_ILLEGAL_ARGUMENT_SIZE = -101
 Return code, input vector size does not match expected output vector size.
 

Private Member Functions

 ChainFkSolverPos_ST (const KDL::Chain &chain)
 

Private Attributes

const KDL::Chain & chain
 
PoeExpression poe
 

Detailed Description

Implementation of a forward position kinematics algorithm. This is a thin wrapper around PoeExpression. Methods that retrieve resulting frames for intermediate links are not supported.

Member Function Documentation

◆ create()

KDL::ChainFkSolverPos * ChainFkSolverPos_ST::create ( const KDL::Chain &  chain)
static
Parameters
chainInput kinematic chain.
Returns
Solver instance.

◆ JntToCart() [1/2]

int ChainFkSolverPos_ST::JntToCart ( const KDL::JntArray &  q_in,
KDL::Frame &  p_out,
int  segmentNr = -1 
)
override
Parameters
q_inInput joint coordinates.
p_outReference to output cartesian pose.
segmentNrDesired segment frame (unsupported).
Returns
Return code, < 0 if something went wrong.

◆ JntToCart() [2/2]

int ChainFkSolverPos_ST::JntToCart ( const KDL::JntArray &  q_in,
std::vector< KDL::Frame > &  p_out,
int  segmentNr = -1 
)
override
Parameters
q_inInput joint coordinates.
p_outReference to a vector of output cartesian poses for all segments.
segmentNrLast selected segment frame.
Returns
Return code, < 0 if something went wrong.
Warning
Unsupported, will return E_OPERATION_NOT_SUPPORTED.

◆ strError()

const char * ChainFkSolverPos_ST::strError ( const int  error) const
override
Parameters
errorError code.
Returns
If error is known then a description of error, otherwise "UNKNOWN ERROR".

◆ updateInternalDataStructures()

void ChainFkSolverPos_ST::updateInternalDataStructures ( )
override

Update the internal data structures. This is required if the number of segments or number of joints of a chain has changed. This provides a single point of contact for solver memory allocations.


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