|
KDL
1.5.1
|
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers. More...
#include <src/chainjnttojacsolver.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 | |
| ChainJntToJacSolver (const Chain &chain) | |
| virtual | ~ChainJntToJacSolver () |
| virtual int | JntToJac (const JntArray &q_in, Jacobian &jac, int seg_nr=-1) |
| Calculate the jacobian expressed in the base frame of the chain, with reference point at the end effector of the *chain. More... | |
| int | setLockedJoints (const std::vector< bool > locked_joints) |
| 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 |
| Twist | t_tmp |
| Frame | T_tmp |
| std::vector< bool > | locked_joints_ |
Class to calculate the jacobian of a general KDL::Chain, it is used by other solvers.
|
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 |
|
virtual |
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
virtual |
Calculate the jacobian expressed in the base frame of the chain, with reference point at the end effector of the *chain.
The algorithm is similar to the one used in KDL::ChainFkSolverVel_recursive
| q_in | input joint positions |
| jac | output jacobian |
| seg_nr | The final segment to compute |
References chain, KDL::changeRefPoint(), KDL::Jacobian::columns(), KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_OUT_OF_RANGE, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::error, KDL::Joint::Fixed, KDL::Segment::getJoint(), KDL::Chain::getNrOfJoints(), KDL::Chain::getNrOfSegments(), KDL::Chain::getSegment(), KDL::Joint::getType(), KDL::Frame::Identity(), locked_joints_, KDL::Frame::M, KDL::Frame::p, KDL::Segment::pose(), KDL::JntArray::rows(), KDL::Jacobian::setColumn(), KDL::SetToZero(), t_tmp, T_tmp, and KDL::Segment::twist().
Referenced by KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), KDL::ChainIkSolverVel_pinv_nso::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::ChainExternalWrenchEstimator::JntToExtWrench(), and KDL::ChainJntToJacDotSolver::JntToJacDot().
| int KDL::ChainJntToJacSolver::setLockedJoints | ( | const std::vector< bool > | locked_joints | ) |
| locked_joints | new values for locked joints |
References chain, KDL::SolverI::E_NOERROR, KDL::SolverI::E_NOT_UP_TO_DATE, KDL::SolverI::E_SIZE_MISMATCH, KDL::SolverI::error, KDL::Chain::getNrOfJoints(), and locked_joints_.
|
inlinevirtualinherited |
Return a description of the latest error.
Reimplemented in KDL::ChainJntToJacDotSolver, KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverPos_NR_JL, KDL::ChainIkSolverPos_NR, KDL::ChainIkSolverPos_LMA, and KDL::ChainExternalWrenchEstimator.
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::error.
Referenced by KDL::ChainExternalWrenchEstimator::strError(), KDL::ChainIkSolverPos_LMA::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverPos_NR_JL::strError(), KDL::ChainIkSolverVel_pinv::strError(), KDL::ChainIkSolverVel_wdls::strError(), and KDL::ChainJntToJacDotSolver::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 chain, KDL::Chain::getNrOfJoints(), and locked_joints_.
Referenced by KDL::ChainExternalWrenchEstimator::updateInternalDataStructures(), KDL::ChainIkSolverVel_pinv::updateInternalDataStructures(), KDL::ChainIkSolverVel_pinv_givens::updateInternalDataStructures(), KDL::ChainIkSolverVel_pinv_nso::updateInternalDataStructures(), KDL::ChainIkSolverVel_wdls::updateInternalDataStructures(), and KDL::ChainJntToJacDotSolver::updateInternalDataStructures().
|
private |
Referenced by JntToJac(), setLockedJoints(), and updateInternalDataStructures().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIdSolver_RNE::CartToJnt(), KDL::TreeIdSolver_RNE::CartToJnt(), KDL::ChainFdSolver_RNE::CartToJnt(), KDL::ChainHdSolver_Vereshchagin::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverVel_pinv_givens::CartToJnt(), KDL::ChainIkSolverVel_pinv_nso::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverPos_NR_JL::CartToJnt(), KDL::ChainIkSolverPos_LMA::CartToJnt(), KDL::SolverI::getError(), KDL::ChainIkSolverVel_wdls::getSigma(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainExternalWrenchEstimator::JntToExtWrench(), JntToJac(), KDL::ChainJntToJacDotSolver::JntToJacDot(), KDL::ChainDynParam::JntToMass(), KDL::ChainExternalWrenchEstimator::setInitialMomentum(), KDL::ChainIkSolverPos_NR_JL::setJointLimits(), KDL::ChainJntToJacDotSolver::setLockedJoints(), setLockedJoints(), KDL::ChainIkSolverVel_pinv_nso::setOptPos(), KDL::ChainIkSolverVel_wdls::setWeightJS(), KDL::ChainIkSolverVel_pinv_nso::setWeights(), KDL::ChainIkSolverVel_wdls::setWeightTS(), KDL::ChainExternalWrenchEstimator::strError(), KDL::ChainIkSolverPos_LMA::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverPos_NR_JL::strError(), KDL::ChainIkSolverVel_pinv::strError(), KDL::ChainIkSolverVel_wdls::strError(), KDL::ChainJntToJacDotSolver::strError(), and KDL::SolverI::strError().
|
private |
Referenced by JntToJac(), setLockedJoints(), and updateInternalDataStructures().
|
private |
Referenced by JntToJac().
|
private |
Referenced by JntToJac().