| orocos_kdl
    | 
This abstract class encapsulates a solver for the forward acceleration kinematics for a KDL::Chain. More...
#include <chainfksolver.hpp>

| Public Member Functions | |
| virtual int | JntToCart (const JntArrayAcc &q_in, FrameAcc &out, int segmentNr=-1)=0 | 
| virtual int | JntToCart (const JntArrayAcc &q_in, std::vector< FrameAcc > &out, int segmentNr=-1)=0 | 
| virtual void | updateInternalDataStructures ()=0 | 
| virtual | ~ChainFkSolverAcc ()=0 | 
|  Public Member Functions inherited from KDL::SolverI | |
| virtual int | getError () const | 
| Return the latest error.  More... | |
| SolverI () | |
| Initialize latest error to E_NOERROR.  More... | |
| virtual const char * | strError (const int error) const | 
| virtual | ~SolverI () | 
| Additional Inherited Members | |
|  Public Types inherited from KDL::SolverI | |
| enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2, E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6, E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8 } | 
|  Protected Attributes inherited from KDL::SolverI | |
| int | error | 
| Latest error, initialized to E_NOERROR in constructor.  More... | |
This abstract class encapsulates a solver for the forward acceleration kinematics for a KDL::Chain.
Definition at line 107 of file chainfksolver.hpp.
| 
 | pure virtual | 
| 
 | pure virtual | 
Calculate forward position, velocity and acceleration kinematics, from joint coordinates to cartesian coordinates
| q_in | input joint coordinates (position, velocity and acceleration | 
| out | output cartesian coordinates (position, velocity and acceleration | 
| 
 | pure virtual | 
Calculate forward position, velocity and acceleration kinematics, from joint coordinates to cartesian coordinates
| q_in | input joint coordinates (position, velocity and acceleration | 
| out | output cartesian coordinates (position, velocity and acceleration for all segments | 
| 
 | pure virtual | 
Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.
Implements KDL::SolverI.
 1.8.17
 1.8.17