KDL
1.3.0
|
Implementation of a recursive forward position and velocity kinematics algorithm to calculate the position and velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain). More...
#include <src/chainfksolvervel_recursive.hpp>
Public Types | |
enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2 } |
Public Member Functions | |
ChainFkSolverVel_recursive (const Chain &chain) | |
~ChainFkSolverVel_recursive () | |
virtual int | JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1) |
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates. More... | |
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... | |
Private Attributes | |
const Chain | chain |
Implementation of a recursive forward position and velocity kinematics algorithm to calculate the position and velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).
|
inherited |
KDL::ChainFkSolverVel_recursive::ChainFkSolverVel_recursive | ( | const Chain & | chain | ) |
KDL::ChainFkSolverVel_recursive::~ChainFkSolverVel_recursive | ( | ) |
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
virtual |
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates.
q_in | input joint coordinates (position and velocity) |
out | output cartesian coordinates (position and velocity) |
Implements KDL::ChainFkSolverVel.
References chain, KDL::Segment::getJoint(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), KDL::Joint::getType(), KDL::FrameVel::Identity(), KDL::Joint::None, KDL::Segment::pose(), KDL::JntArrayVel::q, KDL::JntArrayVel::qdot, KDL::JntArray::rows(), and KDL::Segment::twist().
|
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().
|
private |
Referenced by JntToCart().
|
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().