$search

KDL::TreeIkSolverPos_Online Class Reference
[Kinematic Families]

#include <treeiksolverpos_online.hpp>

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

List of all members.

Public Member Functions

virtual double CartToJnt (const JntArray &q_in, const Frames &p_in, JntArray &q_out)
 TreeIkSolverPos_Online (const double &nr_of_jnts, const std::vector< std::string > &endpoints, const JntArray &q_min, const JntArray &q_max, const JntArray &q_dot_max, const double x_dot_trans_max, const double x_dot_rot_max, TreeFkSolverPos &fksolver, TreeIkSolverVel &iksolver)
 ~TreeIkSolverPos_Online ()

Private Member Functions

void enforceCartVelLimits ()
void enforceJointVelLimits ()

Private Attributes

Twists delta_twists_
TreeFkSolverPosfksolver_
Frames frames_
TreeIkSolverVeliksolver_
JntArray q_dot_
JntArray q_dot_max_
JntArray q_max_
JntArray q_min_
Twist twist_
double x_dot_rot_max_
double x_dot_trans_max_

Detailed Description

Implementation of a general inverse position kinematics algorithm to calculate the position transformation from Cartesian to joint space of a general KDL::Tree. This class has been derived from the TreeIkSolverPos_NR_JL class, but was modified for online solving for use in realtime systems. Thus, the calculation is only done once, meaning that no iteration is done, because this solver is intended to run at a high frequency. It enforces velocity limits in task as well as in joint space. It also takes joint limits into account.

Definition at line 44 of file treeiksolverpos_online.hpp.


Constructor & Destructor Documentation

KDL::TreeIkSolverPos_Online::TreeIkSolverPos_Online ( const double &  nr_of_jnts,
const std::vector< std::string > &  endpoints,
const JntArray &  q_min,
const JntArray &  q_max,
const JntArray &  q_dot_max,
const double  x_dot_trans_max,
const double  x_dot_rot_max,
TreeFkSolverPos fksolver,
TreeIkSolverVel iksolver 
)

Constructor of the solver, it needs the number of joints of the tree, a list of the endpoints you are interested in, the maximum and minimum values you want to enforce and a forward position kinematics solver as well as an inverse velocity kinematics solver for the calculations

Parameters:
nr_of_jnts number of joints of the tree to calculate the joint positions for
endpoints the list of endpoints you are interested in
q_min the minimum joint positions
q_max the maximum joint positions
q_dot_max the maximum joint velocities
x_dot_trans_max the maximum translational velocity of your endpoints
x_dot_rot_max the maximum rotational velocity of your endpoints
fksolver a forward position kinematics solver
iksolver an inverse velocity kinematics solver
Returns:

Definition at line 28 of file treeiksolverpos_online.cpp.

KDL::TreeIkSolverPos_Online::~TreeIkSolverPos_Online (  ) 

Definition at line 58 of file treeiksolverpos_online.cpp.


Member Function Documentation

double KDL::TreeIkSolverPos_Online::CartToJnt ( const JntArray &  q_init,
const Frames p_in,
JntArray &  q_out 
) [virtual]

Calculate inverse position kinematics, from cartesian coordinates to joint coordinates.

Parameters:
q_init initial guess of the joint coordinates
p_in input cartesian coordinates
q_out output joint coordinates
Returns:
if < 0 something went wrong otherwise (>=0) remaining (weighted) distance to target

Implements KDL::TreeIkSolverPos.

Definition at line 62 of file treeiksolverpos_online.cpp.

void KDL::TreeIkSolverPos_Online::enforceCartVelLimits (  )  [private]

Scales translational and rotational velocity vectors of the class member KDL::Twist twist_, if at least one of both exceeds the maximum value/length. Scaling is done propotional to the biggest overshoot among both velocities.

Definition at line 152 of file treeiksolverpos_online.cpp.

void KDL::TreeIkSolverPos_Online::enforceJointVelLimits (  )  [private]

Scales the class member KDL::JntArray q_dot_, if one (or more) joint velocity exceeds the maximum value. Scaling is done propotional to the biggest overshoot among all joint velocities.

Definition at line 114 of file treeiksolverpos_online.cpp.


Member Data Documentation

Definition at line 102 of file treeiksolverpos_online.hpp.

Definition at line 97 of file treeiksolverpos_online.hpp.

Definition at line 101 of file treeiksolverpos_online.hpp.

Definition at line 98 of file treeiksolverpos_online.hpp.

Definition at line 99 of file treeiksolverpos_online.hpp.

Definition at line 94 of file treeiksolverpos_online.hpp.

Definition at line 93 of file treeiksolverpos_online.hpp.

Definition at line 92 of file treeiksolverpos_online.hpp.

Definition at line 100 of file treeiksolverpos_online.hpp.

Definition at line 96 of file treeiksolverpos_online.hpp.

Definition at line 95 of file treeiksolverpos_online.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:17 2013