This abstract class encapsulates the inverse acceleration solver for a KDL::Chain. More...
#include <chainiksolver.hpp>

Public Member Functions | |
| virtual int | CartToJnt (const JntArray &q_in, const JntArray &qdot_in, const Twist a_in, JntArray &qdotdot_out)=0 |
| virtual int | CartTojnt (const JntArray &q_init, const FrameAcc &a_in, JntArrayAcc &q_out)=0 |
| virtual int | CartToJnt (const JntArray &q_in, const Twist &v_in, const Twist &a_in, JntArray &qdot_out, JntArray &qdotdot_out)=0 |
| virtual int | CartTojnt (const JntArray &q_init, const Frame &p_in, const JntArray &qdot_in, const Twist &a_in, JntArray &q_out, JntArray &qdotdot_out)=0 |
| virtual void | updateInternalDataStructures ()=0 |
| virtual | ~ChainIkSolverAcc () |
This abstract class encapsulates the inverse acceleration solver for a KDL::Chain.
Definition at line 102 of file chainiksolver.hpp.
| virtual KDL::ChainIkSolverAcc::~ChainIkSolverAcc | ( | ) | [inline, virtual] |
Definition at line 163 of file chainiksolver.hpp.
| virtual int KDL::ChainIkSolverAcc::CartToJnt | ( | const JntArray & | q_in, |
| const JntArray & | qdot_in, | ||
| const Twist | a_in, | ||
| JntArray & | qdotdot_out | ||
| ) | [pure virtual] |
Calculate inverse acceleration kinematics from joint positions, joint velocities and cartesian acceleration to joint accelerations.
| q_in | input joint positions |
| qdot_in | input joint velocities |
| a_in | input cartesian acceleration |
| qdotdot_out | output joint accelerations |
| virtual int KDL::ChainIkSolverAcc::CartTojnt | ( | const JntArray & | q_init, |
| const FrameAcc & | a_in, | ||
| JntArrayAcc & | q_out | ||
| ) | [pure virtual] |
Calculate inverse position, velocity and acceration kinematics from cartesian coordinates to joint coordinates
| q_init | initial guess for joint positions |
| a_in | input cartesian position, velocity and acceleration |
| q_out | output joint position, velocity and acceleration |
| virtual int KDL::ChainIkSolverAcc::CartToJnt | ( | const JntArray & | q_in, |
| const Twist & | v_in, | ||
| const Twist & | a_in, | ||
| JntArray & | qdot_out, | ||
| JntArray & | qdotdot_out | ||
| ) | [pure virtual] |
Calculate inverse velocity and acceleration kinematics from joint positions and cartesian velocity and acceleration to joint velocities and accelerations.
| q_in | input joint positions |
| v_in | input cartesian velocity |
| a_in | input cartesian acceleration |
| qdot_out | output joint velocities |
| qdotdot_out | output joint accelerations |
| virtual int KDL::ChainIkSolverAcc::CartTojnt | ( | const JntArray & | q_init, |
| const Frame & | p_in, | ||
| const JntArray & | qdot_in, | ||
| const Twist & | a_in, | ||
| JntArray & | q_out, | ||
| JntArray & | qdotdot_out | ||
| ) | [pure virtual] |
Calculate inverse position and acceleration kinematics from joint velocities and cartesian position and acceleration to joint positions and accelerations
| q_init | initial guess for joint positions |
| p_in | input cartesian position |
| qdot_in | input joint velocities |
| a_in | input cartesian acceleration |
| q_out | output joint positions |
| qdotdot_out | output joint accelerations |
| virtual void KDL::ChainIkSolverAcc::updateInternalDataStructures | ( | ) | [pure virtual] |
Update the internal data structures. This is required if the number of segments or number of joints of a chain/tree have changed. This provides a single point of contact for solver memory allocations.
Implements KDL::SolverI.