Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

IKSolver Class Reference

Provides an abstract interface to inverse kinematic solvers. More...

#include <IKSolver.h>

Inheritance diagram for IKSolver:

Detailed Description

Provides an abstract interface to inverse kinematic solvers.

Definition at line 11 of file IKSolver.h.

List of all members.

Classes

struct  Cone
 Cone allows 1-2 freedoms (roll, trade off pitch vs. yaw). More...
struct  Line
 Lines allow 1 freedom, slide along line. More...
struct  Orientation
 abstract base class for orientation information More...
struct  Parallel
 Parallel allows 1 freedom (roll along z vector). More...
struct  Plane
 Planes allow 2 freedoms, move in plane. More...
struct  Point
 Points allow 0 freedoms. More...
struct  Position
 abstract base class for position information More...
struct  Rotation
 Rotation allow 0 freedoms (here specified as a quaternion). More...

Public Types

enum  StepResult_t { SUCCESS, PROGRESS, LIMITS, RANGE }
 

Indicates the type of progress made by the step() family.

More...
typedef FamilyFactory
< IKSolver, std::string,
Factory0Arg< IKSolver > > 
registry_t
 shorthand for type registry to allow dynamically instantiating IKSolvers based on the name found in configuration files

Public Member Functions

virtual ~IKSolver ()
 destructor
virtual bool solve (const Point &pEff, KinematicJoint &j, const Position &pTgt) const
 solve to get an 'effector' point pEff (relative to link following j) to a solution of pTgt (or at least a local minimum)
virtual bool solve (const Rotation &oriEff, KinematicJoint &j, const Orientation &oriTgt) const
 solve to get an 'effector' orientation oriEff (relative to link following j) to a solution of oriTgt (or at least a local minimum)
virtual bool solve (const Point &pEff, const Rotation &oriEff, KinematicJoint &j, const Position &pTgt, float posPri, const Orientation &oriTgt, float oriPri) const =0
 solve to get an 'effector' (pEff, oriEff, relative to link following j) to a solution of pTgt, oriTgt (or at least a local minimum)
virtual StepResult_t step (const Point &pEff, KinematicJoint &j, const Position &pTgt, float pDist) const
 move an 'effector' point pEff (relative to link following j) towards a solution of pTgt (or at least a local minimum)
virtual StepResult_t step (const Rotation &oriEff, KinematicJoint &j, const Orientation &oriTgt, float oriDist) const
 move an 'effector' orientation oriEff (relative to link following j) towards a solution of oriTgt (or at least a local minimum)
virtual StepResult_t step (const Point &pEff, const Rotation &oriEff, KinematicJoint &j, const Position &pTgt, float pDist, float posPri, const Orientation &oriTgt, float oriDist, float oriPri) const =0
 move an 'effector' (pEff, oriEff, relative to link following j) towards a solution of pTgt, oriTgt (or at least a local minimum)

Static Public Member Functions

static registry_tgetRegistry ()

Member Typedef Documentation

shorthand for type registry to allow dynamically instantiating IKSolvers based on the name found in configuration files

Definition at line 156 of file IKSolver.h.


Member Enumeration Documentation

Indicates the type of progress made by the step() family.

Enumerator:
SUCCESS 

goal was reached

PROGRESS 

step moved closer

LIMITS 

not able to progress due to joint limits

RANGE 

not able to progress due to target out of reach

Definition at line 14 of file IKSolver.h.


Constructor & Destructor Documentation

virtual IKSolver::~IKSolver (  )  [virtual]

destructor

Definition at line 120 of file IKSolver.h.


Member Function Documentation

static registry_t& IKSolver::getRegistry (  )  [static]

Definition at line 157 of file IKSolver.h.

Referenced by KinematicJoint::getIK().

virtual bool IKSolver::solve ( const Point pEff,
const Rotation oriEff,
KinematicJoint j,
const Position pTgt,
float  posPri,
const Orientation oriTgt,
float  oriPri 
) const [pure virtual]

solve to get an 'effector' (pEff, oriEff, relative to link following j) to a solution of pTgt, oriTgt (or at least a local minimum)

posPri and oriPri specify relative weighting of each solution in case they are mutually exclusive

Implemented in IKCalliope, IKGradientSolver, IKThreeLink, and PlanarThreeLinkArm.

virtual bool IKSolver::solve ( const Rotation oriEff,
KinematicJoint j,
const Orientation oriTgt 
) const [virtual]

solve to get an 'effector' orientation oriEff (relative to link following j) to a solution of oriTgt (or at least a local minimum)

Definition at line 128 of file IKSolver.h.

virtual StepResult_t IKSolver::step ( const Point pEff,
const Rotation oriEff,
KinematicJoint j,
const Position pTgt,
float  pDist,
float  posPri,
const Orientation oriTgt,
float  oriDist,
float  oriPri 
) const [pure virtual]

move an 'effector' (pEff, oriEff, relative to link following j) towards a solution of pTgt, oriTgt (or at least a local minimum)

pDist and oriDist specifies the maximum distance to move towards each solution; posPri and oriPri specify relative weighting of each solution in case they are mutually exclusive

Implemented in IKCalliope, IKGradientSolver, IKThreeLink, and PlanarThreeLinkArm.

virtual StepResult_t IKSolver::step ( const Rotation oriEff,
KinematicJoint j,
const Orientation oriTgt,
float  oriDist 
) const [virtual]

move an 'effector' orientation oriEff (relative to link following j) towards a solution of oriTgt (or at least a local minimum)

oriDist specifies the maximum distance to move in radians

Definition at line 145 of file IKSolver.h.

virtual StepResult_t IKSolver::step ( const Point pEff,
KinematicJoint j,
const Position pTgt,
float  pDist 
) const [virtual]

move an 'effector' point pEff (relative to link following j) towards a solution of pTgt (or at least a local minimum)

pDist specifies the maximum distance to move

Definition at line 139 of file IKSolver.h.

Referenced by step().


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

Tekkotsu v5.1CVS
Generated Tue Jan 31 04:32:20 2012 by Doxygen 1.6.3