Public Member Functions | Static Public Attributes | Private Attributes
KDL::TreeIkSolverVel_wdls Class Reference

#include <treeiksolvervel_wdls.hpp>

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

List of all members.

Public Member Functions

virtual double CartToJnt (const JntArray &q_in, const Twists &v_in, JntArray &qdot_out)
double getLambda () const
const MatrixXd & getWeightJS () const
const MatrixXd & getWeightTS () const
void setLambda (const double &lambda)
void setWeightJS (const MatrixXd &Mq)
void setWeightTS (const MatrixXd &Mx)
 TreeIkSolverVel_wdls (const Tree &tree, const std::vector< std::string > &endpoints)
 Child SVD failed.
virtual ~TreeIkSolverVel_wdls ()

Static Public Attributes

static const int E_SVD_FAILED = -100

Private Attributes

MatrixXd J
MatrixXd J_Wq
Jacobians jacobians
TreeJntToJacSolver jnttojacsolver
double lambda
VectorXd qdot
VectorXd S
VectorXd t
VectorXd tmp
Tree tree
MatrixXd U
MatrixXd V
MatrixXd Wq
MatrixXd Wq_V
MatrixXd Wy
MatrixXd Wy_J_Wq
VectorXd Wy_t
MatrixXd Wy_U

Detailed Description

Definition at line 19 of file treeiksolvervel_wdls.hpp.


Constructor & Destructor Documentation

KDL::TreeIkSolverVel_wdls::TreeIkSolverVel_wdls ( const Tree tree,
const std::vector< std::string > &  endpoints 
)

Child SVD failed.

Definition at line 14 of file treeiksolvervel_wdls.cpp.

Definition at line 35 of file treeiksolvervel_wdls.cpp.


Member Function Documentation

double KDL::TreeIkSolverVel_wdls::CartToJnt ( const JntArray q_in,
const Twists v_in,
JntArray qdot_out 
) [virtual]

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

Parameters:
q_ininput joint positions
v_ininput cartesian velocity
qdot_outoutput joint velocities
Returns:
if < 0 something went wrong distance to goal otherwise (weighted norm of v_in)

Implements KDL::TreeIkSolverVel.

Definition at line 50 of file treeiksolvervel_wdls.cpp.

double KDL::TreeIkSolverVel_wdls::getLambda ( ) const [inline]

Definition at line 80 of file treeiksolvervel_wdls.hpp.

const MatrixXd& KDL::TreeIkSolverVel_wdls::getWeightJS ( ) const [inline]

Definition at line 51 of file treeiksolvervel_wdls.hpp.

const MatrixXd& KDL::TreeIkSolverVel_wdls::getWeightTS ( ) const [inline]

Definition at line 77 of file treeiksolvervel_wdls.hpp.

void KDL::TreeIkSolverVel_wdls::setLambda ( const double &  lambda)

Definition at line 46 of file treeiksolvervel_wdls.cpp.

void KDL::TreeIkSolverVel_wdls::setWeightJS ( const MatrixXd &  Mq)

Definition at line 38 of file treeiksolvervel_wdls.cpp.

void KDL::TreeIkSolverVel_wdls::setWeightTS ( const MatrixXd &  Mx)

Definition at line 42 of file treeiksolvervel_wdls.cpp.


Member Data Documentation

const int KDL::TreeIkSolverVel_wdls::E_SVD_FAILED = -100 [static]

Definition at line 21 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::J [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::J_Wq [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

Definition at line 85 of file treeiksolvervel_wdls.hpp.

Definition at line 84 of file treeiksolvervel_wdls.hpp.

Definition at line 89 of file treeiksolvervel_wdls.hpp.

VectorXd KDL::TreeIkSolverVel_wdls::qdot [private]

Definition at line 88 of file treeiksolvervel_wdls.hpp.

VectorXd KDL::TreeIkSolverVel_wdls::S [private]

Definition at line 88 of file treeiksolvervel_wdls.hpp.

VectorXd KDL::TreeIkSolverVel_wdls::t [private]

Definition at line 88 of file treeiksolvervel_wdls.hpp.

VectorXd KDL::TreeIkSolverVel_wdls::tmp [private]

Definition at line 88 of file treeiksolvervel_wdls.hpp.

Definition at line 83 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::U [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::V [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::Wq [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::Wq_V [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::Wy [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.

Definition at line 87 of file treeiksolvervel_wdls.hpp.

VectorXd KDL::TreeIkSolverVel_wdls::Wy_t [private]

Definition at line 88 of file treeiksolvervel_wdls.hpp.

MatrixXd KDL::TreeIkSolverVel_wdls::Wy_U [private]

Definition at line 87 of file treeiksolvervel_wdls.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Jun 14 2019 19:33:23