KDL
1.3.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_nso.hpp>
Public Types | |
enum | { E_DEGRADED = +1, E_NOERROR = 0, E_NO_CONVERGE = -1, E_UNDEFINED = -2 } |
Public Member Functions | |
ChainIkSolverVel_pinv_nso (const Chain &chain, JntArray opt_pos, JntArray weights, double eps=0.00001, int maxiter=150, double alpha=0.25) | |
Constructor of the solver. More... | |
ChainIkSolverVel_pinv_nso (const Chain &chain, double eps=0.00001, int maxiter=150, double alpha=0.25) | |
~ChainIkSolverVel_pinv_nso () | |
virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, JntArray &qdot_out) |
Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities. More... | |
virtual int | CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out) |
not (yet) implemented. More... | |
virtual int | setWeights (const JntArray &weights) |
Set joint weights for optimization criterion. More... | |
virtual int | setOptPos (const JntArray &opt_pos) |
Set optimal joint positions. More... | |
virtual int | setAlpha (const double alpha) |
Set null psace velocity gain. 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 |
ChainJntToJacSolver | jnt2jac |
Jacobian | jac |
SVD_HH | svd |
std::vector< JntArray > | U |
JntArray | S |
std::vector< JntArray > | V |
JntArray | tmp |
JntArray | tmp2 |
double | eps |
int | maxiter |
double | alpha |
JntArray | weights |
JntArray | opt_pos |
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.
In case of a redundant robot this solver optimizes the the following criterium: g=0.5*sum(weight*(Desired_joint_positions - actual_joint_positions))^2 as described in A. Liegeois. Automatic supervisory control of the configuration and behavior of multibody mechnisms. IEEE Transactions on Systems, Man, and Cybernetics, 7(12):868–871, 1977
|
inherited |
KDL::ChainIkSolverVel_pinv_nso::ChainIkSolverVel_pinv_nso | ( | const Chain & | chain, |
JntArray | opt_pos, | ||
JntArray | weights, | ||
double | eps = 0.00001 , |
||
int | maxiter = 150 , |
||
double | alpha = 0.25 |
||
) |
Constructor of the solver.
chain | the chain to calculate the inverse velocity kinematics for |
opt_pos | the desired positions of the chain used by to resolve the redundancy |
weights | the weights applied in the joint space |
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 |
alpha | the null-space velocity gain |
|
explicit |
KDL::ChainIkSolverVel_pinv_nso::~ChainIkSolverVel_pinv_nso | ( | ) |
|
virtual |
Calculate inverse velocity kinematics, from joint positions and cartesian velocity to joint velocities.
q_in | input joint positions |
v_in | input cartesian velocity |
qdot_out | output joint velocities |
Implements KDL::ChainIkSolverVel.
References alpha, KDL::Jacobian::columns(), eps, jac, jnt2jac, KDL::ChainJntToJacSolver::JntToJac(), maxiter, opt_pos, KDL::Jacobian::rows(), S, svd, tmp, tmp2, U, V, and weights.
|
inlinevirtual |
not (yet) implemented.
Implements KDL::ChainIkSolverVel.
|
inlinevirtualinherited |
Return the latest error.
References KDL::SolverI::error.
|
virtual |
|
virtual |
|
virtual |
Set joint weights for optimization criterion.
weights | the joint weights |
References weights.
|
inlinevirtualinherited |
Return a description of the latest error.
Reimplemented in KDL::ChainIkSolverVel_wdls, KDL::ChainIkSolverVel_pinv, KDL::ChainIkSolverPos_NR, and KDL::ChainJntToJacSolver.
References KDL::SolverI::E_NO_CONVERGE, KDL::SolverI::E_NOERROR, and KDL::SolverI::error.
Referenced by KDL::ChainJntToJacSolver::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverVel_pinv::strError(), and KDL::ChainIkSolverVel_wdls::strError().
|
private |
Referenced by CartToJnt(), and setAlpha().
|
private |
|
private |
Referenced by CartToJnt().
|
protectedinherited |
Latest error, initialized to E_NOERROR in constructor.
Referenced by KDL::ChainIkSolverPos_NR::CartToJnt(), KDL::ChainIkSolverVel_pinv::CartToJnt(), KDL::ChainIkSolverVel_wdls::CartToJnt(), KDL::SolverI::getError(), KDL::ChainJntToJacSolver::JntToJac(), KDL::ChainJntToJacSolver::strError(), KDL::ChainIkSolverPos_NR::strError(), KDL::ChainIkSolverVel_pinv::strError(), KDL::SolverI::strError(), and KDL::ChainIkSolverVel_wdls::strError().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt(), and setOptPos().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt().
|
private |
Referenced by CartToJnt(), and setWeights().