-
Notifications
You must be signed in to change notification settings - Fork 71
Tutorial 1.1
The general idea to using this library can be summarized into three steps:
- Setup: Choose an appropriate algorithm, set the appropriate solver features, and create a tree.
-
Solve: Copy positions and rotations from your tree into the solver's tree and call
solve()
- Retrieve: Copy the new positions and rotations from the solver's tree back into your own.
Steps 2. and 3. can be repeated over and over for every frame. If the tree changes (e.g. nodes are added or removed) you will have to revisit parts of step 1.
The library was designed such that the only visible symbol exported at all is a symbol called ik
(or whatever you set IK_API_NAME to). This is a hierarchical structure that exposes all of the library's functionality through function pointers. Every function you can call will be of the form ik.interface_name.function_name
.
Before you can use any part of the library you must initialize it:
if (ik.init() != IK_OK)
error("Failed to initialize IK");
You can call init()
multiple times. The library keeps track of how many times it was initialized. Notice however that if init()
fails, you should skip the corresponding call to deinit()
.
int memory_leaks = ik.deinit();
If you called init()
more than once, then the "last" call to deinit()
is the one that will de-initialize the library. It returns the number of memory leaks if IK_MEMORY_DEBUGGING is enabled. This may or may not be interesting to you and it is safe to ignore the return value. Under normal conditions, "0" should always be returned.
The library will generate various log messages (warnings and statistics), which are silenced by default. If you are interested in listening to what the library has to say, you can initialize the log with:
if (ik.log.init() != IK_OK)
error("Failed to initialize IK logging");
The library will make an effort to inform you if something is configured wrong, or if you use something in the wrong way, so it is recommended to enable logging at least in debug mode. The messages are written to stdout by default. See the section on callback interfaces to register your own message handler if you want to route the messages elsewhere.
The log supports 5 different levels of severity: DEBUG
, INFO
, WARNING
, ERROR
and FATAL
. For debug builds, the severity is set to DEBUG
by default. For release build, it is set to INFO
. Messages logged below the severity level are discarded.
ik.log.set_severity(IK_WARNING); /* Only interested in warnings, errors and fatals */
If you want to log your own messages into this message stream, you can do so with the message
function:
ik.log.message("iHello IK log!");
Notice the "i" prefixing the "Hello IK log!" message. The first character in the string specifies severity level. Here, "i" means "info". Valid characters are d
, i
, w
, e
, or f
. Specifying no character causes the message to not be filtered.
You need to call the log's deinit()
function in your cleanup code:
ik.log.deinit();
As with ik.init()
, ik.log.init()
also keeps track of how many times you called it and every successful call must be matched with a corresponding ik.log.deinit()
.
You can access information on how the library was built through the ik.info
interface.
const char* v = ik.info.version(); /* Returns the version string of the library */
int bn = ik.info.build_number(); /* Returns how many times the library was compiled */
const char* h = ik.info.host(); /* Returns the name of the host computer that built the library */
const char* d = ik.info.date(); /* Returns the time the library was built */
const char* ch = ik.info.commit(); /* Returns the commit hash */
const char* cp = ik.info.compiler(); /* Returns the compiler used to build the library */
const char* cm = ik.info.cmake(); /* Returns the exact cmake options used */
const char* a = ik.info.all(); /* Returns everything above as a single string */
You can run unit tests through the ik.tests
interface.
if (ik.tests.run() != IK_OK)
error("Oh oh, unit tests failed!");
ik.tests.run()
will return the error codes IK_UNIT_TESTS_FAILED
if any tests fail, or IK_BUILD_WITHOUT_TESTS
if IK_TESTS=OFF
was specified during CMake configuration. If all tests pass, IK_OK
is returned.
A quick note on "static" and "dynamic" interfaces: Library-level functions such as
ik.init()
or ik.log.message()
are globally accessible and/or store
their state globally. We refer to the interface that exposes these functions as
a "static interface". A lot of the API however requires context before it can
call the correct functions. This is the case with solver, node, effector and
constraint objects, because the functions that act on these objects entirely depend
on which type of solver you end up creating. The node, effector and constraint
interfaces are embedded into the solver object for this reason and these are referred
to as a "dynamic interface".
Confused? Don't worry. You will see what I mean momentarily.
First, let's talk about solvers. As of this writing, there are four algorithms available, one of which is not feature complete (MSS). Each has a specific use case with pros and cons:
- IK_ONE_BONE: As the name implies, this solver rotates bones so they point towards a target position. This is useful for things like eyeballs, rotating heads, pointing guns in a direction, etc.
- IK_TWO_BONE: This solver most likely covers the majority of use cases. It solves the two bone IK problem analytically (no iterations) and is very fast. This is useful for legs, arms, robotic limbs, anything that has a single joint and two bones.
- IK_FABRIK: An extremely fast general purpose IK solver. Converges very quickly (5-20 iterations), works with constraints, supports target rotations, supports multiple end effectors. FABRIK is a heuristic algorithm meaning it isn't based on any physical model and produces results that can "look wrong" on organic creatures. FABRIK is good at making small adjustments, such as foot placement to match inclination. It is not a suitable algorithm for driving animations on organic creatures.
- IK_MSS: A mass-spring based solver. Produces excellent looking results for organic creatures and is reasonably fast. Supports constraints, target rotations, and multiple end effectors. MSS is a physically based model that is aware of the model's distribution of mass. Each joint specifies how "heavy" it is, making heavier nodes react slower than lighter nodes to approximate how a real organic joint might behave. The IK library provides a method for automatically calculating joint masses, however, it is recommended to tweak and set these values manually for optimal results.
(MSS is under heavy development and is not exposed through the API yet).
Once you have chosen which algorithm you want to use, you can create the solver object:
ik_solver_t* solver = ik.solver.create(IK_FABRIK);
The solver has a few properties and features which can be enabled and disabled according to your requirements.
First and foremost, you will want to set the maximum number of iterations and tolerance:
solver->max_iterations = 20;
solver->tolerance = 1e-3;
FABRIK converges extremely quickly, you can sometimes get away with just 3-5 iterations. MSS takes longer to converge, approximately 100-1000 iterations. ONE_BONE and TWO_BONE solvers ignore both of these values since they calculate the result directly.
Depending on your world scale, the tolerance should be set to something that is approximately a 10th to a 100th the size of the chain being solved. It is a trade-off between accuracy and solver speed, since the less accurate the result has to be, the earlier the solver can bail.
The solver also has a set of flags you can enable or disable. These flags are:
- IK_ENABLE_CONSTRAINTS: Due to performance reasons, constraint support is disabled by default. If you plan on using constraints you will want to enable this.
-
IK_ENABLE_TARGET_ROTATIONS: When enabled, the effectors will try to match the target rotation (specified by
effector->target_rotation
) as well as the target position. When disabled, the solver will only try to reach the target's position. -
IK_ENABLE_JOINT_ROTATIONS: (Enabled by default) Required for skinned models. When enabled, solvers that work entirely with positions (FABRIK, MSS) will calculate the correct joint rotations as a post processing step. When disabled, these solvers will only calculate positions and
node->rotation
will be left untouched. Solvers that require joint rotations will calculate them anyway (ONE_BONE, TWO_BONE, CCD).
You can enable or disable features at any point by setting or clearing one of the appropriate flags listed above. Here is an example:
solver->flags |= IK_ENABLE_CONSTRAINTS; /* We want constraint support */
solver->flags &= ~IK_ENABLE_TARGET_ROTATIONS; /* We don't want to match the effector's target rotation */
With the solver created, you now have access to the solver->node
,
solver->effector
and solver->constraint
interfaces, which are all
structures containing function pointers to the appropriate object types.
The library provides a leightweight interface for building and maintaining a tree structure. Each node in the tree stores various information, such as the current transform or effector target information and chain length. The result data is also written to this tree and can be retrieved.
(see node.h for more info)
Creating a tree is quite straight forward. Every node requires a unique identifier within the tree structure. This is passed as an argument during creation and should not be changed thereafter.
struct ik_node_t* tree = solver->node->create(0);
struct ik_node_t* node = solver->node->create(1);
solver->node->add_child(tree, node);
Or shorter:
struct ik_node_t* tree = solver->node->create(0);
struct ik_node_t* node = solver->node->create_child(1, tree);
You can remove nodes with the function solver->node->destroy()
. You can
retrieve node objects by uid with solver->node->find_child()
Node positions are specified in local space and can be changed at any point:
node->position = ik.vec3.vec3(0, 1, 0);
node->rotation = ik.quat.quat(1, 0, 0, 0);
Note however that if you change the position and the distance to the previous
node changes, you will have to call ik.solver.calculate_segment_lengths()
once to update the internal distances.
You may have a requirement to store user specific data per node. For this you can write to the node->user_data
field
node->user_data = some_user_specific_structure;
so you can retrieve it later on when applying the solved results back to your scene (see the section on solvers below on how that works).
You will need to mirror the same structure present in your project (assuming your project is using a scene graph or something similar). Whether you do this continuously or whether you rebuild the whole tree from scratch before solving when relevant parts of your scene graph become "dirty" is up to you. The former approach is recommended if your scene graph is expected to change a lot. The latter is of course easier to implement.
Important: Whenever you change the tree in any way you need to call
ik.solver.rebuild()
to update internal structures. Failing to do so will
result in segfaults.
Effectors are used to set the target position and rotation of a node.
In order to mark a node as an effector, you must create and attach an effector
object using solver->effector->create()
and solver->effector->attach()
.
struct ik_effector_t* effector = solver->effector->create();
solver->effector->attach(effector, node);
The most important fields that can be to set on the effector are:
effector->chain_length = 3; /* how many parent segments should be affected */
effector->target_position = getMyTargetPosition();
effector->target_rotation = getMyTargetRotation();
A chain length of 1 means a single segment or "bone" is affected. Arms and
legs typically use a value of 2. The default value is 0, which means
all nodes right down to the root node are affected. Note that you must call
ik.solver.rebuild()
after chainging the chain length (more info
later).
The target position and rotation is set in global space, where the target position is a 3-dimensional vector type and the rotation is a quaternion.
Effectors have a weight
parameter (ranges from 0-1) indicating how much
influence it has on the tree to be solved. You can make use of this to
smoothly transition in and out of IK solutions.
effector->weight = splineFunction();
You may have noticed that the weight causes a linear interpolation of the target position. This can look bad on organic creatures, especially when the solved tree is far apart from the initial tree. You might consider enabling nlerping, which causes the weight to rotate around the next subbase joint (using nlerping). This feature can be enabled by setting the flag:
effector->flags |= IK_WEIGHT_NLERP;
Here you can see two transition results, with and without nlerping enabled.
TODO: IK_IGNORE_PARENT_ROTATION
A typical solver invokation might look like this:
static void apply_nodes_to_scene(struct ik_node_t* ikNode)
{
MyGameNode* node = (MyGameNode*)ikNode->user_data;
node->SetLocalPosition(ikNode->position);
node->SetLocalRotation(ikNode->rotation);
}
void MyGame::Solve()
{
if (tree_was_modified_in_some_way())
ik.solver.rebuild(solver);
if (distances_between_nodes_changed())
ik.solver.update_distances(solver);
my_effector->target_position = Get3DMousePosition();
ik.solver.solve(solver);
ik.solver.iterate_affected_nodes(solver, apply_nodes_to_scene);
}
Where tree_was_modified_in_some_way()
returns true whenever any of the following actions occur:
- Setting the solver's tree (ik.solver.set_tree())
- Adding or removing nodes from the tree
- Adding or removing effectors from the tree
- Adding or removing constraints from the tree
- Changing effector->chain_length
- Changing the constraint type
If you have translational movements in your animation, that is, if the
distances between nodes change from frame to frame, you need to call
ik.solver.update_distances()
every time that happens. Note however that ik.solver.rebuild()
already calls this function.
The function apply_nodes_to_scene()
is passed to
ik.solver.iterate_affected_nodes()
as a callback function, which will be
called for every node in the tree breadth first. The example code above assumes that
node->user_data
was previously initialized with a pointer to a
MyGameNode
object. This is the mechanism with which to copy data from the
ik library's tree to your game's tree.
If you were to execute the code above, you would obtain a more "continuous" solution of
the IK problem. We're never actually copying any new positions into the solver's tree; the positions and rotations from the last solve()
are still there and are being used as a basis for the next solution. Here is an example of what it might look like:
A lot of the time you may want to reset the tree to its "initial pose" (the
positions and rotations that existed before the last solve). In order to do this, the library provides two functions: duplicate()
and copy_tree_from()
.
static void apply_nodes_to_scene(struct ik_node_t* ikNode)
{
MyGameNode* node = (MyGameNode*)ikNode->user_data;
node->SetLocalPosition(ikNode->position);
node->SetLocalRotation(ikNode->rotation);
}
void MyGame::Solve()
{
if (tree_was_modified_in_some_way())
{
solver->node->destroy(originalTree_);
originalTree_ = solver->node->duplicate(solver->tree);
ik.solver.rebuild(solver);
}
my_effector->target_position = Get3DMousePosition();
solver->node->copy_data(solver->tree, originalTree_);
ik.solver.solve(solver);
ik.solver.iterate_affected_nodes(solver, apply_nodes_to_scene);
}
Here we are initializing all positions and rotations in the solver's tree with the positions and rotations stored in our "backup" tree, which was created earlier.
The result now looks much different. Rather than a continuous solution, the calculation is performed on the initial pose every time, causing the chain to have a tendency to snap back into its original pose if possible:
This is typically the desired mode of operation for animated characters: Apply the current pose to your skeleton, copy those positions and rotations into the solver's tree, solve, and copy them back again into the skeleton. Here's what that might look like in code:
static void apply_nodes_to_scene(struct ik_node_t* ikNode)
{
MyGameNode* node = (MyGameNode*)ikNode->user_data;
node->SetLocalPosition(ikNode->position);
node->SetLocalRotation(ikNode->rotation);
}
static void apply_scene_to_nodes(struct ik_node_t* ikNode)
{
MyGameNode* node = (MyGameNode*)ikNode->user_data;
ikNode->position = node->GetLocalPosition();
ikNode->rotation = node->GetLocalRotation();
}
void MyGame::Solve()
{
if (tree_was_modified_in_some_way())
ik.solver.rebuild(solver);
ik.solver.iterate_affected_nodes(solver, apply_scene_to_nodes);
ik.solver.solve(solver);
ik.solver.iterate_affected_nodes(solver, apply_nodes_to_scene);
}
There are some flags that should be set depending on your needs. By default, the solver will calculate final rotations. This is desired if you are solving IK for a skinned character for example, but has a considerable performance impact if you are using FABRIK or MSS. If you don't care about the orientation of joints, consider clearing this flag:
solver->flags |= IK_ENABLE_JOINT_ROTATIONS;
The result with and without final rotations, respectively:
By default the solver will disregard target rotations (the solver will try to match the last bone to the rotation set
via effector->target_rotation
). This can be enabled by setting the
following flag:
solver->flags |= IK_ENABLE_TARGET_ROTATIONS;
The result: Notice how towards the end we are able to rotate the target and the chain of bones tries to match that rotation:
(Not implemented as of this writing)
If you require the current transforms to be in global space instead of local space, you can use the ik.transform
interface to transform the solver's tree between these two spaces:
ik.solver.solve(solver);
/* want to apply results in global space instead of in local space */
ik.transform.local_to_global(solver->tree);
ik.solver.iterate_affected_nodes(solver);
ik.transform.global_to_local(solver->tree); /* if you won't be writing new positions and rotations to the solver's tree for the next solve(), you need to transform back */