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 <chainiksolvervel_pinv.hpp>
Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q_init, const FrameVel &v_in, JntArrayVel &q_out) |
| not (yet) implemented. | |
| 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. | |
| ChainIkSolverVel_pinv (const Chain &chain, double eps=0.00001, int maxiter=150) | |
| Constructor of the solver. | |
| ~ChainIkSolverVel_pinv () | |
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.
| KDL::ChainIkSolverVel_pinv::ChainIkSolverVel_pinv | ( | const Chain & | chain, | |
| double | eps = 0.00001, |
|||
| int | maxiter = 150 | |||
| ) |
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 40 of file chainiksolvervel_pinv.cpp.
| virtual int KDL::ChainIkSolverVel_pinv::CartToJnt | ( | const JntArray & | q_init, | |
| const FrameVel & | v_in, | |||
| JntArrayVel & | q_out | |||
| ) | [inline, virtual] |
not (yet) implemented.
Implements KDL::ChainIkSolverVel.
Definition at line 62 of file chainiksolvervel_pinv.hpp.
| int KDL::ChainIkSolverVel_pinv::CartToJnt | ( | const JntArray & | q_in, | |
| const Twist & | v_in, | |||
| JntArray & | qdot_out | |||
| ) | [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.
Definition at line 45 of file chainiksolvervel_pinv.cpp.
References KDL::SVD_HH::calculate(), KDL::Jacobian::columns(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::Jacobian::rows().
1.6.1