23 #ifndef KDL_CHAIN_FDSOLVER_HPP 24 #define KDL_CHAIN_FDSOLVER_HPP This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
Solver interface supporting storage and description of the latest error.
Definition: solveri.hpp:84
Definition: articulatedbodyinertia.cpp:26
std::vector< Wrench > Wrenches
Definition: chainfdsolver.hpp:34
This abstract class encapsulates the inverse dynamics solver for a KDL::Chain.
Definition: chainfdsolver.hpp:41
virtual int CartToJnt(const JntArray &q, const JntArray &q_dot, const JntArray &torques, const Wrenches &f_ext, JntArray &q_dotdot)=0
Calculate forward dynamics from joint positions, joint velocities, joint torques/forces, and externally applied forces/torques to joint accelerations.