This abstract class encapsulates the inverse acceleration solver for a KDL::Chain.  
 More...
#include <chainiksolver.hpp>
|  | 
| 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_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 int | CartTojnt (const JntArray &q_init, const FrameAcc &a_in, JntArrayAcc &q_out)=0 | 
|  | 
| virtual void | updateInternalDataStructures ()=0 | 
|  | 
| virtual | ~ChainIkSolverAcc () | 
|  | 
| virtual int | getError () const | 
|  | Return the latest error.  More... 
 | 
|  | 
|  | SolverI () | 
|  | Initialize latest error to E_NOERROR.  More... 
 | 
|  | 
| virtual const char * | strError (const int error) const | 
|  | 
| virtual | ~SolverI () | 
|  | 
|  | 
| enum | { E_DEGRADED = +1, 
E_NOERROR = 0, 
E_NO_CONVERGE = -1, 
E_UNDEFINED = -2,
 E_NOT_UP_TO_DATE = -3, 
E_SIZE_MISMATCH = -4, 
E_MAX_ITERATIONS_EXCEEDED = -5, 
E_OUT_OF_RANGE = -6,
 E_NOT_IMPLEMENTED = -7, 
E_SVD_FAILED = -8
 }
 | 
|  | 
| int | error | 
|  | Latest error, initialized to E_NOERROR in constructor.  More... 
 | 
|  | 
This abstract class encapsulates the inverse acceleration solver for a KDL::Chain. 
Definition at line 102 of file chainiksolver.hpp.
◆ ~ChainIkSolverAcc()
  
  | 
        
          | virtual KDL::ChainIkSolverAcc::~ChainIkSolverAcc | ( |  | ) |  |  | inlinevirtual | 
 
 
◆ CartToJnt() [1/2]
Calculate inverse acceleration kinematics from joint positions, joint velocities and cartesian acceleration to joint accelerations.
- Parameters
- 
  
    | q_in | input joint positions |  | qdot_in | input joint velocities |  | a_in | input cartesian acceleration |  | qdotdot_out | output joint accelerations |  
 
- Returns
- if < 0 something went wrong 
 
 
◆ CartToJnt() [2/2]
Calculate inverse velocity and acceleration kinematics from joint positions and cartesian velocity and acceleration to joint velocities and accelerations.
- Parameters
- 
  
    | 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 |  
 
- Returns
- if < 0 something went wrong 
 
 
◆ CartTojnt() [1/2]
Calculate inverse position and acceleration kinematics from joint velocities and cartesian position and acceleration to joint positions and accelerations
- Parameters
- 
  
    | 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 |  
 
- Returns
- if < 0 something went wrong 
 
 
◆ CartTojnt() [2/2]
Calculate inverse position, velocity and acceration kinematics from cartesian coordinates to joint coordinates
- Parameters
- 
  
    | q_init | initial guess for joint positions |  | a_in | input cartesian position, velocity and acceleration |  | q_out | output joint position, velocity and acceleration |  
 
- Returns
- if < 0 something went wrong 
 
 
◆ updateInternalDataStructures()
  
  | 
        
          | 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.
 
 
The documentation for this class was generated from the following file: