KDL::ChainIkSolverVel_pinv_givens Class Reference

Implementation of a inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain. More...

#include <chainiksolvervel_pinv_givens.hpp>

Inheritance diagram for KDL::ChainIkSolverVel_pinv_givens:
KDL::ChainIkSolverVel

List of all members.

Public Member Functions

virtual int CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
 not (yet) implemented.
virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
 Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities.
 ChainIkSolverVel_pinv_givens (const Chain &chain)
 Constructor of the solver.
 ~ChainIkSolverVel_pinv_givens ()

Detailed Description

Implementation of a inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain.

It uses a svd-calculation based on householders rotations.

Definition at line 24 of file chainiksolvervel_pinv_givens.hpp.


Constructor & Destructor Documentation

KDL::ChainIkSolverVel_pinv_givens::ChainIkSolverVel_pinv_givens ( const Chain chain  ) 

Constructor of the solver.

Parameters:
chain the chain to calculate the inverse velocity kinematics for

Definition at line 27 of file chainiksolvervel_pinv_givens.cpp.

KDL::ChainIkSolverVel_pinv_givens::~ChainIkSolverVel_pinv_givens (  ) 

Definition at line 48 of file chainiksolvervel_pinv_givens.cpp.


Member Function Documentation

virtual int KDL::ChainIkSolverVel_pinv_givens::CartToJnt ( const JntArray q_init,
const FrameVel v_in,
JntArrayVel q_out 
) [inline, virtual]

not (yet) implemented.

Implements KDL::ChainIkSolverVel.

Definition at line 42 of file chainiksolvervel_pinv_givens.hpp.

int KDL::ChainIkSolverVel_pinv_givens::CartToJnt ( const JntArray q_in,
const Twist v_in,
JntArray qdot_out 
) [virtual]

Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities.

Parameters:
q_in input joint positions
v_in input cartesian velocity
qdot_out output joint velocities
Returns:
if < 0 something went wrong

Implements KDL::ChainIkSolverVel.

Definition at line 53 of file chainiksolvervel_pinv_givens.cpp.

References KDL::Chain::getNrOfJoints(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::svd_eigen_Macie().


The documentation for this class was generated from the following files:

Generated on Wed Nov 23 19:02:16 2011 for FreeCAD by  doxygen 1.6.1