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 <chainfksolvervel_recursive.hpp>
Public Member Functions | |
ChainFkSolverVel_recursive (const Chain &chain) | |
virtual int | JntToCart (const JntArrayVel &q_in, FrameVel &out, int segmentNr=-1) |
Calculate forward position and velocity kinematics, from joint coordinates to cartesian coordinates. | |
~ChainFkSolverVel_recursive () |
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.
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) | |
segmentNr | default to -1 |
Implements KDL::ChainFkSolverVel.
Definition at line 36 of file chainfksolvervel_recursive.cpp.
References 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().