#include <advanced_chainfksolver_recursive.hpp>
Public Member Functions | |
AdvancedChainFkSolverVel_recursive (const KDL::Chain &chain) | |
KDL::FrameVel | getFrameVelAtSegment (uint16_t seg_idx) const |
virtual int | JntToCart (const KDL::JntArrayVel &q_in, KDL::FrameVel &out, int seg_nr=-1) |
~AdvancedChainFkSolverVel_recursive () | |
Private Attributes | |
const KDL::Chain & | chain_ |
FrameVelVector_t | segment_vel_ |
Implementation of a recursive forward velocities kinematics algorithm to calculate the velocity transformation from joint space to Cartesian space of a general kinematic chain (KDL::Chain).
Definition at line 71 of file advanced_chainfksolver_recursive.hpp.
Definition at line 117 of file advanced_chainfksolver_recursive.cpp.
Definition at line 190 of file advanced_chainfksolver_recursive.cpp.
KDL::FrameVel AdvancedChainFkSolverVel_recursive::getFrameVelAtSegment | ( | uint16_t | seg_idx | ) | const |
seg_idx | Index of the segment starting with 0. |
Definition at line 177 of file advanced_chainfksolver_recursive.cpp.
int AdvancedChainFkSolverVel_recursive::JntToCart | ( | const KDL::JntArrayVel & | q_in, |
KDL::FrameVel & | out, | ||
int | seg_nr = -1 |
||
) | [virtual] |
q_in | Joint states. |
p_out | The output frame of the given segment or end-effector. |
seg_nr | The max. segment nr until calculation should stop. |
Calculates the cartesion velocities given to the joints and joint velocities array. This special implementation ensures that the velocities are stored in a vector so it is not necessary to call the method for each segment again and again.
Implements KDL::ChainFkSolverVel.
Definition at line 127 of file advanced_chainfksolver_recursive.cpp.
const KDL::Chain& AdvancedChainFkSolverVel_recursive::chain_ [private] |
Definition at line 93 of file advanced_chainfksolver_recursive.hpp.
Definition at line 94 of file advanced_chainfksolver_recursive.hpp.