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

IK solver using Screw Theory. More...

#include <ChainIkSolverPos_ST.hpp>

Inheritance diagram for roboticslab::ChainIkSolverPos_ST:

Public Member Functions

virtual ~ChainIkSolverPos_ST ()
 Destructor.
 
int CartToJnt (const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
 Calculate inverse position kinematics. 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::ChainIkSolverPos * create (const KDL::Chain &chain, const ConfigurationSelectorFactory &configFactory)
 Create an instance of ChainIkSolverPos_ST. More...
 

Static Public Attributes

static const int E_SOLUTION_NOT_FOUND = -100
 Return code, IK solution not found.
 
static const int E_OUT_OF_LIMITS = -101
 Return code, target pose out of robot limits.
 
static const int E_NOT_REACHABLE = 100
 Return code, solution out of reach.
 

Private Member Functions

 ChainIkSolverPos_ST (const KDL::Chain &chain, ScrewTheoryIkProblem *problem, ConfigurationSelector *config)
 

Private Attributes

const KDL::Chain & chain
 
ScrewTheoryIkProblemproblem
 
ConfigurationSelectorconfig
 

Detailed Description

Implementation of an inverse position kinematics algorithm. This is a thin wrapper around ScrewTheoryIkProblem. Non-exhaustive tests on TEO's (UC3M) right arm kinematic chain reveal that this is 5-10 faster than a numeric Newton-Raphson solver as provided by KDL (e.g. KDL::ChainIkSolverPos_NR_JL).

Member Function Documentation

◆ CartToJnt()

int ChainIkSolverPos_ST::CartToJnt ( const KDL::JntArray &  q_init,
const KDL::Frame &  p_in,
KDL::JntArray &  q_out 
)
override
Parameters
q_initInitial guess of the joint coordinates (unused).
p_inInput cartesian coordinates.
q_outOutput joint coordinates.
Returns
Return code, E_SOLUTION_NOT_FOUND if there is no solution or E_NOT_REACHABLE if at least one of them is out of reach.

◆ create()

KDL::ChainIkSolverPos * ChainIkSolverPos_ST::create ( const KDL::Chain &  chain,
const ConfigurationSelectorFactory configFactory 
)
static
Parameters
chainInput kinematic chain.
configFactoryInstance of an abstract factory class that instantiates a ConfigurationSelector.
Returns
Solver instance or null if no solution was found.

◆ strError()

const char * ChainIkSolverPos_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 ChainIkSolverPos_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: