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

Recursive newton euler inverse dynamics solver. More...

#include <chainidsolver_recursive_newton_euler.hpp>

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

List of all members.

Public Member Functions

int CartToJnt (const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext, JntArray &torques)
 ChainIdSolver_RNE (const Chain &chain, Vector grav)
 ~ChainIdSolver_RNE ()

Private Attributes

std::vector< Twista
Twist ag
Chain chain
std::vector< Wrenchf
unsigned int nj
unsigned int ns
std::vector< TwistS
std::vector< Twistv
std::vector< FrameX

Detailed Description

Recursive newton euler inverse dynamics solver.

The algorithm implementation is based on the book "Rigid Body Dynamics Algorithms" of Roy Featherstone, 2008 (ISBN:978-0-387-74314-1) See page 96 for the pseudo-code.

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.

Definition at line 40 of file chainidsolver_recursive_newton_euler.hpp.


Constructor & Destructor Documentation

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

Parameters:
chainThe kinematic chain to calculate the inverse dynamics for, an internal copy will be made.
gravThe gravity vector to use during the calculation.

Definition at line 27 of file chainidsolver_recursive_newton_euler.cpp.

Definition at line 48 of file chainidsolver_recursive_newton_euler.hpp.


Member Function Documentation

int KDL::ChainIdSolver_RNE::CartToJnt ( const JntArray &  q,
const JntArray &  q_dot,
const JntArray &  q_dotdot,
const Wrenches 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::ChainIdSolver.

Definition at line 34 of file chainidsolver_recursive_newton_euler.cpp.


Member Data Documentation

std::vector<Twist> KDL::ChainIdSolver_RNE::a [private]

Definition at line 69 of file chainidsolver_recursive_newton_euler.hpp.

Definition at line 71 of file chainidsolver_recursive_newton_euler.hpp.

Definition at line 63 of file chainidsolver_recursive_newton_euler.hpp.

std::vector<Wrench> KDL::ChainIdSolver_RNE::f [private]

Definition at line 70 of file chainidsolver_recursive_newton_euler.hpp.

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

Definition at line 64 of file chainidsolver_recursive_newton_euler.hpp.

unsigned int KDL::ChainIdSolver_RNE::ns [private]

Definition at line 65 of file chainidsolver_recursive_newton_euler.hpp.

std::vector<Twist> KDL::ChainIdSolver_RNE::S [private]

Definition at line 67 of file chainidsolver_recursive_newton_euler.hpp.

std::vector<Twist> KDL::ChainIdSolver_RNE::v [private]

Definition at line 68 of file chainidsolver_recursive_newton_euler.hpp.

std::vector<Frame> KDL::ChainIdSolver_RNE::X [private]

Definition at line 66 of file chainidsolver_recursive_newton_euler.hpp.


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


orocos_kdl
Author(s):
autogenerated on Mon Oct 6 2014 03:11:17