KDL
1.4.0
|
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations to calculate the position transformation from Cartesian to joint space of a general KDL::Chain. More...
#include <src/chainiksolverpos_nr_jl.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 | |
ChainIkSolverPos_NR_JL (const Chain &chain, const JntArray &q_min, const JntArray &q_max, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6) | |
Child FK solver failed. More... | |
ChainIkSolverPos_NR_JL (const Chain &chain, ChainFkSolverPos &fksolver, ChainIkSolverVel &iksolver, unsigned int maxiter=100, double eps=1e-6) | |
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain. More... | |
~ChainIkSolverPos_NR_JL () | |
virtual int | CartToJnt (const JntArray &q_init, const Frame &p_in, JntArray &q_out) |
Calculates the joint values that correspond to the input pose given an initial guess. More... | |
int | setJointLimits (const JntArray &q_min, const JntArray &q_max) |
Function to set the joint limits. More... | |
virtual void | updateInternalDataStructures () |
Update the internal data structures. More... | |
const char * | strError (const int error) const |
Return a description of the latest error. More... | |
virtual int | getError () const |
Return the latest error. More... | |
Static Public Attributes | |
static const int | E_IKSOLVERVEL_FAILED = -100 |
static const int | E_FKSOLVERPOS_FAILED = -101 |
Child IK solver vel failed. More... | |
Protected Attributes | |
int | error |
Latest error, initialized to E_NOERROR in constructor. More... | |
Private Attributes | |
const Chain & | chain |
unsigned int | nj |
JntArray | q_min |
JntArray | q_max |
ChainIkSolverVel & | iksolver |
ChainFkSolverPos & | fksolver |
JntArray | delta_q |
unsigned int | maxiter |
double | eps |
Frame | f |
Twist | delta_twist |
Implementation of a general inverse position kinematics algorithm based on Newton-Raphson iterations to calculate the position transformation from Cartesian to joint space of a general KDL::Chain.
Takes joint limits into account.
|
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. |
KDL::ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL | ( | const Chain & | chain, |
const JntArray & | q_min, | ||
const JntArray & | q_max, | ||
ChainFkSolverPos & | fksolver, | ||
ChainIkSolverVel & | iksolver, | ||
unsigned int | maxiter = 100 , |
||
double | eps = 1e-6 |
||
) |
Child FK solver failed.
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
chain | the chain to calculate the inverse position for |
q_min | the minimum joint positions |
q_max | the maximum joint positions |
fksolver | a forward position kinematics solver |
iksolver | an inverse velocity kinematics solver |
maxiter | the maximum Newton-Raphson iterations, default: 100 |
eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
KDL::ChainIkSolverPos_NR_JL::ChainIkSolverPos_NR_JL | ( | const Chain & | chain, |
ChainFkSolverPos & | fksolver, | ||
ChainIkSolverVel & | iksolver, | ||
unsigned int | maxiter = 100 , |
||
double | eps = 1e-6 |
||
) |
Constructor of the solver, it needs the chain, a forward position kinematics solver and an inverse velocity kinematics solver for that chain.
chain | the chain to calculate the inverse position for |
fksolver | a forward position kinematics solver |
iksolver | an inverse velocity kinematics solver |
maxiter | the maximum Newton-Raphson iterations, default: 100 |
eps | the precision for the position, used to end the iterations, default: epsilon (defined in kdl.hpp) |
References KDL::JntArray::data, q_max, and q_min.
KDL::ChainIkSolverPos_NR_JL::~ChainIkSolverPos_NR_JL | ( | ) |
|
virtual |
Calculates the joint values that correspond to the input pose given an initial guess.
q_init | Initial guess for the joint values. |
p_in | The input pose of the chain tip. |
q_out | The resulting output joint values |
Implements KDL::ChainIkSolverPos.
References KDL::Add(), KDL::ChainIkSolverVel::CartToJnt(), chain, delta_q, delta_twist, KDL::diff(), E_FKSOLVERPOS_FAILED, E_IKSOLVERVEL_FAILED, KDL::SolverI::E_MAX_ITERATIONS_EXCEEDED, KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_SIZE_MISMATCH, eps, KDL::Equal(), KDL::SolverI::error, f, fksolver, KDL::Chain::getNrOfJoints(), iksolver, KDL::ChainFkSolverPos::JntToCart(), maxiter, nj, q_max, q_min, KDL::JntArray::rows(), and KDL::Twist::Zero().
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
Function to set the joint limits.
q_min | minimum values for the joints |
q_max | maximum values for the joints |
References KDL::SolverI::E_NOERROR, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::error, nj, q_max, q_min, and KDL::JntArray::rows().
|
virtual |
Return a description of the latest error.
Reimplemented from KDL::SolverI.
References E_FKSOLVERPOS_FAILED, E_IKSOLVERVEL_FAILED, and KDL::SolverI::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::ChainIkSolverPos.
References chain, KDL::JntArray::data, delta_q, fksolver, KDL::Chain::getNrOfJoints(), iksolver, nj, q_max, q_min, KDL::JntArray::resize(), KDL::ChainFkSolverPos::updateInternalDataStructures(), and KDL::ChainIkSolverVel::updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt().
|
static |
Child IK solver vel failed.
Referenced by CartToJnt(), and strError().
|
static |
Referenced by CartToJnt(), and strError().
|
private |
Referenced by CartToJnt().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), KDL::ChainIdSolver_RNE::CartToJnt(), KDL::ChainIkSolverVel_pinv_nso::CartToJnt(), KDL::ChainIdSolver_Vereshchagin::CartToJnt(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), 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(), 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().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt(), setJointLimits(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), ChainIkSolverPos_NR_JL(), setJointLimits(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), ChainIkSolverPos_NR_JL(), setJointLimits(), and updateInternalDataStructures().