Public Member Functions | Private Attributes
KdlChainIdInertia Class Reference

Recursive Newton Euler ID solver with composite rigid body inertia. More...

#include <KdlChainIdInertia.h>

List of all members.

Public Member Functions

int CartToJnt (const KDL::JntArray &q, const KDL::JntArray &q_dot, const KDL::JntArray &q_dotdot, const KDL::Wrenches &f_ext, KDL::JntArray &torques, KDL::JntArray &Hv)
 KdlChainIdInertia (const KDL::Chain &chain, KDL::Vector grav)
 Constructor for KdlChainIdInertia.
 ~KdlChainIdInertia ()

Private Attributes

std::vector< KDL::Twista
KDL::Twist ag
KDL::Chain chain
std::vector< KDL::Wrenchf
KDL::Wrench Fis
std::vector
< KDL::RigidBodyInertia
Ii
unsigned int nj
unsigned int ns
std::vector< KDL::TwistS
std::vector< KDL::Twistv
std::vector< KDL::FrameX

Detailed Description

Recursive Newton Euler ID solver with composite rigid body inertia.

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

It calculates the torques and composite inertias 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. The composite inertias calculated are equivalent to the diagonal of the joint space inertia matrix, H.

Definition at line 24 of file KdlChainIdInertia.h.


Constructor & Destructor Documentation

Constructor for KdlChainIdInertia.

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.
grav

Definition at line 14 of file KdlChainIdInertia.cpp.

Definition at line 32 of file KdlChainIdInertia.h.


Member Function Documentation

int KdlChainIdInertia::CartToJnt ( const KDL::JntArray q,
const KDL::JntArray q_dot,
const KDL::JntArray q_dotdot,
const KDL::Wrenches f_ext,
KDL::JntArray torques,
KDL::JntArray Hv 
)

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
HvThe composite rigid body inertia each joint sees
qPosition
q_dotVelocity
q_dotdotAcceleration
forceExt
torques
Hv

Definition at line 31 of file KdlChainIdInertia.cpp.


Member Data Documentation

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

Definition at line 54 of file KdlChainIdInertia.h.

Definition at line 58 of file KdlChainIdInertia.h.

Definition at line 48 of file KdlChainIdInertia.h.

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

Definition at line 55 of file KdlChainIdInertia.h.

Definition at line 57 of file KdlChainIdInertia.h.

Definition at line 56 of file KdlChainIdInertia.h.

unsigned int KdlChainIdInertia::nj [private]

Definition at line 49 of file KdlChainIdInertia.h.

unsigned int KdlChainIdInertia::ns [private]

Definition at line 50 of file KdlChainIdInertia.h.

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

Definition at line 52 of file KdlChainIdInertia.h.

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

Definition at line 53 of file KdlChainIdInertia.h.

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

Definition at line 51 of file KdlChainIdInertia.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