KDL
1.4.0
|
Recursive newton euler inverse dynamics solver. More...
#include <src/chainidsolver_recursive_newton_euler.hpp>
Public Types | |
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 } |
Public Member Functions | |
ChainIdSolver_RNE (const Chain &chain, Vector grav) | |
Constructor for the solver, it will allocate all the necessary memory. More... | |
~ChainIdSolver_RNE () | |
int | CartToJnt (const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext, JntArray &torques) |
Function to calculate from Cartesian forces to joint torques. More... | |
virtual void | updateInternalDataStructures () |
Update the internal data structures. More... | |
virtual int | getError () const |
Return the latest error. More... | |
virtual const char * | strError (const int error) const |
Return a description of the latest error. More... | |
Protected Attributes | |
int | error |
Latest error, initialized to E_NOERROR in constructor. More... | |
Private Attributes | |
const Chain & | chain |
unsigned int | nj |
unsigned int | ns |
std::vector< Frame > | X |
std::vector< Twist > | S |
std::vector< Twist > | v |
std::vector< Twist > | a |
std::vector< Wrench > | f |
Twist | ag |
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.
|
inherited |
Enumerator | |
---|---|
E_DEGRADED | Converged but degraded solution (e.g. WDLS with psuedo-inverse singular) |
E_NOERROR | No error. |
E_NO_CONVERGE | Failed to converge. |
E_UNDEFINED | Undefined value (e.g. computed a NAN, or tan(90 degrees) ) |
E_NOT_UP_TO_DATE | Chain size changed. |
E_SIZE_MISMATCH | Input size does not match internal state. |
E_MAX_ITERATIONS_EXCEEDED | Maximum number of iterations exceeded. |
E_OUT_OF_RANGE | Requested index out of range. |
E_NOT_IMPLEMENTED | Not yet implemented. |
E_SVD_FAILED | Internal svd calculation failed. |
Constructor for the solver, it will allocate all the necessary memory.
chain | The kinematic chain to calculate the inverse dynamics for, an internal copy will be made. |
grav | The gravity vector to use during the calculation. |
References ag, and KDL::Vector::Zero().
|
inline |
References CartToJnt(), and updateInternalDataStructures().
|
virtual |
Function to calculate from Cartesian forces to joint torques.
Input parameters;
q | The current joint positions |
q_dot | The current joint velocities |
q_dotdot | The current joint accelerations |
f_ext | The external forces (no gravity) on the segments Output parameters: |
torques | the resulting torques for the joints |
Implements KDL::ChainIdSolver.
References a, ag, chain, KDL::dot(), KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::error, f, KDL::Segment::getInertia(), KDL::Segment::getJoint(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), KDL::Joint::getType(), nj, KDL::Joint::None, ns, KDL::Segment::pose(), KDL::JntArray::rows(), S, KDL::Segment::twist(), v, and X.
Referenced by KDL::ChainDynParam::JntToCoriolis(), KDL::ChainDynParam::JntToGravity(), and ~ChainIdSolver_RNE().
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
inlinevirtualinherited |
Return a description of the latest error.
Reimplemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverPos_LMA, KDL::ChainJntToJacDotSolver, KDL::ChainIkSolverPos_NR_JL, KDL::ChainIkSolverVel_pinv, and KDL::ChainIkSolverPos_NR.
References KDL::SolverI::E_DEGRADED, KDL::SolverI::E_MAX_ITERATIONS_EXCEEDED, KDL::SolverI::E_NO_CONVERGE, KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_IMPLEMENTED, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_OUT_OF_RANGE, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::E_SVD_FAILED, KDL::SolverI::E_UNDEFINED, and KDL::SolverI::updateInternalDataStructures().
Referenced by KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverVel_pinv::strError(), KDL::ChainIkSolverPos_NR_JL::strError(), KDL::ChainJntToJacDotSolver::strError(), KDL::ChainIkSolverPos_LMA::strError(), and KDL::ChainIkSolverVel_wdls::strError().
|
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.
References a, chain, f, KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), nj, ns, S, v, and X.
Referenced by KDL::ChainDynParam::updateInternalDataStructures(), and ~ChainIdSolver_RNE().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and ChainIdSolver_RNE().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), CartToJnt(), KDL::ChainIkSolverVel_pinv_nso::CartToJnt(), KDL::ChainIdSolver_Vereshchagin::CartToJnt(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::ChainIkSolverPos_LMA::CartToJnt(), KDL::SolverI::getError(), KDL::ChainIkSolverVel_wdls::getSigma(), KDL::ChainIkSolverVel_pinv::getSVDResult(), KDL::ChainIkSolverVel_wdls::getSVDResult(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::ChainDynParam::JntToMass(), KDL::ChainJntToJacDotSolver::setInternialRepresentation(), KDL::ChainIkSolverPos_NR_JL::setJointLimits(), KDL::ChainJntToJacSolver::setLockedJoints(), KDL::ChainJntToJacDotSolver::setLockedJoints(), KDL::ChainIkSolverVel_pinv_nso::setOptPos(), KDL::ChainIkSolverVel_wdls::setWeightJS(), KDL::ChainIkSolverVel_pinv_nso::setWeights(), and KDL::ChainIkSolverVel_wdls::setWeightTS().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().