Public Member Functions | Private Attributes
KDL::ChainIkSolverVel_pinv_nso Class Reference

#include <chainiksolvervel_pinv_nso.hpp>

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

List of all members.

Public Member Functions

virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out)
virtual int CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out)
 ChainIkSolverVel_pinv_nso (const Chain &chain, const JntArray &opt_pos, const JntArray &weights, double eps=0.00001, int maxiter=150, double alpha=0.25)
 ChainIkSolverVel_pinv_nso (const Chain &chain, double eps=0.00001, int maxiter=150, double alpha=0.25)
int getSVDResult () const
virtual int setAlpha (const double alpha)
virtual int setOptPos (const JntArray &opt_pos)
virtual int setWeights (const JntArray &weights)
 ~ChainIkSolverVel_pinv_nso ()

Private Attributes

double alpha
const Chain chain
double eps
Jacobian jac
ChainJntToJacSolver jnt2jac
int maxiter
unsigned int nj
JntArray opt_pos
Eigen::VectorXd S
Eigen::VectorXd Sinv
int svdResult
Eigen::VectorXd tmp
Eigen::VectorXd tmp2
Eigen::MatrixXd U
Eigen::MatrixXd V
JntArray weights

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.

In case of a redundant robot this solver optimizes the the following criterium: g=0.5*sum(weight*(Desired_joint_positions - actual_joint_positions))^2 as described in A. Liegeois. Automatic supervisory control of the configuration and behavior of multibody mechnisms. IEEE Transactions on Systems, Man, and Cybernetics, 7(12):868–871, 1977

Definition at line 46 of file chainiksolvervel_pinv_nso.hpp.


Constructor & Destructor Documentation

KDL::ChainIkSolverVel_pinv_nso::ChainIkSolverVel_pinv_nso ( const Chain chain,
const JntArray opt_pos,
const JntArray weights,
double  eps = 0.00001,
int  maxiter = 150,
double  alpha = 0.25 
)

Constructor of the solver

Parameters:
chainthe chain to calculate the inverse velocity kinematics for
opt_posthe desired positions of the chain used by to resolve the redundancy
weightsthe weights applied in the joint space
epsif a singular value is below this value, its inverse is set to zero, default: 0.00001
maxitermaximum iterations for the svd calculation, default: 150
alphathe null-space velocity gain

Definition at line 27 of file chainiksolvervel_pinv_nso.cpp.

KDL::ChainIkSolverVel_pinv_nso::ChainIkSolverVel_pinv_nso ( const Chain chain,
double  eps = 0.00001,
int  maxiter = 150,
double  alpha = 0.25 
) [explicit]

Definition at line 47 of file chainiksolvervel_pinv_nso.cpp.

Definition at line 65 of file chainiksolvervel_pinv_nso.cpp.


Member Function Documentation

int KDL::ChainIkSolverVel_pinv_nso::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_ininput joint positions
v_ininput cartesian velocity
qdot_outoutput joint velocities
Returns:
if < 0 something went wrong

Implements KDL::ChainIkSolverVel.

Definition at line 70 of file chainiksolvervel_pinv_nso.cpp.

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

not (yet) implemented.

Implements KDL::ChainIkSolverVel.

Definition at line 72 of file chainiksolvervel_pinv_nso.hpp.

Retrieve the latest return code from the SVD algorithm

Returns:
0 if CartToJnt() not yet called, otherwise latest SVD result code.

Definition at line 102 of file chainiksolvervel_pinv_nso.hpp.

int KDL::ChainIkSolverVel_pinv_nso::setAlpha ( const double  alpha) [virtual]

Set null psace velocity gain

Parameters:
alphaNUllspace velocity cgain

Definition at line 165 of file chainiksolvervel_pinv_nso.cpp.

int KDL::ChainIkSolverVel_pinv_nso::setOptPos ( const JntArray opt_pos) [virtual]

Set optimal joint positions

Parameters:
opt_posoptimal joint positions

Definition at line 157 of file chainiksolvervel_pinv_nso.cpp.

int KDL::ChainIkSolverVel_pinv_nso::setWeights ( const JntArray weights) [virtual]

Set joint weights for optimization criterion

Parameters:
weightsthe joint weights

Definition at line 149 of file chainiksolvervel_pinv_nso.cpp.


Member Data Documentation

Definition at line 118 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 102 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 115 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 108 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 106 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 116 of file chainiksolvervel_pinv_nso.hpp.

unsigned int KDL::ChainIkSolverVel_pinv_nso::nj [private]

Definition at line 107 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 120 of file chainiksolvervel_pinv_nso.hpp.

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_nso::S [private]

Definition at line 110 of file chainiksolvervel_pinv_nso.hpp.

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_nso::Sinv [private]

Definition at line 111 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 117 of file chainiksolvervel_pinv_nso.hpp.

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_nso::tmp [private]

Definition at line 113 of file chainiksolvervel_pinv_nso.hpp.

Eigen::VectorXd KDL::ChainIkSolverVel_pinv_nso::tmp2 [private]

Definition at line 114 of file chainiksolvervel_pinv_nso.hpp.

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_nso::U [private]

Definition at line 109 of file chainiksolvervel_pinv_nso.hpp.

Eigen::MatrixXd KDL::ChainIkSolverVel_pinv_nso::V [private]

Definition at line 112 of file chainiksolvervel_pinv_nso.hpp.

Definition at line 119 of file chainiksolvervel_pinv_nso.hpp.


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


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:29