This abstract class encapsulates the inverse velocity solver for a KDL::Tree.
More...
#include <src/treeiksolver.hpp>
This abstract class encapsulates the inverse velocity solver for a KDL::Tree.
◆ ~TreeIkSolverVel()
| virtual KDL::TreeIkSolverVel::~TreeIkSolverVel |
( |
| ) |
|
|
inlinevirtual |
◆ CartToJnt()
| virtual double KDL::TreeIkSolverVel::CartToJnt |
( |
const JntArray & | q_in, |
|
|
const Twists & | v_in, |
|
|
JntArray & | qdot_out ) |
|
pure virtual |
Calculate inverse velocity kinematics, from joint positions and cartesian velocities to joint velocities.
- Parameters
-
| q_in | input joint positions |
| v_in | input cartesian velocity |
| qdot_out | output joint velocities |
- Returns
- if < 0 something went wrong distance to goal otherwise (weighted norm of v_in)
Implemented in KDL::TreeIkSolverVel_wdls.
The documentation for this class was generated from the following file: