Recursive newton euler forward dynamics solver. More...
#include <chainfdsolver_recursive_newton_euler.hpp>
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 (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 Chain & | chain |
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... | |
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 for the solver, it will allocate all the necessary memory
chain | The kinematic chain to calculate the forward dynamics for, an internal copy will be made. |
grav | The gravity vector to use during the calculation. |
Definition at line 29 of file chainfdsolver_recursive_newton_euler.cpp.
|
inline |
Definition at line 50 of file chainfdsolver_recursive_newton_euler.hpp.
|
virtual |
Function to calculate from Cartesian forces to joint torques. Input parameters;
q | The current joint positions |
q_dot | The current joint velocities |
torques | The current joint torques (applied by controller) |
f_ext | The external forces (no gravity) on the segments Output parameters: |
q_dotdot | The resulting joint accelerations |
Implements KDL::ChainFdSolver.
Definition at line 51 of file chainfdsolver_recursive_newton_euler.cpp.
void KDL::ChainFdSolver_RNE::RK4Integrator | ( | 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;
nj | The number of joints |
t | The current time |
dt | The integration period |
q | The current joint positions |
q_dot | The current joint velocities |
torques | The current joint torques (applied by controller) |
f_ext | The external forces (no gravity) on the segments |
fdsolver | The forward dynamics solver Output parameters: |
t | The updated time |
q | The updated joint positions |
q_dot | The updated joint velocities |
q_dotdot | The current joint accelerations |
dq | The joint position increment |
dq_dot | The joint velocity increment Temporary parameters: |
qtemp | Intermediate joint positions |
qdtemp | Intermediate joint velocities |
Definition at line 95 of file chainfdsolver_recursive_newton_euler.cpp.
|
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.
|
private |
Definition at line 107 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 95 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 105 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 96 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 101 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 102 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 97 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 104 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 98 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 99 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 106 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 100 of file chainfdsolver_recursive_newton_euler.hpp.
|
private |
Definition at line 103 of file chainfdsolver_recursive_newton_euler.hpp.