Authors: Daniel Ostermeier,
Jonathan Külz and Matthias Althoff
This toolbox is based on the following scientific publication:
D. Ostermeier, J. Külz and M. Althoff, "Automatic Geometric Decomposition for Analytical Inverse Kinematics," in IEEE Robotics and Automation Letters, vol. 10, no. 10, pp. 9964-9971, Oct. 2025
@ARTICLE{EAIK,
author={Ostermeier, Daniel and K{\"u}lz, Jonathan and Althoff, Matthias},
journal={IEEE Robotics and Automation Letters},
title={Automatic Geometric Decomposition for Analytical Inverse Kinematics},
year={2025},
volume={10},
number={10},
pages={9964-9971},
doi={10.1109/LRA.2025.3597897}
}
You may find our open-access publication here:
Please cite the above work when using this code within your own projects.
Also, please visit our website for additional informations.
Additional derivations that were used within this toolbox are contained in this PDF. Feel free to contact us if you have any questions or suggestions: Open up a GitHub issue.
With this toolbox, we propose a method for automatic inverse kinematic derivation. We exploit intersecting and parallel axes to remodel a manipulator's kinematic chain.
This allows for a hard-coded decomposition algorithm to solve its inverse kinematics by employing pre-solved subproblems. Our approach surpasses current analytical methods in terms of usability and derivation speed without compromising computation time or the completeness of the overall solution set.
The following figure illustrates a robot with a spherical wrist and the geometric representation of a subproblem we use to solve parts of its IK:
We adopt the solutions and overall canonical subproblem set from Elias et al.:
A. J. Elias and J. T. Wen, “IK-Geo: Unified robot inverse kinematics
using subproblem decomposition,” Mechanism and Machine Theory,
vol. 209, no. 105971, 2025.
Check out their publication and implementation.
The current implementation supports automatic derivation of solutions for the following 6R and 5R manipulators, as well as their mirrored version (switched base and endeffector), and all non-redundant 1-4R manipulators. In addition, we allow the user to solve arbitrary nR manipulators that, by locking individual joints, corrspond to one of the below kinematic families.
Robot configurations (without their mirrored version) that can be solved by the current EAIK implementation. NR-Robots that contain these structures as kinematic subchains are solvable if the leftover redundant joints are locked in place. For the 5R manipulators, all (non-redundant) specializations of the shown classes (i.e., with additional intersecting/parallel axes) are solvable as well.
We implement an user friendly interface for parametrizing a robot by a URDF file, DH parameters, or simply the homogeneous transformations that correspond to the joint axes placements.
The following figure shows an overview of our interface and a superficial showcase of our method:
If you require a vast amount of IK problems to be computed at once, we also implement a multithreaded batched version that allows you to make full use of your processor.
We use Eigen 3.4 for a fast implementation of the linear algebra operations within this toolbox. Make sure you have your Eigen headers placed in their standard directory ('/usr/include/eigen3', '/usr/local/include/eigen3') - otherwise the following step will not work for you.
We suggest using our pip-installable PyPI package. Simply use the following command on your Linux machine:
pip install EAIK
If you want to directly use the C++ functionality as a library and skip the Python wrapper, simply clone our GitHub Repository and follow the following steps.
Make sure to clone the external dependencies of this library using:
$ git clone --recurse-submodules [email protected]:OstermD/EAIK.git
Then build the EAIK C++ library by using:
$ mkdir EAIK/CPP/src/build && cd EAIK/CPP/src/build
$ cmake ..
$ make
We currently provide support parametrizing a robot via DH parameters, homogeneous transformations of each joint in zero-pose with respect to the basis, as well as ROS URDF files. Some quick examples that demonstrate the usability of our implementation are shown in the following code-snippets:
import numpy as np
from eaik.IK_DH import DhRobot
"""
Example DH parametrization + forward kinematics for a random robot kinematic
"""
d = np.array([0.67183, 0.13970, 0, 0.43180, 0, 0.0565])
alpha = np.array([-np.pi/2, 0, np.pi/2, -np.pi/2, np.pi/2, 0])
a = np.array([0,0.43180, -0.02032, 0,0,0])
bot = Robot(alpha, a, d)
print(bot.hasKnownDecomposition())
print(bot.fwdKin(np.array([1,1,1,1,1,1])))import numpy as np
import random
from eaik.IK_URDF import UrdfRobot
import evaluate_ik as eval
def urdf_example(path, batch_size):
"""
Loads spherical-wrist robot from urdf, calculates IK using subproblems and checks the solution for a certian batch size
"""
bot = UrdfRobot(path)
# Example desired pose
test_angles = []
for i in range(batch_size):
rand_angles = np.array([random.random(), random.random(), random.random(), random.random(), random.random(),random.random()])
rand_angles *= 2*np.pi
test_angles.append(rand_angles)
poses = []
for angles in test_angles:
poses.append(bot.fwdKin(angles))
for pose in poses:
ik_solutions = bot.IK(pose)
# Print forward kinematics for all solutions
for Q in ik_solutions.Q:
pose_fwd = bot.fwdKin(Q)
print(pose_fwd)Even more examples for the python interface are available here.
The example below is just a small code snipped. As the C++ code quickly becomes more evolved, we recommend to look into the Software Tests we wrote for the C++ side. The code there can also be used as an example on how you can use our library in a bigger project that, e.g., requires checks for least-square solutions etc.
#include <eigen3/Eigen/Dense>
#include <vector>
#include "EAIK.h"
const Eigen::Vector3d zv(0, 0, 0);
const Eigen::Vector3d ex(1, 0, 0);
const Eigen::Vector3d ey(0, 1, 0);
const Eigen::Vector3d ez(0, 0, 1);
double rand_angle(); // Just some random angle in [0; 2pi)
void ik_7R_KUKA_R800()
{
// Robot configuration for KUKA LBR iiwa 7 R800
// Define axes unit vectors
Eigen::Matrix<double, 3, 7> H;
H << ez, ey, ez, -ey, ez, ey, ez;
// Define offsets between reference points on joint axes
Eigen::Matrix<double, 3, 8> P;
P << (0.15 + 0.19) * ez,
zv, 0.21 * ez,
0.19 * ez,
(0.21 + 0.19) * ez,
zv,
zv,
(0.081 + 0.045) * ez;
// Kuka R800 with q3 locked in random configuration
double q3_angle = rand_angle();
// Create Robot
EAIK::Robot kukaR800(H, P,
Eigen::Matrix<double, 3, 3>::Identity(),
{std::pair<int, double>(2, q3_angle)});
// Forward Kinematics
IKS::Homogeneous_T ee_pose = kukaR800.fwdkin(std::vector{
rand_angle(),
rand_angle(),
q3_angle,
rand_angle(),
rand_angle(),
rand_angle(),
rand_angle()
});
// Inverse Kinematics
IKS::IK_Solution solution = robot.calculate_IK(ee_pose);
}
void main()
{
ik_7R_KUKA_R800();
}Again, if you are stuck somewhere or have open questions feel free to reach out to us.
For the following experiments we use the Schunk Powerball LWA-4P manipulator—a modularizable 6R manipulator with a spherical wrist and two consecutive intersecting axes in its base.
For the first experiment, we consider a linear end-effector trajectory reaching from a start position of (x, y, z) = (0m, 0m, 0.5m) to an end position (x, y, z) = (0m, 0m, 1.0m) and back.
We align the orientation of the end effector with that of the base of the robot and keep it constant throughout the whole trajectory.
In this example, all points along the trajectory with a z-coordinate smaller than or equal to 0.8m are reachable by the manipulator (neglecting joint limits and self-collisions). However, the first and last axis of the LWA-4P are collinear at every point along this trajectory—the manipulator is always in a singular configuration. Hence, infinitely many IK solutions exist for each point along this trajectory with z ≤ 0.8m. On the other hand, all points with a z-coordinate larger than 0.8m are placed outside the workspace of the manipulator—no IK solution exists for any of these points. We sample 100 discrete points along this trajectory and try to compute the IK solution for each point. We obtain the following results:
We obtain at least one IK solution for any point along the trajectory.
For points where z ≤ 0.8m, this solution is analytically correct with an error in the magnitude of double-precision accuracy. For points where z > 0.8m, this solution is a least-squares solution to the underlying
subproblems as discussed in our manuscript under Section IV-B. We linearly interpolate between the
discrete samples in joint space to obtain the joint trajectories in the following figure. While the solutions
to the subproblems in Elias et al. are unable to represent the full infinite solution space that arises from singular
configurations, they still yield at least one consistent and analytically accurate solution.
The following animation shows a simplified LWA-4P model that executes the IK solutions obtained via our method (EAIK). Blue arrows resemble the joint axes of the manipulator, while the pink bars resemble its links.
Green points represent the commanded positions while exiting the workspace, while red points represent the commanded positions when re-entering the manipulator's workspace (100 points in total).
When using our method (EAIK), we obtain sensible joint angles even when commanding poses outside of the workspace of the manipulator or during singular configurations. When the manipulator reaches its workspace boundary, our method returns feasible least-squares solutions:
For the second experiment, we induce a slight offset to the trajectory from Experiment 1 along the y-axis.
The new trajectory starts with the end-effector position (x, y, z) = (0m, −0.001m, 0.5m), reaches to the
position (x, y, z) = (0m, −0.001m, 1.0m) and goes back to (x, y, z) = (0m, −0.001m, 0.5m). Again, we sample
100 equidistant points from this trajectory and try to compute IK solutions.
Just like in the first experiment, every point on the trajectory with z ≤ 0.8m can be reached by the manipulator. This time, however, all these points are reachable in non-singular configurations. Therefore, there exists only a finite set of IK solutions to each such point. Our method yields solutions accurate up to the expected floating-point precision.
For all points where z > 0.8m, no IK solution exists. However, in real-world situations, values that lie exactly on the workspace boundary can not be perfectly separated from those that lie beyond it. E.g., due to floating-point inaccuracies, a desired set-point of 0.8m may be represented as 0.8m + ϵ where 1 >> ϵ > 0. Our method returns an IK solution that resembles the least-squares solution to the underlying subproblems. The error between the desired and actual error in the end-effector position is often negligible in such cases. These properties make the solutions returned by the subproblems in Elias et al., and thus the solutions provided by our method, consistent and stable even across workspace boundaries.
As the offset induced in the y-direction is quite small (1mm), the trajectory plot (and also the animation) of our method's performance in this experiment is indistinguishable by the human eye from the plot in the first experiment. We therefore refrain from plotting the same figures again and refer the reader to the visualizations in the prior experiment.
NOTE: All of the following experiments were conducted on a computer with an AMD Ryzen 7 8-core processor and 64GB of DDR4 memory within Ubuntu 22.04.
We compare our method, i.e., the EAIK toolbox, to different frameworks on common 6R manipulators: The UR5 robot (three parallel and two intersecting axes), the Puma (spherical wrist and two intersecting axes), and the ABB IRB 6640 (spherical wrist and two parallel axes). A Franka Emika Panda (spherical wrist) represents the category of redundant 7R robots, which we solve by joint-locking. We further use two conceptual manipulators from Elias et al.: The “Spherical” (spherical wrist) and “3-Parallel” (three parallel axes) robot. Besides IKFast, we also list the computation times on the numerical Gauss-Newton (GN) and Levenberg-Marquard (LM) solvers implemented in the Python Robotics Toolbox.
The following figure shows a comparison of the IK computation times of six representative manipulators on 5,000 randomly assigned end-effector poses (left) and the batch-times on 10,000 random (analytically solvable) 6R manipulators (right). The measured times in (left) correspond to a single solution for the numerical approaches—which we marked with an asterisk—and the set of all possible solutions for EAIK, IKFast, and the method by He et al. respectively. In (left), we additionally include derivation times and only show our method along the numerical ones, as the derivation times of IKFast are too long for this task to finish within a reasonable time. Our method shows the smallest overall variance and, except for the Puma and Panda robot, consistently surpasses all other methods.
Further, we randomly generate 20 different 6R manipulators with their last three joints resembling a spherical wrist. The chosen manipulators cover all decisive combinations of intersecting or parallel axes relevant to our current decomposition. For these manipulators, the input to our method is a series of six homogeneous transformations that describe the position and orientation of the respective joints. The time measurements were obtained by running a batch size of 100'000 derivations.
IK derivation (left) and computation times (right)We further compare our method to one of the current state-of-the-art methods for general analytical IK computation: IKFAST. We use five typical industrial 6R manipulators that comply with the Pieper criteria. The UR5 robot (three parallel and two intersecting axes), the Puma (spherical wrist and two intersecting axes), and the IRB 6640 (spherical wrist and two parallel axes) resemble real-world manipulators. The Spherical (spherical wrist) and 3-Parallel (three parallel axes) robots, on the other hand, are made up by Elias et al. The input to our implementation is an URDF file that contains the manipulator's structure. The input to IKFast is an equivalent COLLADA XML file.
Table: IK-derivation times of IKFast and our methodWe compare our approach to the learning-based approach IKFlow by the 7R Franka Panda robot. As this robot is inherently redundant, we need to set one joint angle in advance (i.e., use joint locking) to solve the Panda robot analytically, while IKFlow is able to make use of all seven joints. Our experiments show a mean computation time of 75.07 μs for IKFlow (7507 μs per batch - IKFlow performs batched computation for 100 poses simultaneously) and 3.67 μs for our method. However, by employing joint locking, we can not sample from the same infinite solution space that IKFlow makes use of, which leads to less diverse solutions.
The following figure shows the just mentioned values for the Panda robot, as well as the position and orientation errors that different methods resulted for non-redundant UR5 robot.
Computation times and position error for the Panda robot, as well as the UR5. The dashed red lines indicates the repeatability precision of the robot according to its datasheet.To further evaluate our implementation's accuracy, we sample 100 random poses throughout the workspace of a representative subset of the above mentioned manipulators. We calculate the error metric of each solution by the Frobenius norm of the difference between the homogeneous transformation of our IK's result and the ground truth, i.e., the sum of the squared differences between the entries in the matrices.
Panda computation times and Error metric across 100 poses for three representative manipulatorsWe further create 10'000 resampled bootstrap distributions (each 100 samples) and calculate their respective means. The means of these resamplings, together with a bias corrected and accelerated (B. Efron) 95% confidence interval, are visualized in the following figures:
IKFAST - the analytical solver that we compare our implementation to - is part of the work of:
R. Diankov. “Kinematics and Control of Robot Manipulators”. PhD thesis. Carnegie Mellon University Pittsburgh, Pennsylvania, 2010
IKFlow - the learning-based solver that we compare our implementation to - is part of the work of: B. Ames, J. Morgan, and G. Konidaris, “IKFlow: Generating diverse inverse kinematics solutions,” IEEE Robotics and Automation Letters, vol. 7, no. 3, 2022.
Python Robotics Toolbox - the toolbox we use to compare our implementation to numerical solvers - is part of the work of: P. Corke and J. Haviland, “Not your grandmother’s toolbox–the robotics toolbox reinvented for Python,” in Proc. of the IEEE Int. Conf. on Robotics and Automation (ICRA), 2021, pp. 11 357–11 363
Y. He and S. Liu, “Analytical inverse kinematics for Franka Emika Panda – a geometrical solver for 7-DOF manipulators with un- conventional design,” in Proc. of the IEEE Int. Conf. on Control, Mechatronics and Automation (ICCMA), 2021, pp. 194–199
B. Efron. "Better Bootstrap Confidence Intervals". Journal of the American Statistical Association. Vol. 82, No. 397: 171–185, 1987