Public Member Functions | Private Member Functions | Private Attributes | List of all members
KDL::TreeIdSolver_RNE Class Reference

Recursive newton euler inverse dynamics solver for kinematic trees. More...

#include <treeidsolver_recursive_newton_euler.hpp>

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

Public Member Functions

int CartToJnt (const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const WrenchMap &f_ext, JntArray &torques)
 
 TreeIdSolver_RNE (const Tree &tree, Vector grav)
 
virtual void updateInternalDataStructures ()
 
- Public Member Functions inherited from KDL::SolverI
virtual int getError () const
 Return the latest error. More...
 
 SolverI ()
 Initialize latest error to E_NOERROR. More...
 
virtual const char * strError (const int error) const
 
virtual ~SolverI ()
 

Private Member Functions

void initAuxVariables ()
 Helper function to initialize private members X, S, v, a, f. More...
 
void rne_step (SegmentMap::const_iterator segment, const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const WrenchMap &f_ext, JntArray &torques)
 One recursion step. More...
 

Private Attributes

std::map< std::string, Twista
 
Twist ag
 
std::map< std::string, Wrenchf
 
unsigned int nj
 
unsigned int ns
 
std::map< std::string, TwistS
 
const Treetree
 
std::map< std::string, Twistv
 
std::map< std::string, FrameX
 

Additional Inherited Members

- Public Types inherited from KDL::SolverI
enum  {
  E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2,
  E_NOT_UP_TO_DATE = -3, E_SIZE_MISMATCH = -4, E_MAX_ITERATIONS_EXCEEDED = -5, E_OUT_OF_RANGE = -6,
  E_NOT_IMPLEMENTED = -7, E_SVD_FAILED = -8
}
 
- Protected Attributes inherited from KDL::SolverI
int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

Detailed Description

Recursive newton euler inverse dynamics solver for kinematic trees.

It calculates the torques for the joints, given the motion of the joints (q,qdot,qdotdot), external forces on the segments (expressed in the segments reference frame) and the dynamical parameters of the segments.

This is an extension of the inverse dynamic solver for kinematic chains,

See also
ChainIdSolver_RNE. The main difference is the use of STL maps instead of vectors to represent external wrenches (as well as internal variables exploited during the recursion).

Definition at line 41 of file treeidsolver_recursive_newton_euler.hpp.

Constructor & Destructor Documentation

◆ TreeIdSolver_RNE()

KDL::TreeIdSolver_RNE::TreeIdSolver_RNE ( const Tree tree,
Vector  grav 
)

Constructor for the solver, it will allocate all the necessary memory

Parameters
treeThe kinematic tree to calculate the inverse dynamics for, an internal reference will be stored.
gravThe gravity vector to use during the calculation.

Definition at line 28 of file treeidsolver_recursive_newton_euler.cpp.

Member Function Documentation

◆ CartToJnt()

int KDL::TreeIdSolver_RNE::CartToJnt ( const JntArray q,
const JntArray q_dot,
const JntArray q_dotdot,
const WrenchMap f_ext,
JntArray torques 
)
virtual

Function to calculate from Cartesian forces to joint torques. Input parameters;

Parameters
qThe current joint positions
q_dotThe current joint velocities
q_dotdotThe current joint accelerations
f_extThe external forces (no gravity) on the segments Output parameters:
torquesthe resulting torques for the joints

Implements KDL::TreeIdSolver.

Definition at line 52 of file treeidsolver_recursive_newton_euler.cpp.

◆ initAuxVariables()

void KDL::TreeIdSolver_RNE::initAuxVariables ( )
private

Helper function to initialize private members X, S, v, a, f.

Definition at line 41 of file treeidsolver_recursive_newton_euler.cpp.

◆ rne_step()

void KDL::TreeIdSolver_RNE::rne_step ( SegmentMap::const_iterator  segment,
const JntArray q,
const JntArray q_dot,
const JntArray q_dotdot,
const WrenchMap f_ext,
JntArray torques 
)
private

One recursion step.

Definition at line 78 of file treeidsolver_recursive_newton_euler.cpp.

◆ updateInternalDataStructures()

void KDL::TreeIdSolver_RNE::updateInternalDataStructures ( )
virtual

Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.

Implements KDL::SolverI.

Definition at line 35 of file treeidsolver_recursive_newton_euler.cpp.

Member Data Documentation

◆ a

std::map<std::string,Twist> KDL::TreeIdSolver_RNE::a
private

Definition at line 78 of file treeidsolver_recursive_newton_euler.hpp.

◆ ag

Twist KDL::TreeIdSolver_RNE::ag
private

Definition at line 80 of file treeidsolver_recursive_newton_euler.hpp.

◆ f

std::map<std::string,Wrench> KDL::TreeIdSolver_RNE::f
private

Definition at line 79 of file treeidsolver_recursive_newton_euler.hpp.

◆ nj

unsigned int KDL::TreeIdSolver_RNE::nj
private

Definition at line 73 of file treeidsolver_recursive_newton_euler.hpp.

◆ ns

unsigned int KDL::TreeIdSolver_RNE::ns
private

Definition at line 74 of file treeidsolver_recursive_newton_euler.hpp.

◆ S

std::map<std::string,Twist> KDL::TreeIdSolver_RNE::S
private

Definition at line 76 of file treeidsolver_recursive_newton_euler.hpp.

◆ tree

const Tree& KDL::TreeIdSolver_RNE::tree
private

Definition at line 72 of file treeidsolver_recursive_newton_euler.hpp.

◆ v

std::map<std::string,Twist> KDL::TreeIdSolver_RNE::v
private

Definition at line 77 of file treeidsolver_recursive_newton_euler.hpp.

◆ X

std::map<std::string,Frame> KDL::TreeIdSolver_RNE::X
private

Definition at line 75 of file treeidsolver_recursive_newton_euler.hpp.


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


orocos_kdl
Author(s):
autogenerated on Thu Apr 13 2023 02:19:15