#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) |
virtual int | JntToCart (const KDL::JntArrayVel &q_in, std::vector< KDL::FrameVel > &out, int segmentNr=-1) |
virtual void | updateInternalDataStructures () |
~AdvancedChainFkSolverVel_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 |
SolverI () | |
virtual const char * | strError (const int error) const |
virtual | ~SolverI () |
Private Attributes | |
const KDL::Chain & | chain_ |
FrameVelVector_t | segment_vel_ |
Additional Inherited Members | |
Public Attributes inherited from KDL::SolverI | |
E_DEGRADED | |
E_MAX_ITERATIONS_EXCEEDED | |
E_NO_CONVERGE | |
E_NOERROR | |
E_NOT_IMPLEMENTED | |
E_NOT_UP_TO_DATE | |
E_OUT_OF_RANGE | |
E_SIZE_MISMATCH | |
E_SVD_FAILED | |
E_UNDEFINED | |
Protected Attributes inherited from KDL::SolverI | |
int | error |
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.
AdvancedChainFkSolverVel_recursive::AdvancedChainFkSolverVel_recursive | ( | const KDL::Chain & | chain | ) |
Definition at line 117 of file advanced_chainfksolver_recursive.cpp.
AdvancedChainFkSolverVel_recursive::~AdvancedChainFkSolverVel_recursive | ( | ) |
Definition at line 237 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 224 of file advanced_chainfksolver_recursive.cpp.
|
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.
|
virtual |
Definition at line 176 of file advanced_chainfksolver_recursive.cpp.
|
inlinevirtual |
Implements KDL::ChainFkSolverVel.
Definition at line 91 of file advanced_chainfksolver_recursive.hpp.
|
private |
Definition at line 91 of file advanced_chainfksolver_recursive.hpp.
|
private |
Definition at line 95 of file advanced_chainfksolver_recursive.hpp.