KDL
1.4.0
|
Implementation of a inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain. More...
#include <src/chainiksolvervel_pinv.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 | |
ChainIkSolverVel_pinv (const Chain &chain, double eps=0.00001, int maxiter=150) | |
Constructor of the solver. More... | |
~ChainIkSolverVel_pinv () | |
virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out) |
Find an output joint velocity qdot_out, given a starting joint pose q_init and a desired cartesian velocity v_in. More... | |
virtual int | CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out) |
not (yet) implemented. More... | |
unsigned int | getNrZeroSigmas () const |
Retrieve the number of singular values of the jacobian that are < eps; if the number of near zero singular values is > jac.col()-jac.row(), then the jacobian pseudoinverse is singular. More... | |
int | getSVDResult () const |
Retrieve the latest return code from the SVD algorithm. More... | |
virtual const char * | strError (const int error) const |
Return a description of the latest error. More... | |
virtual void | updateInternalDataStructures () |
Update the internal data structures. More... | |
virtual int | getError () const |
Return the latest error. More... | |
Static Public Attributes | |
static const int | E_CONVERGE_PINV_SINGULAR = +100 |
solution converged but (pseudo)inverse is singular More... | |
Protected Attributes | |
int | error |
Latest error, initialized to E_NOERROR in constructor. More... | |
Private Attributes | |
const Chain & | chain |
ChainJntToJacSolver | jnt2jac |
unsigned int | nj |
Jacobian | jac |
SVD_HH | svd |
std::vector< JntArray > | U |
JntArray | S |
std::vector< JntArray > | V |
JntArray | tmp |
double | eps |
int | maxiter |
unsigned int | nrZeroSigmas |
int | svdResult |
Implementation of a inverse velocity kinematics algorithm based on the generalize pseudo inverse to calculate the velocity transformation from Cartesian to joint space of a general KDL::Chain.
It uses a svd-calculation based on householders rotations.
|
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. |
|
explicit |
Constructor of the solver.
chain | the chain to calculate the inverse velocity kinematics for |
eps | if a singular value is below this value, its inverse is set to zero, default: 0.00001 |
maxiter | maximum iterations for the svd calculation, default: 150 |
KDL::ChainIkSolverVel_pinv::~ChainIkSolverVel_pinv | ( | ) |
|
virtual |
Find an output joint velocity qdot_out, given a starting joint pose q_init and a desired cartesian velocity v_in.
Implements KDL::ChainIkSolverVel.
References chain, KDL::Jacobian::columns(), KDL::JntArray::data, E_CONVERGE_PINV_SINGULAR, KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::E_SVD_FAILED, eps, KDL::SolverI::error, KDL::Chain::getNrOfJoints(), jac, jnt2jac, KDL::ChainJntToJacSolver::JntToJac(), maxiter, nj, nrZeroSigmas, KDL::Jacobian::rows(), KDL::JntArray::rows(), S, svd, svdResult, tmp, U, and V.
|
inlinevirtual |
not (yet) implemented.
Implements KDL::ChainIkSolverVel.
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
inline |
Retrieve the number of singular values of the jacobian that are < eps; if the number of near zero singular values is > jac.col()-jac.row(), then the jacobian pseudoinverse is singular.
References nrZeroSigmas.
|
inline |
Retrieve the latest return code from the SVD algorithm.
References KDL::SolverI::error, strError(), svdResult, and updateInternalDataStructures().
|
virtual |
Return a description of the latest error.
Reimplemented from KDL::SolverI.
References E_CONVERGE_PINV_SINGULAR, and KDL::SolverI::strError().
Referenced by getSVDResult().
|
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::ChainIkSolverVel.
References chain, KDL::Chain::getNrOfJoints(), jac, jnt2jac, nj, KDL::Jacobian::resize(), KDL::JntArray::resize(), S, svd, tmp, U, KDL::ChainJntToJacSolver::updateInternalDataStructures(), and V.
Referenced by getSVDResult().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
static |
solution converged but (pseudo)inverse is singular
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(), CartToJnt(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::ChainIkSolverPos_LMA::CartToJnt(), KDL::SolverI::getError(), KDL::ChainIkSolverVel_wdls::getSigma(), 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().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and getNrZeroSigmas().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and getSVDResult().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().
|
private |
Referenced by CartToJnt(), and updateInternalDataStructures().