Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
KdlTreeIk Class Reference

#include <KdlTreeIk.h>

Inheritance diagram for KdlTreeIk:
Inheritance graph
[legend]

List of all members.

Public Types

typedef KDL::Twist NodePriority

Public Member Functions

virtual void getFrames (const KDL::JntArray &joints_in, std::map< std::string, KDL::Frame > &frameMap)
 getJoints
virtual void getJointPositions (const KDL::JntArray &joints_in, const std::vector< std::string > &nodeNames, const std::vector< KDL::Frame > &nodeFrames, KDL::JntArray &joints_out, const std::vector< NodePriority > &nodePriorities)
double getTimeStep () const
 KdlTreeIk ()
void resetSolver ()
void setEpsilon (double eps_in=1e-6)
void setJointInertias (const std::map< std::string, double > &inertia_in)
void setLambda (double lambda=0.05)
void setMaxCriticalIterations (unsigned int maxIter_in=50)
void setMaxNonCriticalIterations (unsigned int maxIter_in=5)
void setPositionLimiter (boost::shared_ptr< JointNamePositionLimiter > posLimiter)
void setPriorityTol (const std::map< int, std::pair< double, double > > &priority_tol)
void setTimeStep (double timeStep_in=0.01)
 set time step between trajectory bread crumbs
 ~KdlTreeIk ()

Public Attributes

std::auto_ptr< KdlTreeFkfkPosSolverPtr

Static Public Attributes

static const int CRITICAL = r2_msgs::PriorityArray::CRITICAL
static const int HIGH = r2_msgs::PriorityArray::HIGH
static const int IGNORE = r2_msgs::PriorityArray::IGNORE
static const int LOW = r2_msgs::PriorityArray::LOW
static const int MEDIUM = r2_msgs::PriorityArray::MEDIUM

Protected Member Functions

virtual void initialize ()
 initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded

Protected Attributes

unsigned int critMaxIter
double eps
std::map< std::string, double > inertiaMap
 the mapping of joint names to joint inertias Joint Name : joint inertia
KDL::JntArray inertias
 the inertia of each joint in the same position as received from getJointPositions
std::auto_ptr
< KDL::TreeJntToJacSolver
jacSolverPtr
std::vector< std::string > jointNames
double lambda_squared
double maxInertia
double minInertia
unsigned int nonCritMaxIter
boost::shared_ptr
< JointNamePositionLimiter
positionLimiter
std::map< int, std::pair
< double, double > > 
priorityTolMap
 the mapping between priority number and tolerence amount Priority Num : (Linear Tolerence, Angular Tolerence) (m, rad)
double timeStep

Private Member Functions

void getJointVelocities (const KDL::JntArray &joints_in, const std::vector< std::pair< std::string, KDL::Twist > > &twist_deltas, const std::vector< NodePriority > &nodePriorities, KDL::JntArray &joint_deltas) const
 getJointVelocities - getJointVelocities.

Private Attributes

bool useDampedLeastSquares

Detailed Description

Definition at line 23 of file KdlTreeIk.h.


Member Typedef Documentation

Definition at line 26 of file KdlTreeIk.h.


Constructor & Destructor Documentation

Definition at line 9 of file KdlTreeIk.cpp.

Definition at line 21 of file KdlTreeIk.cpp.


Member Function Documentation

void KdlTreeIk::getFrames ( const KDL::JntArray joints_in,
std::map< std::string, KDL::Frame > &  frameMap 
) [virtual]

getJoints

Parameters:
joints_ininput joints
nodeNamesinput frame names
nodeFramesinput frames
joints_outoutput joints
nodePrioritiesinput node priorities (6 * nodeNames.size())

Reimplemented in MobileTreeIk.

Definition at line 56 of file KdlTreeIk.cpp.

void KdlTreeIk::getJointPositions ( const KDL::JntArray joints_in,
const std::vector< std::string > &  nodeNames,
const std::vector< KDL::Frame > &  nodeFrames,
KDL::JntArray joints_out,
const std::vector< NodePriority > &  nodePriorities 
) [virtual]

Reimplemented in MobileTreeIk, and KdlTreeTr.

Definition at line 99 of file KdlTreeIk.cpp.

void KdlTreeIk::getJointVelocities ( const KDL::JntArray joints_in,
const std::vector< std::pair< std::string, KDL::Twist > > &  twist_deltas,
const std::vector< NodePriority > &  nodePriorities,
KDL::JntArray joint_deltas 
) const [private]

getJointVelocities - getJointVelocities.

Definition at line 215 of file KdlTreeIk.cpp.

double KdlTreeIk::getTimeStep ( ) const [inline]

Definition at line 38 of file KdlTreeIk.h.

void KdlTreeIk::initialize ( ) [protected, virtual]

initialize called by both of the load functions, allowing derived classes to perform additional initialization after the tree is loaded

Reimplemented from KdlTreeParser.

Reimplemented in MobileTreeIk, and KdlTreeTr.

Definition at line 25 of file KdlTreeIk.cpp.

Definition at line 35 of file KdlTreeIk.cpp.

void KdlTreeIk::setEpsilon ( double  eps_in = 1e-6) [inline]

Definition at line 61 of file KdlTreeIk.h.

void KdlTreeIk::setJointInertias ( const std::map< std::string, double > &  inertia_in)

Reimplemented in KdlTreeTr.

Definition at line 60 of file KdlTreeIk.cpp.

void KdlTreeIk::setLambda ( double  lambda = 0.05) [inline]

Definition at line 68 of file KdlTreeIk.h.

void KdlTreeIk::setMaxCriticalIterations ( unsigned int  maxIter_in = 50) [inline]

Definition at line 50 of file KdlTreeIk.h.

void KdlTreeIk::setMaxNonCriticalIterations ( unsigned int  maxIter_in = 5) [inline]

Definition at line 56 of file KdlTreeIk.h.

void KdlTreeIk::setPositionLimiter ( boost::shared_ptr< JointNamePositionLimiter posLimiter) [inline]

Definition at line 66 of file KdlTreeIk.h.

void KdlTreeIk::setPriorityTol ( const std::map< int, std::pair< double, double > > &  priority_tol) [inline]

Reimplemented in MobileTreeIk.

Definition at line 75 of file KdlTreeIk.h.

void KdlTreeIk::setTimeStep ( double  timeStep_in = 0.01)

set time step between trajectory bread crumbs

Parameters:
timeStep_intime step
Returns:
void
Exceptions:
invalid_argumentTime step must be greater than 0

Definition at line 41 of file KdlTreeIk.cpp.


Member Data Documentation

const int KdlTreeIk::CRITICAL = r2_msgs::PriorityArray::CRITICAL [static]

Definition at line 31 of file KdlTreeIk.h.

unsigned int KdlTreeIk::critMaxIter [protected]

Definition at line 110 of file KdlTreeIk.h.

double KdlTreeIk::eps [protected]

Definition at line 112 of file KdlTreeIk.h.

Definition at line 100 of file KdlTreeIk.h.

const int KdlTreeIk::HIGH = r2_msgs::PriorityArray::HIGH [static]

Definition at line 30 of file KdlTreeIk.h.

const int KdlTreeIk::IGNORE = r2_msgs::PriorityArray::IGNORE [static]

Definition at line 27 of file KdlTreeIk.h.

std::map<std::string, double> KdlTreeIk::inertiaMap [protected]

the mapping of joint names to joint inertias Joint Name : joint inertia

Definition at line 124 of file KdlTreeIk.h.

the inertia of each joint in the same position as received from getJointPositions

Definition at line 119 of file KdlTreeIk.h.

Definition at line 115 of file KdlTreeIk.h.

std::vector<std::string> KdlTreeIk::jointNames [protected]

Definition at line 105 of file KdlTreeIk.h.

double KdlTreeIk::lambda_squared [protected]

Definition at line 113 of file KdlTreeIk.h.

const int KdlTreeIk::LOW = r2_msgs::PriorityArray::LOW [static]

Definition at line 28 of file KdlTreeIk.h.

double KdlTreeIk::maxInertia [protected]

Definition at line 126 of file KdlTreeIk.h.

const int KdlTreeIk::MEDIUM = r2_msgs::PriorityArray::MEDIUM [static]

Definition at line 29 of file KdlTreeIk.h.

double KdlTreeIk::minInertia [protected]

Definition at line 125 of file KdlTreeIk.h.

unsigned int KdlTreeIk::nonCritMaxIter [protected]

Definition at line 111 of file KdlTreeIk.h.

boost::shared_ptr<JointNamePositionLimiter> KdlTreeIk::positionLimiter [protected]

Definition at line 134 of file KdlTreeIk.h.

std::map<int, std::pair<double, double> > KdlTreeIk::priorityTolMap [protected]

the mapping between priority number and tolerence amount Priority Num : (Linear Tolerence, Angular Tolerence) (m, rad)

Definition at line 132 of file KdlTreeIk.h.

double KdlTreeIk::timeStep [protected]

Definition at line 108 of file KdlTreeIk.h.

Definition at line 144 of file KdlTreeIk.h.


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


robodyn_controllers
Author(s):
autogenerated on Sat Jun 8 2019 20:20:54