$search

KDL::ChainIkSolverVel_pinv Class Reference
[Kinematic Families]

#include <chainiksolvervel_pinv.hpp>

Inheritance diagram for KDL::ChainIkSolverVel_pinv:
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 (const Chain &chain, double eps=0.00001, int maxiter=150)
 ~ChainIkSolverVel_pinv ()

Private Attributes

const Chain chain
double eps
Jacobian jac
ChainJntToJacSolver jnt2jac
int maxiter
JntArray S
SVD_HH svd
JntArray tmp
std::vector< JntArray > U
std::vector< JntArray > V

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 40 of file chainiksolvervel_pinv.hpp.


Constructor & Destructor Documentation

KDL::ChainIkSolverVel_pinv::ChainIkSolverVel_pinv ( const Chain chain,
double  eps = 0.00001,
int  maxiter = 150 
) [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 24 of file chainiksolvervel_pinv.cpp.

KDL::ChainIkSolverVel_pinv::~ChainIkSolverVel_pinv (  ) 

Definition at line 38 of file chainiksolvervel_pinv.cpp.


Member Function Documentation

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

not (yet) implemented.

Implements KDL::ChainIkSolverVel.

Definition at line 62 of file chainiksolvervel_pinv.hpp.

int KDL::ChainIkSolverVel_pinv::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 43 of file chainiksolvervel_pinv.cpp.


Member Data Documentation

Definition at line 62 of file chainiksolvervel_pinv.hpp.

Definition at line 72 of file chainiksolvervel_pinv.hpp.

Definition at line 66 of file chainiksolvervel_pinv.hpp.

Definition at line 65 of file chainiksolvervel_pinv.hpp.

Definition at line 73 of file chainiksolvervel_pinv.hpp.

JntArray KDL::ChainIkSolverVel_pinv::S [private]

Definition at line 69 of file chainiksolvervel_pinv.hpp.

Definition at line 67 of file chainiksolvervel_pinv.hpp.

JntArray KDL::ChainIkSolverVel_pinv::tmp [private]

Definition at line 71 of file chainiksolvervel_pinv.hpp.

std::vector<JntArray> KDL::ChainIkSolverVel_pinv::U [private]

Definition at line 68 of file chainiksolvervel_pinv.hpp.

std::vector<JntArray> KDL::ChainIkSolverVel_pinv::V [private]

Definition at line 70 of file chainiksolvervel_pinv.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