Main Page | Modules | Class Hierarchy | Alphabetical List | Data Structures | File List | Data Fields | Globals | Related Pages

otFabrik2D Class Reference
[Iterative Inverse Kinematics SolverIterative Inverse Kinematics Solver]

Library for fast forward and inverse kinematics solver based on the FABRIK algorithm.

#include <otFabrik2D.h>


Public Member Functions

 otFabrik2D ()
void begin (S16 numJoints, S16 lengths[], F32 tolerance=10)
void close ()
U8 solve (F32 x, F32 y, S16 lengths[])
U8 solve (F32 x, F32 y, F32 toolAngle, S16 lengths[])
U8 solve (F32 x, F32 y, F32 toolAngle, F32 grippingOffset, S16 lengths[])
U8 solve2 (F32 x, F32 y, F32 z, S16 lengths[])
U8 solve2 (F32 x, F32 y, F32 z, F32 toolAngle, S16 lengths[])
U8 solve2 (F32 x, F32 y, F32 z, F32 toolAngle, F32 grippingOffset, S16 lengths[])
F32 getX (S16 joint)
F32 getY (S16 joint)
F32 getZ (S16 joint=0)
F32 getAngle (S16 joint)
F32 getBaseAngle ()
void setBaseAngle (F32 baseAngle)
F32 getTolerance ()
void setTolerance (F32 tolerance)
void setJoints (F32 angles[], S16 lengths[])
S16 numJoints ()
ChaingetChain ()


Constructor & Destructor Documentation

otFabrik2D.otFabrik2D  ) 
 

Default constructor.


Member Function Documentation

void otFabrik2D.begin S16  numJoints,
S16  lengths[],
F32  tolerance = 10
 

Initializes the library.
Creates the chain to be used for the inverse kinematics solver

Parameters:
numJoints Number of Joint
lengths Lengths of chain
tolerance Is optional, will be set to 10 by default

void otFabrik2D.close  ) 
 

Release all allocated memory

F32 otFabrik2D.getAngle S16  joint  ) 
 

Read angle of a joint

Parameters:
joint Joint number
Returns:
Angle (radians) of joint

F32 otFabrik2D.getBaseAngle  ) 
 

Read base angle

Returns:
Base angle (radians) of a chain

Chain* otFabrik2D.getChain  ) 
 

Gets the IK chain object

Returns:
IK chain object

F32 otFabrik2D.getTolerance  ) 
 

Read end effector tolerance of chain.

Returns:
End effector tolerance of chain

F32 otFabrik2D.getX S16  joint  ) 
 

Read x position of a joint

Parameters:
joint Joint number
Returns:
x position of joint

F32 otFabrik2D.getY S16  joint  ) 
 

Read y position of a joint

Parameters:
joint Joint number
Returns:
y position of joint

F32 otFabrik2D.getZ S16  joint = 0  ) 
 

Read z position of a joint Passing the joint argument will not do anything. It is just there for consistency with getX and getY.

Parameters:
joint Joint number (optional)
Returns:
z offset of the chain from the plane

S16 otFabrik2D.numJoints  ) 
 

Gets the number of joints of the chain

Returns:
Number of joints of the chain

void otFabrik2D.setBaseAngle F32  baseAngle  ) 
 

Set the base angle

Parameters:
baseAngle Base angle (radians) of chain to set

void otFabrik2D.setJoints F32  angles[],
S16  lengths[]
 

Manually sets the joint angles and updates their position using forward kinematics

Parameters:
angles New joint angles (in radians). Angles must be equal to the number of joints - 1
lengths List of lengths between each joint

void otFabrik2D.setTolerance F32  tolerance  ) 
 

Sets the tolerance of the distance between the end effector and the target

Parameters:
tolerance Tolerance value

U8 otFabrik2D.solve F32  x,
F32  y,
F32  toolAngle,
F32  grippingOffset,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target with tool angle and gripping offset.

Parameters:
x Positions of target
y Positions of target
toolAngle Desired tool angle in radians
grippingOffset Offset
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value

U8 otFabrik2D.solve F32  x,
F32  y,
F32  toolAngle,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target with tool angle. Will only work for 3DOF.

Parameters:
x Positions of target
y Positions of target
toolAngle Desired tool angle
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value

U8 otFabrik2D.solve F32  x,
F32  y,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target. Will only work for 3DOF.

Parameters:
x Positions of target
y Positions of target
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value

U8 otFabrik2D.solve2 F32  x,
F32  y,
F32  z,
F32  toolAngle,
F32  grippingOffset,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target. With tool angle and gripping offset introducing the z-axis, which allows a rotational base of the manipulator. Angle of the chain defines the base rotation. Will only work for 4DOF, i.e. 4 joints or more and a rotational base.

Parameters:
x Positions of target
y Positions of target
z Positions of target, defines the offset from the plane
toolAngle Desired tool angle in radians
grippingOffset Offset
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value

U8 otFabrik2D.solve2 F32  x,
F32  y,
F32  z,
F32  toolAngle,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target. With tool angle introducing the z-axis, which allows a rotational base of the manipulator. Angle of the chain defines the base rotation. Will only work for 4DOF, i.e. 4 joints or more and a rotational base.

Parameters:
x Positions of target
y Positions of target
z Positions of target, defines the offset from the plane
toolAngle Desired tool angle in radians
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value

U8 otFabrik2D.solve2 F32  x,
F32  y,
F32  z,
S16  lengths[]
 

Solves the inverse kinematics of the stored chain to reach the target. Introducing the z-axis, which allows a rotational base of the manipulator. Angle of the chain defines the base rotation. Will only work for 4DOF, i.e. 4 joints or more and a rotational base.

Parameters:
x Positions of target
y Positions of target
z Positions of target, defines the offset from the plane
lengths Lengths between each joint
Returns:
0 if FABRIK could not converge, 1 if FABRIK converged to the set threshold, 2 if FABRIK converged with a higher tolerance value


The documentation for this class was generated from the following file: footer
otStudio - Library Reference - (C) 2020-23 Officina Turini, All Rights Reserved
Document built with Doxygen 1.4.0