#include <advanced_chainfksolver_recursive.hpp>

Public Member Functions | |
| AdvancedChainFkSolverPos_recursive (const KDL::Chain &chain) | |
| void | dumpAllSegmentPostures () const |
| KDL::Frame | getFrameAtSegment (uint16_t seg_idx) const |
| virtual int | JntToCart (const KDL::JntArray &q_in, KDL::Frame &p_out, int seg_nr=-1) |
| ~AdvancedChainFkSolverPos_recursive () | |
Public Member Functions inherited from KDL::ChainFkSolverPos | |
| virtual int | JntToCart (const JntArray &q_in, std::vector< KDL::Frame > &p_out, int segmentNr=-1)=0 |
| virtual void | updateInternalDataStructures ()=0 |
| virtual | ~ChainFkSolverPos () |
Public Member Functions inherited from KDL::SolverI | |
| virtual int | getError () const |
| SolverI () | |
| virtual const char * | strError (const int error) const |
| virtual | ~SolverI () |
Private Attributes | |
| const KDL::Chain & | chain_ |
| FrameVector_t | segment_pos_ |
Additional Inherited Members | |
Public Attributes inherited from KDL::SolverI | |
| E_DEGRADED | |
| E_MAX_ITERATIONS_EXCEEDED | |
| E_NO_CONVERGE | |
| E_NOERROR | |
| E_NOT_IMPLEMENTED | |
| E_NOT_UP_TO_DATE | |
| E_OUT_OF_RANGE | |
| E_SIZE_MISMATCH | |
| E_SVD_FAILED | |
| E_UNDEFINED | |
Protected Attributes inherited from KDL::SolverI | |
| int | error |
Implementation of a recursive forward position kinematics algorithm to calculate the position transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).
Definition at line 35 of file advanced_chainfksolver_recursive.hpp.
| AdvancedChainFkSolverPos_recursive::AdvancedChainFkSolverPos_recursive | ( | const KDL::Chain & | chain | ) |
Definition at line 21 of file advanced_chainfksolver_recursive.cpp.
| AdvancedChainFkSolverPos_recursive::~AdvancedChainFkSolverPos_recursive | ( | ) |
Definition at line 112 of file advanced_chainfksolver_recursive.cpp.
| void AdvancedChainFkSolverPos_recursive::dumpAllSegmentPostures | ( | ) | const |
Output of all previously set segment positions.
Definition at line 93 of file advanced_chainfksolver_recursive.cpp.
| KDL::Frame AdvancedChainFkSolverPos_recursive::getFrameAtSegment | ( | uint16_t | seg_idx | ) | const |
| seg_idx | Index of the segment starting with 0. |
Access previously set segment positions via index.
Definition at line 78 of file advanced_chainfksolver_recursive.cpp.
|
virtual |
| q_in | Joint states. |
| p_out | The output frame of the given segment or end-effector. |
| seg_nr | The max. segment nr until calculation should stop. |
Calculates the cartesion positions given to the joints array. This special implementation ensures that the positions are stored in a vector so it is not necessary to call the method for each segment again and again.
Implements KDL::ChainFkSolverPos.
Definition at line 31 of file advanced_chainfksolver_recursive.cpp.
|
private |
Definition at line 58 of file advanced_chainfksolver_recursive.hpp.
|
private |
Definition at line 59 of file advanced_chainfksolver_recursive.hpp.