#include <chainiksolvervel_pinv.hpp>
Public Member Functions | |
virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out) |
virtual int | CartToJnt (const JntArray &, const FrameVel &, JntArrayVel &) |
ChainIkSolverVel_pinv (const Chain &chain, double eps=0.00001, int maxiter=150) | |
unsigned int | getNrZeroSigmas () const |
int | getSVDResult () const |
virtual const char * | strError (const int error) const |
virtual void | updateInternalDataStructures () |
~ChainIkSolverVel_pinv () | |
Public Member Functions inherited from KDL::ChainIkSolverVel | |
virtual | ~ChainIkSolverVel () |
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 | ~SolverI () |
Static Public Attributes | |
static const int | E_CONVERGE_PINV_SINGULAR = +100 |
solution converged but (pseudo)inverse is singular More... | |
Private Attributes | |
const Chain & | chain |
double | eps |
Jacobian | jac |
ChainJntToJacSolver | jnt2jac |
int | maxiter |
unsigned int | nj |
unsigned int | nrZeroSigmas |
JntArray | S |
SVD_HH | svd |
int | svdResult |
JntArray | tmp |
std::vector< JntArray > | U |
std::vector< JntArray > | V |
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 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.
Definition at line 40 of file chainiksolvervel_pinv.hpp.
|
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 |
Definition at line 26 of file chainiksolvervel_pinv.cpp.
KDL::ChainIkSolverVel_pinv::~ChainIkSolverVel_pinv | ( | ) |
Definition at line 57 of file chainiksolvervel_pinv.cpp.
|
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.
Definition at line 62 of file chainiksolvervel_pinv.cpp.
|
inlinevirtual |
not (yet) implemented.
Implements KDL::ChainIkSolverVel.
Definition at line 80 of file chainiksolvervel_pinv.hpp.
|
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
Definition at line 87 of file chainiksolvervel_pinv.hpp.
|
inline |
Retrieve the latest return code from the SVD algorithm
Definition at line 93 of file chainiksolvervel_pinv.hpp.
|
virtual |
Return a description of the latest error
Reimplemented from KDL::SolverI.
Definition at line 132 of file chainiksolvervel_pinv.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::ChainIkSolverVel.
Definition at line 43 of file chainiksolvervel_pinv.cpp.
|
private |
Definition at line 101 of file chainiksolvervel_pinv.hpp.
|
static |
solution converged but (pseudo)inverse is singular
Definition at line 44 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 110 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 104 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 102 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 111 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 103 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 112 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 107 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 105 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 113 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 109 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 106 of file chainiksolvervel_pinv.hpp.
|
private |
Definition at line 108 of file chainiksolvervel_pinv.hpp.