#include <chainfksolvervel_recursive.hpp>
Public Member Functions | |
ChainFkSolverVel_recursive (const Chain &chain) | |
virtual int | JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1) |
virtual int | JntToCart (const JntArrayVel &q_in, std::vector< FrameVel > &out, int segmentNr=-1) |
virtual void | updateInternalDataStructures () |
~ChainFkSolverVel_recursive () | |
Public Member Functions inherited from KDL::ChainFkSolverVel | |
virtual int | JntToCart (const JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1)=0 |
virtual | ~ChainFkSolverVel () |
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 () |
Private Attributes | |
const Chain & | chain |
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... | |
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).
Definition at line 37 of file chainfksolvervel_recursive.hpp.
KDL::ChainFkSolverVel_recursive::ChainFkSolverVel_recursive | ( | const Chain & | chain | ) |
Definition at line 27 of file chainfksolvervel_recursive.cpp.
KDL::ChainFkSolverVel_recursive::~ChainFkSolverVel_recursive | ( | ) |
Definition at line 32 of file chainfksolvervel_recursive.cpp.
|
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.
Definition at line 36 of file chainfksolvervel_recursive.cpp.
|
virtual |
Definition at line 67 of file chainfksolvervel_recursive.cpp.
|
inlinevirtual |
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::ChainFkSolverVel.
Definition at line 45 of file chainfksolvervel_recursive.hpp.
|
private |
Definition at line 45 of file chainfksolvervel_recursive.hpp.