Main Page   Modules   Namespace List   Class Hierarchy   Alphabetical List   Compound List   File List   Namespace Members   Compound Members   File Members   Related Pages  

InverseKinematics

The InverseKinematics Library. More...

Compounds

class  IKCCD
class  IKDirectSearch
 This class contains methods for calculating inverse position and velocity solutions for serial manipulators using the Resolved Rate technique. More...

class  IKJacobian
 This class contains methods for calculating inverse position and velocity solutions for serial manipulators using the Resolved Rate technique. More...

class  IKJAvoidLimits
 This class is used to calculate the inverse position solution using a weighting matrix based on the joint limits. More...

class  IKJDLS
 IKJacobian with Damped Least Square (DLS) technique. More...

class  IKJGenerateOptions
 Generates a set of inverse kinematics solutions for redundant serial manipulators. More...

class  IKJReconfig
 Used to calculate the inverse position solution using the active/inactive functionality. More...

class  IKJTranspose
 This class contains methods for calculating inverse position solutions for serial manipulators (especially low DOF manipulators) using the Jacobian Transpose technique. More...

class  IKMitsubishi
 IKMitsubishi Implements a closed form solution for a standard Mitsubishi Robot. More...

class  IKPosition
 IKPosition acts as the base class for inverse position functionality. More...

class  IKPuma
 IKPuma Implements a closed form solution for a standard Puma Robot. More...

class  IKVelocity
 IKVelocity acts as the base class for inverse velocity functionality. More...

class  KinematicsHandler
 KinematicsHandler describes an abstract class for computing the forward and inverse kinematics of serial robot arms. This class also checks for position limits. User should derive a specific class from this or use the GeneralKinematicsHandler class that is derived from KinematicsHandler. This class and dervied classes implement functionality that computes the forward and inverse position solution. It also checks joint travel limits and singularities. Objects of this class will always maintain a valid joint state and the corresponding cartesian state. Inputs that violate position limits or lead to singularities will not lead to an erroneous state of the system. More...


Variables

const OSCARError IKErrors
const OSCARError ikDefinitionError
const OSCARError badLimitsData
const OSCARError minMOTReached
const OSCARError maxIterationCountReached
const OSCARError singularity
const OSCARError illegalNullSpaceSize
const OSCARError outOfReach

Detailed Description

This library contains functionality for calculating inverse position solutions. There are several different inverse kinematics algorithms implemented in this library including: jacobian-based inverse, jacobian-based inverse with active/inactive coordinates, circular descent, direct search, and closed-form puma.

Variable Documentation

const OSCARError OSCAR::badLimitsData
 

The joint limits data provided is not in the correct format or is incomplete.

The joint limits data provided is not in the correct format or is incomplete.

const OSCARError OSCAR::ikDefinitionError
 

const OSCARError OSCAR::IKErrors
 

This error defines the starting point of errors associated with Inverse Kinematics.

This error defines the starting point of errors associated with Inverse Kinematics.

const OSCARError OSCAR::illegalNullSpaceSize
 

The size of null space joints is too large.

The size of null space joints is too large.

const OSCARError OSCAR::maxIterationCountReached
 

During the inverse calculation, the maximum iteration count that was set was reached. This generally indicates a singularity.

During the inverse calculation, the maximum iteration count that was set was reached. This generally indicates a singularity.

const OSCARError OSCAR::minMOTReached
 

During the inverse calculation, the MOT reached the minimum value that was specifed. This generally indicates a singularity.

During the inverse calculation, the MOT reached the minimum value that was specifed. This generally indicates a singularity.

const OSCARError OSCAR::outOfReach
 

The position inverse kinematics calculation fails because the desired handpose is out of the robot's reach.

The position inverse kinematics calculation fails because the desired handpose is out of the robot's reach.

See also:
singularity

const OSCARError OSCAR::singularity
 

Singularity during the inverse kinematics calculation.

Singularity during the inverse kinematics calculation.

See also:
minMOTReached

maxIterationCountReached

RRG Homepage OSCAR Overview OSCAR Tutorials Simulations