This library is an implementation of the FABRIK method(Forward And Backward Reaching Inverse kinematic) for whole human body in the Python programming language. and is released under the MIT software license and is under developement. It can simulate the human behavior in reaching a target with consideration of the human joints constraints. NOTE: This library is under developement so there is some update in future.
You can install the fabrik
library using the following command:
pip3 install git+https://github.com/Atiehmerikh/FABRIK_python.git
To use the code you should specify some values in text files (see test
folder in the root):
First you should consider the numbering in body_number.jpg
file and rest of input files
are based on these numbering
joits_position.txt
: This is the initial position of the jointsjoints_constraint.txt
: This is the constraints for each human body joints. According to the joint reference plane and coordinate, you should enter four number for each joint (Adduction, Abduction, Flexion, Extension).Notice that order of these four number is according to joints orientation in its reference plane(in degree).orientation.txt
: This is the initial orientation of each joint in quaternionbone_twist_constraints.txt
: The twist limitations for each bone. The limitation for each bone should be based on the outer bone number. For anyone that you don't have data let it be on its default.constraint_type.txt
: File for getting the joints constraint ("BALL": for ball and socket) and ("hinge" : for hinge type)target.txt
: First line of this file specifies the target position and the second line represents the orientation of the target
After creating these files inside the input
folder (see test
folder) and creating output
folder (it should be empty first), you can test the FABRIK method like the following:
from fabrik_full_body import fabrik, input_reader
reader = input_reader.InputReader()
manipulator = fabrik.FABRIK(reader.joints(),
reader.initial_joints_position(),
reader.orientation(),
reader.target_position(),
reader.target_orientation(),
reader.joints_constraints(),
reader.constraint_type(),
reader.bone_orientation_limit())
manipulator.solve()
Output is a text file (output/angles.txt
) which computed joint angles and also the final position in stick diagram.
The FABRIK algorithm is explained in the following research paper:
Aristidou, A., & Lasenby, J. (2011). FABRIK: a fast, iterative solver for the inverse kinematics problem. Graphical Models, 73(5), 243-260.
- solve the algorihm for joints constraint which makes parabolic section in joints reference plane
- target locating on the line of kinematic
- Handling If the target is unreachable i.e. if the distance between the root and the target is less than the length of the kinematic chain.
- multiple end effector
- the human feet be able to move