This abstract class encapsulates the inverse dynamics solver for a KDL::Tree. More...
#include <treeidsolver.hpp>

Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const WrenchMap &f_ext, JntArray &torques)=0 |
This abstract class encapsulates the inverse dynamics solver for a KDL::Tree.
Definition at line 40 of file treeidsolver.hpp.
| virtual int KDL::TreeIdSolver::CartToJnt | ( | const JntArray & | q, |
| const JntArray & | q_dot, | ||
| const JntArray & | q_dotdot, | ||
| const WrenchMap & | f_ext, | ||
| JntArray & | torques | ||
| ) | [pure virtual] |
Calculate inverse dynamics, from joint positions, velocity, acceleration, external forces to joint torques/forces.
| q | input joint positions |
| q_dot | input joint velocities |
| q_dotdot | input joint accelerations |
| f_ext | the external forces (no gravity) on the segments |
| torque | output joint torques |
Implemented in KDL::TreeIdSolver_RNE.