Classes | Enumerations
ikfast_kinematics_plugin Namespace Reference

Classes

class  IKFastKinematicsPlugin

Enumerations

enum  IkParameterizationType {
  IKP_None = 0, IKP_Transform6D = 0x67000001, IKP_Rotation3D = 0x34000002, IKP_Translation3D = 0x33000003,
  IKP_Direction3D = 0x23000004, IKP_Ray4D = 0x46000005, IKP_Lookat3D = 0x23000006, IKP_TranslationDirection5D = 0x56000007,
  IKP_TranslationXY2D = 0x22000008, IKP_TranslationXYOrientation3D = 0x33000009, IKP_TranslationLocalGlobal6D = 0x3600000a, IKP_TranslationXAxisAngle4D = 0x4400000b,
  IKP_TranslationYAxisAngle4D = 0x4400000c, IKP_TranslationZAxisAngle4D = 0x4400000d, IKP_TranslationXAxisAngleZNorm4D = 0x4400000e, IKP_TranslationYAxisAngleXNorm4D = 0x4400000f,
  IKP_TranslationZAxisAngleYNorm4D = 0x44000010, IKP_NumberOfParameterizations = 16, IKP_VelocityDataBit, IKP_Transform6DVelocity = IKP_Transform6D | IKP_VelocityDataBit,
  IKP_Rotation3DVelocity = IKP_Rotation3D | IKP_VelocityDataBit, IKP_Translation3DVelocity = IKP_Translation3D | IKP_VelocityDataBit, IKP_Direction3DVelocity = IKP_Direction3D | IKP_VelocityDataBit, IKP_Ray4DVelocity = IKP_Ray4D | IKP_VelocityDataBit,
  IKP_Lookat3DVelocity = IKP_Lookat3D | IKP_VelocityDataBit, IKP_TranslationDirection5DVelocity = IKP_TranslationDirection5D | IKP_VelocityDataBit, IKP_TranslationXY2DVelocity = IKP_TranslationXY2D | IKP_VelocityDataBit, IKP_TranslationXYOrientation3DVelocity = IKP_TranslationXYOrientation3D | IKP_VelocityDataBit,
  IKP_TranslationLocalGlobal6DVelocity = IKP_TranslationLocalGlobal6D | IKP_VelocityDataBit, IKP_TranslationXAxisAngle4DVelocity = IKP_TranslationXAxisAngle4D | IKP_VelocityDataBit, IKP_TranslationYAxisAngle4DVelocity = IKP_TranslationYAxisAngle4D | IKP_VelocityDataBit, IKP_TranslationZAxisAngle4DVelocity = IKP_TranslationZAxisAngle4D | IKP_VelocityDataBit,
  IKP_TranslationXAxisAngleZNorm4DVelocity = IKP_TranslationXAxisAngleZNorm4D | IKP_VelocityDataBit, IKP_TranslationYAxisAngleXNorm4DVelocity = IKP_TranslationYAxisAngleXNorm4D | IKP_VelocityDataBit, IKP_TranslationZAxisAngleYNorm4DVelocity = IKP_TranslationZAxisAngleYNorm4D | IKP_VelocityDataBit, IKP_UniqueIdMask = 0x0000ffff,
  IKP_CustomDataBit = 0x00010000
}
 The types of inverse kinematics parameterizations supported. More...

Enumeration Type Documentation

The types of inverse kinematics parameterizations supported.

The minimum degree of freedoms required is set in the upper 4 bits of each type. The number of values used to represent the parameterization ( >= dof ) is the next 4 bits. The lower bits contain a unique id of the type.

Enumerator:
IKP_None 
IKP_Transform6D 

end effector reaches desired 6D transformation

IKP_Rotation3D 

end effector reaches desired 3D rotation

IKP_Translation3D 

end effector origin reaches desired 3D translation

IKP_Direction3D 

direction on end effector coordinate system reaches desired direction

IKP_Ray4D 

ray on end effector coordinate system reaches desired global ray

IKP_Lookat3D 

direction on end effector coordinate system points to desired 3D position

IKP_TranslationDirection5D 

end effector origin and direction reaches desired 3D translation and

IKP_TranslationXY2D 

2D translation along XY plane

direction. Can be thought of as Ray IK where the origin of the ray must coincide.

IKP_TranslationXYOrientation3D 

2D translation along XY plane and 1D rotation around Z axis. The

IKP_TranslationLocalGlobal6D 

local point on end effector origin reaches desired 3D global point

offset of the rotation is measured starting at +X, so at +X is it 0, at +Y it is pi/2.

IKP_TranslationXAxisAngle4D 

end effector origin reaches desired 3D translation, manipulator

IKP_TranslationYAxisAngle4D 

direction makes a specific angle with x-axis like a cone, angle is from 0-pi. Axes defined in the manipulator base link's coordinate system) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationZAxisAngle4D 

direction makes a specific angle with y-axis like a cone, angle is from 0-pi. Axes defined in the manipulator base link's coordinate system) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationXAxisAngleZNorm4D 

direction makes a specific angle with z-axis like a cone, angle is from 0-pi. Axes are defined in the manipulator base link's coordinate system. end effector origin reaches desired 3D translation, manipulator

IKP_TranslationYAxisAngleXNorm4D 

direction needs to be orthogonal to z-axis and be rotated at a certain angle starting from the x-axis (defined in the manipulator base link's coordinate system) end effector origin reaches desired 3D translation, manipulator

IKP_TranslationZAxisAngleYNorm4D 

direction needs to be orthogonal to x-axis and be rotated at a certain angle starting from the y-axis (defined in the manipulator base link's coordinate system) end effector origin reaches desired 3D translation, manipulator

IKP_NumberOfParameterizations 

number of parameterizations (does not count IKP_None)

direction needs to be orthogonal to y-axis and be rotated at a certain angle starting from the z-axis (defined in the manipulator base link's coordinate system)

IKP_VelocityDataBit 

bit is set if the data represents the time-derivate velocity of an IkParameterization

IKP_Transform6DVelocity 
IKP_Rotation3DVelocity 
IKP_Translation3DVelocity 
IKP_Direction3DVelocity 
IKP_Ray4DVelocity 
IKP_Lookat3DVelocity 
IKP_TranslationDirection5DVelocity 
IKP_TranslationXY2DVelocity 
IKP_TranslationXYOrientation3DVelocity 
IKP_TranslationLocalGlobal6DVelocity 
IKP_TranslationXAxisAngle4DVelocity 
IKP_TranslationYAxisAngle4DVelocity 
IKP_TranslationZAxisAngle4DVelocity 
IKP_TranslationXAxisAngleZNorm4DVelocity 
IKP_TranslationYAxisAngleXNorm4DVelocity 
IKP_TranslationZAxisAngleYNorm4DVelocity 
IKP_UniqueIdMask 

the mask for the unique ids

IKP_CustomDataBit 

bit is set if the ikparameterization contains custom data, this is only used

Definition at line 72 of file ikfast61_moveit_plugin_template.cpp.



moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Wed Jun 19 2019 19:24:24