KDL  1.4.0
Public Types | Public Member Functions | Protected Attributes | List of all members
KDL::ChainIkSolverAcc Class Referenceabstract

This abstract class encapsulates the inverse acceleration solver for a KDL::Chain. More...

#include <src/chainiksolver.hpp>

Inheritance diagram for KDL::ChainIkSolverAcc:
Inheritance graph
[legend]
Collaboration diagram for KDL::ChainIkSolverAcc:
Collaboration graph
[legend]

Public Types

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
}
 

Public Member Functions

virtual int CartToJnt (const JntArray &q_in, const JntArray &qdot_in, const Twist a_in, JntArray &qdotdot_out)=0
 Calculate inverse acceleration kinematics from joint positions, joint velocities and cartesian acceleration to joint accelerations. More...
 
virtual int CartTojnt (const JntArray &q_init, const FrameAcc &a_in, JntArrayAcc &q_out)=0
 Calculate inverse position, velocity and acceration kinematics from cartesian coordinates to joint coordinates. More...
 
virtual int CartToJnt (const JntArray &q_in, const Twist &v_in, const Twist &a_in, JntArray &qdot_out, JntArray &qdotdot_out)=0
 Calculate inverse velocity and acceleration kinematics from joint positions and cartesian velocity and acceleration to joint velocities and accelerations. More...
 
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
 Calculate inverse position and acceleration kinematics from joint velocities and cartesian position and acceleration to joint positions and accelerations. More...
 
virtual void updateInternalDataStructures ()=0
 Update the internal data structures. More...
 
virtual ~ChainIkSolverAcc ()
 
virtual int getError () const
 Return the latest error. More...
 
virtual const char * strError (const int error) const
 Return a description of the latest error. More...
 

Protected Attributes

int error
 Latest error, initialized to E_NOERROR in constructor. More...
 

Detailed Description

This abstract class encapsulates the inverse acceleration solver for a KDL::Chain.

Member Enumeration Documentation

§ anonymous enum

anonymous enum
inherited
Enumerator
E_DEGRADED 

Converged but degraded solution (e.g. WDLS with psuedo-inverse singular)

E_NOERROR 

No error.

E_NO_CONVERGE 

Failed to converge.

E_UNDEFINED 

Undefined value (e.g. computed a NAN, or tan(90 degrees) )

E_NOT_UP_TO_DATE 

Chain size changed.

E_SIZE_MISMATCH 

Input size does not match internal state.

E_MAX_ITERATIONS_EXCEEDED 

Maximum number of iterations exceeded.

E_OUT_OF_RANGE 

Requested index out of range.

E_NOT_IMPLEMENTED 

Not yet implemented.

E_SVD_FAILED 

Internal svd calculation failed.

Constructor & Destructor Documentation

§ ~ChainIkSolverAcc()

virtual KDL::ChainIkSolverAcc::~ChainIkSolverAcc ( )
inlinevirtual

Member Function Documentation

§ CartToJnt() [1/2]

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.

Parameters
q_ininput joint positions
qdot_ininput joint velocities
a_ininput cartesian acceleration
qdotdot_outoutput joint accelerations
Returns
if < 0 something went wrong

§ CartTojnt() [1/2]

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.

Parameters
q_initinitial guess for joint positions
a_ininput cartesian position, velocity and acceleration
q_outoutput joint position, velocity and acceleration
Returns
if < 0 something went wrong

§ CartToJnt() [2/2]

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.

Parameters
q_ininput joint positions
v_ininput cartesian velocity
a_ininput cartesian acceleration
qdot_outoutput joint velocities
qdotdot_outoutput joint accelerations
Returns
if < 0 something went wrong

§ CartTojnt() [2/2]

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.

Parameters
q_initinitial guess for joint positions
p_ininput cartesian position
qdot_ininput joint velocities
a_ininput cartesian acceleration
q_outoutput joint positions
qdotdot_outoutput joint accelerations
Returns
if < 0 something went wrong

§ getError()

virtual int KDL::SolverI::getError ( ) const
inlinevirtualinherited

Return the latest error.

References KDL::SolverI::error.

§ strError()

virtual const char* KDL::SolverI::strError ( const int  error) const
inlinevirtualinherited

§ 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.

Member Data Documentation

§ error

int KDL::SolverI::error
protectedinherited

The documentation for this class was generated from the following file: