#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) |
~ChainFkSolverVel_recursive () | |
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).
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.
Definition at line 32 of file chainfksolvervel_recursive.cpp.
int KDL::ChainFkSolverVel_recursive::JntToCart | ( | const JntArrayVel & | q_in, |
FrameVel & | out, | ||
int | segmentNr = -1 |
||
) | [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.
int KDL::ChainFkSolverVel_recursive::JntToCart | ( | const JntArrayVel & | q_in, |
std::vector< FrameVel > & | out, | ||
int | segmentNr = -1 |
||
) | [virtual] |
Definition at line 67 of file chainfksolvervel_recursive.cpp.
const Chain KDL::ChainFkSolverVel_recursive::chain [private] |
Definition at line 46 of file chainfksolvervel_recursive.hpp.