KDL
1.3.0
|
This abstract class encapsulates a solver for the forward acceleration kinematics for a KDL::Chain. More...
#include <src/chainfksolver.hpp>
Public Types | |
enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2 } |
Public Member Functions | |
virtual int | JntToCart (const JntArrayAcc &q_in, FrameAcc &out, int segmentNr=-1)=0 |
Calculate forward position, velocity and accelaration kinematics, from joint coordinates to cartesian coordinates. More... | |
virtual | ~ChainFkSolverAcc ()=0 |
virtual int | getError () const |
Return the latest error. More... | |
virtual const char * | strError (const int error) const |
Return a description of the latest error. More... | |
Protected Attributes | |
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.
|
inherited |
|
pure virtual |
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
pure virtual |
Calculate forward position, velocity and accelaration kinematics, from joint coordinates to cartesian coordinates.
q_in | input joint coordinates (position, velocity and acceleration |
out | output cartesian coordinates (position, velocity and acceleration |
|
inlinevirtualinherited |
Return a description of the latest error.
Reimplemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverPos_NR, and KDL::ChainJntToJacSolver.
References KDL::SolverI::E_NO_CONVERGE, and KDL::SolverI::E_NOERROR.
Referenced by KDL::ChainJntToJacSolver::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverVel_pinv::strError(), and KDL::ChainIkSolverVel_wdls::strError().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::SolverI::getError(), KDL::ChainIkSolverVel_pinv::getSVDResult(), KDL::ChainIkSolverVel_wdls::getSVDResult(), and KDL::ChainJntToJacSolver::JntToJac().