#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 () |
Chain * | getChain () |
|
Default constructor. |
|
Initializes the library.
|
|
Release all allocated memory |
|
Read angle of a joint
|
|
Read base angle
|
|
Gets the IK chain object
|
|
Read end effector tolerance of chain.
|
|
Read x position of a joint
|
|
Read y position of a joint
|
|
Read z position of a joint Passing the joint argument will not do anything. It is just there for consistency with getX and getY.
|
|
Gets the number of joints of the chain
|
|
Set the base angle
|
|
Manually sets the joint angles and updates their position using forward kinematics
|
|
Sets the tolerance of the distance between the end effector and the target
|
|
Solves the inverse kinematics of the stored chain to reach the target with tool angle and gripping offset.
|
|
Solves the inverse kinematics of the stored chain to reach the target with tool angle. Will only work for 3DOF.
|
|
Solves the inverse kinematics of the stored chain to reach the target. Will only work for 3DOF.
|
|
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.
|
|
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.
|
|
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.
|