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

Recursive newton euler forward dynamics solver. More...

#include <chainfdsolver_recursive_newton_euler.hpp>

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

Public Member Functions

int CartToJnt (const JntArray &q, const JntArray &q_dot, const JntArray &torques, const Wrenches &f_ext, JntArray &q_dotdot)
 
 ChainFdSolver_RNE (const Chain &chain, Vector grav)
 
void RK4Integrator (unsigned int &nj, const double &t, double &dt, KDL::JntArray &q, KDL::JntArray &q_dot, KDL::JntArray &torques, KDL::Wrenches &f_ext, KDL::ChainFdSolver_RNE &fdsolver, KDL::JntArray &q_dotdot, KDL::JntArray &dq, KDL::JntArray &dq_dot, KDL::JntArray &q_temp, KDL::JntArray &q_dot_temp)
 
virtual void updateInternalDataStructures ()
 
 ~ChainFdSolver_RNE ()
 
- 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 Attributes

Eigen::VectorXd acc_eig
 
const Chainchain
 
Eigen::VectorXd D_eig
 
ChainDynParam DynSolver
 
JntSpaceInertiaMatrix H
 
Eigen::MatrixXd H_eig
 
ChainIdSolver_RNE IdSolver
 
Eigen::MatrixXd L_eig
 
unsigned int nj
 
unsigned int ns
 
Eigen::VectorXd r_eig
 
JntArray Tzeroacc
 
Eigen::VectorXd Tzeroacc_eig
 

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 forward 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 Chapter 6 for basic algorithm.

It calculates the accelerations for the joints (qdotdot), given the position and velocity 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 42 of file chainfdsolver_recursive_newton_euler.hpp.

Constructor & Destructor Documentation

KDL::ChainFdSolver_RNE::ChainFdSolver_RNE ( const Chain chain,
Vector  grav 
)

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

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

Definition at line 29 of file chainfdsolver_recursive_newton_euler.cpp.

KDL::ChainFdSolver_RNE::~ChainFdSolver_RNE ( )
inline

Definition at line 50 of file chainfdsolver_recursive_newton_euler.hpp.

Member Function Documentation

int KDL::ChainFdSolver_RNE::CartToJnt ( const JntArray q,
const JntArray q_dot,
const JntArray torques,
const Wrenches f_ext,
JntArray q_dotdot 
)
virtual

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

Parameters
qThe current joint positions
q_dotThe current joint velocities
torquesThe current joint torques (applied by controller)
f_extThe external forces (no gravity) on the segments Output parameters:
q_dotdotThe resulting joint accelerations

Implements KDL::ChainFdSolver.

Definition at line 51 of file chainfdsolver_recursive_newton_euler.cpp.

void KDL::ChainFdSolver_RNE::RK4Integrator ( unsigned int &  nj,
const double &  t,
double &  dt,
KDL::JntArray q,
KDL::JntArray q_dot,
KDL::JntArray torques,
KDL::Wrenches f_ext,
KDL::ChainFdSolver_RNE fdsolver,
KDL::JntArray q_dotdot,
KDL::JntArray dq,
KDL::JntArray dq_dot,
KDL::JntArray q_temp,
KDL::JntArray q_dot_temp 
)

Function to integrate the joint accelerations resulting from the forward dynamics solver. Input parameters;

Parameters
njThe number of joints
tThe current time
dtThe integration period
qThe current joint positions
q_dotThe current joint velocities
torquesThe current joint torques (applied by controller)
f_extThe external forces (no gravity) on the segments
fdsolverThe forward dynamics solver Output parameters:
tThe updated time
qThe updated joint positions
q_dotThe updated joint velocities
q_dotdotThe current joint accelerations
dqThe joint position increment
dq_dotThe joint velocity increment Temporary parameters:
qtempIntermediate joint positions
qdtempIntermediate joint velocities

Definition at line 95 of file chainfdsolver_recursive_newton_euler.cpp.

void KDL::ChainFdSolver_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 46 of file chainfdsolver_recursive_newton_euler.cpp.

Member Data Documentation

Eigen::VectorXd KDL::ChainFdSolver_RNE::acc_eig
private

Definition at line 107 of file chainfdsolver_recursive_newton_euler.hpp.

const Chain& KDL::ChainFdSolver_RNE::chain
private

Definition at line 95 of file chainfdsolver_recursive_newton_euler.hpp.

Eigen::VectorXd KDL::ChainFdSolver_RNE::D_eig
private

Definition at line 105 of file chainfdsolver_recursive_newton_euler.hpp.

ChainDynParam KDL::ChainFdSolver_RNE::DynSolver
private

Definition at line 96 of file chainfdsolver_recursive_newton_euler.hpp.

JntSpaceInertiaMatrix KDL::ChainFdSolver_RNE::H
private

Definition at line 100 of file chainfdsolver_recursive_newton_euler.hpp.

Eigen::MatrixXd KDL::ChainFdSolver_RNE::H_eig
private

Definition at line 102 of file chainfdsolver_recursive_newton_euler.hpp.

ChainIdSolver_RNE KDL::ChainFdSolver_RNE::IdSolver
private

Definition at line 97 of file chainfdsolver_recursive_newton_euler.hpp.

Eigen::MatrixXd KDL::ChainFdSolver_RNE::L_eig
private

Definition at line 104 of file chainfdsolver_recursive_newton_euler.hpp.

unsigned int KDL::ChainFdSolver_RNE::nj
private

Definition at line 98 of file chainfdsolver_recursive_newton_euler.hpp.

unsigned int KDL::ChainFdSolver_RNE::ns
private

Definition at line 99 of file chainfdsolver_recursive_newton_euler.hpp.

Eigen::VectorXd KDL::ChainFdSolver_RNE::r_eig
private

Definition at line 106 of file chainfdsolver_recursive_newton_euler.hpp.

JntArray KDL::ChainFdSolver_RNE::Tzeroacc
private

Definition at line 101 of file chainfdsolver_recursive_newton_euler.hpp.

Eigen::VectorXd KDL::ChainFdSolver_RNE::Tzeroacc_eig
private

Definition at line 103 of file chainfdsolver_recursive_newton_euler.hpp.


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


orocos_kdl
Author(s):
autogenerated on Fri Mar 12 2021 03:05:44