#include <chaindynparam.hpp>
Public Member Functions | |
ChainDynParam (const Chain &chain, Vector _grav) | |
virtual int | JntToCoriolis (const JntArray &q, const JntArray &q_dot, JntArray &coriolis) |
virtual int | JntToGravity (const JntArray &q, JntArray &gravity) |
virtual int | JntToMass (const JntArray &q, JntSpaceInertiaMatrix &H) |
virtual void | updateInternalDataStructures () |
virtual | ~ChainDynParam () |
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 | |
Twist | ag |
const Chain & | chain |
ChainIdSolver_RNE | chainidsolver_coriolis |
ChainIdSolver_RNE | chainidsolver_gravity |
Wrench | F |
Vector | grav |
std::vector< ArticulatedBodyInertia, Eigen::aligned_allocator< ArticulatedBodyInertia > > | Ic |
JntArray | jntarraynull |
unsigned int | nj |
int | nr |
unsigned int | ns |
std::vector< Twist > | S |
Vector | vectornull |
std::vector< Wrench > | wrenchnull |
std::vector< Frame > | X |
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... | |
Implementation of a method to calculate the matrices H (inertia),C(coriolis) and G(gravitation) for the calculation torques out of the pose and derivatives. (inverse dynamics)
The algorithm implementation for H is based on the book "Rigid Body Dynamics Algorithms" of Roy Featherstone, 2008 (ISBN:978-0-387-74314-1) See page 107 for the pseudo-code. This algorithm is extended for the use of fixed joints
It calculates the joint-space inertia matrix, 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 47 of file chaindynparam.hpp.
Definition at line 29 of file chaindynparam.cpp.
|
virtual |
Definition at line 149 of file chaindynparam.cpp.
|
virtual |
Definition at line 127 of file chaindynparam.cpp.
Definition at line 139 of file chaindynparam.cpp.
|
virtual |
Definition at line 60 of file chaindynparam.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 chaindynparam.cpp.
|
private |
Definition at line 76 of file chaindynparam.hpp.
|
private |
Definition at line 61 of file chaindynparam.hpp.
|
private |
Definition at line 68 of file chaindynparam.hpp.
|
private |
Definition at line 69 of file chaindynparam.hpp.
|
private |
Definition at line 75 of file chaindynparam.hpp.
|
private |
Definition at line 65 of file chaindynparam.hpp.
|
private |
Definition at line 74 of file chaindynparam.hpp.
|
private |
Definition at line 67 of file chaindynparam.hpp.
|
private |
Definition at line 63 of file chaindynparam.hpp.
|
private |
Definition at line 62 of file chaindynparam.hpp.
|
private |
Definition at line 64 of file chaindynparam.hpp.
|
private |
Definition at line 72 of file chaindynparam.hpp.
|
private |
Definition at line 66 of file chaindynparam.hpp.
|
private |
Definition at line 70 of file chaindynparam.hpp.
|
private |
Definition at line 71 of file chaindynparam.hpp.