$search

KDL::ChainIkSolverVel_pinv_givens Class Reference
[Kinematic Families]

#include <chainiksolvervel_pinv_givens.hpp>

Inheritance diagram for KDL::ChainIkSolverVel_pinv_givens:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual int CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
 ChainIkSolverVel_pinv_givens (const Chain &chain)
 ~ChainIkSolverVel_pinv_givens ()

Private Attributes

MatrixXd B
const Chain chain
Jacobian jac
MatrixXd jac_eigen
ChainJntToJacSolver jnt2jac
int m
int n
VectorXd qdot_eigen
VectorXd S
VectorXd SUY
VectorXd tempi
VectorXd tempj
bool toggle
bool transpose
MatrixXd U
VectorXd UY
MatrixXd V
VectorXd v_in_eigen

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  )  [explicit]

Constructor of the solver

Parameters:
chain the chain to calculate the inverse velocity kinematics for
eps if a singular value is below this value, its inverse is set to zero, default: 0.00001
maxiter maximum iterations for the svd calculation, default: 150

Definition at line 25 of file chainiksolvervel_pinv_givens.cpp.

KDL::ChainIkSolverVel_pinv_givens::~ChainIkSolverVel_pinv_givens (  ) 

Definition at line 46 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 46 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 51 of file chainiksolvervel_pinv_givens.cpp.


Member Data Documentation

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 46 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 50 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 49 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 52 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 52 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 51 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 51 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 53 of file chainiksolvervel_pinv_givens.hpp.

Definition at line 54 of file chainiksolvervel_pinv_givens.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


orocos_kdl
Author(s): Ruben Smits, Erwin Aertbelien, Orocos Developers
autogenerated on Fri Mar 1 16:20:15 2013