This content originally appeared on Level Up Coding - Medium and was authored by Luiz doleron | Luiz d'Oleron
Delta Robots are a popular pick-n-paste robotic platform with tricky kinematics. In this story, I show how to find the inverse kinematic equation by using two different approaches: the classic way and my custom way.
As usual, the IK equations are implemented in pure C++.
Robot geometry & frame reference
The delta robot geometry is defined by 4 positive values:
- L: the upper arm length
- l: the lower arm length
- F: the base (top equilateral triangle) side
- E: the end-effector (bottom equilateral triangle) side
These attributes are shown in the image below:

Note that we set the reference frame on top of the robot.
The inverse kinematics problem
Now, we can define the IK problem as:
- Given a robot geometry {L, l, F, e}
- A point (x, y, z) in the space
Find the angles θ1, θ2 and θ3 so that the center of the end-effector is located at (x, y, z):

In resume, we want to find a function IK(x, y, z) such that:
IK(x, y, z) = (θ1, θ2, θ3)
Solving the IK problem: the classic way
The classic strategy to find the delta IK equations is simple:
- Choose an arm
- Find the point P of the upper arm’s end
- Use the triangle to find theta

In this approach, P is found using the intersection of two circles (I will explain it in the next section).
Once we find theta for one arm, we can rotate (x, y, z) by 120º and 240º around the 0z axis to find the other two thetas.
Fiding P
P can be achieved by the intersection of the following two circles:

Note that we are using R’ as the projection of R onto the plane YZ. Thus, the points Q, P, and R’ are given by:
Q = (0, -Fd, 0)
P = (0, Py, Pz)
R'= (0, y - Ed, z)
where Fd and Ed as the joint offsets. These offsets can be easily derived from the base and end-effector equilateral sides, respectively:

Fd = sqrt(3) * F / 6
Ed = sqrt(3) * e / 6
Finally, we end up with the following two circle equations:
(Py + Fd)² + Pz² = L² (equation 1)
(Py - y + Ed)² + (Pz - z)² = l² - x² (equation 2)
The point P = (0, Py, Pz) is the solution of the system.
Solving the system
We can solve this system very straightforwardly:
First, change the yreference:
ÿ = y - Ed
Equations 1 and 2 are now:
Py² + 2PyFd + Fd² + Pz² - L² = 0 (equation 1)
Py² - 2Py*ÿ + ÿ² + Pz² - 2Pz*z + z² - l² + x² = 0 (equation 2)
If we subtract equation 1 from equation 2, we end up with:
- 2Py*ÿ - 2PyFd - 2Pz*z + ÿ² + z² - l² + x² - Fd² + L² = 0
Note that this subtraction cancels the terms Py² and Pz².
What to do with this new equation? The trick is to rearrange the equation to get a linear formula, as shown below:
a = (x²+ ÿ² + z² + L² - l² - Fd²) / (2z)
b = -(Fd + ÿ)/ z
Now, we have a linear relationship between Py and Pz :
Pz = a + bPy (equation 3)
Replacing equation 3 in equation 2 results in a second-degree polynomial:
A*Py² + B*Py + C = 0
Where
A = b² + 1
B = 2*(b * [a - z] - ÿ)
C = ÿ² + (a - z)² - (l² - x²)
We can solve this quadratic equation using the Bhaskara formula:
Py = [-B ± sqrt(B² - 4*A*C)] / (2*A)
This can result in zero, one, or two real solutions. In fact, there exist two solutions, one valid and the other invalid:

We must pick the valid (outer) solution, which means that we end up using:
Py = [-B - sqrt(B² - 4*A*C)] / (2*A)
Once we find Py, we can plug it into the line equation to find Pz. Finally, we can use atan2()to find theta:
theta = atan2(-Pz, [-Fd - Py])
This is the angle θ for only one arm. Of course, each arm has a different θ. To find the other θ’s is very simple. We only need to rotate (x, y, z) around the axis z:

using ω = 120º and ω = 240º, and repeat the same procedure here to get the other two thetas. This procedure is described in the implementation section later in this story.
Alternative solution
The classic solution, based on intersecting two circles, provides two geometric solutions (one useful and the other invalid), requiring some analytical manipulation to model the equations as linear or quadratic functions, which is tedious, tricky, and error-prone. Thinking about that, I ended up formulating a simpler solution that resides in the idea of solving the following two triangles:

The first triangle allows find α by its arc sine:
d = y - Ed + Fd
W = sqrt(z² + d²)
α = asin(d / W)
The second triangle allows us to find ω using the laws of triangles:
A² = l² - x²
ω = acos([W² + L² - A²] / [2 * L * W])
Now, we can find θ by:
θ = π/2 + α - ω
This is theta for one arm. In the same way as in the classic approach, we can rotate (x, y, z) around the z-axis.
Implementing the two approaches
The first approach can be implemented straightforwardly as follows:
double IK_first_appraoch(
double L, double l,
double Fd, double Ed,
double x, double y, double z)
{
double y_hat = y - Ed;
// Z = a + b*Y
double a = (x * x + y_hat * y_hat + z * z + L * L - l * l - Fd * Fd) / (2 * z);
double b = -(Fd + y_hat) / z;
// AY² + BY + C = 0
double A = b * b + 1;
double B = 2.0 * (b * (a - z) - y_hat);
double C = y_hat * y_hat + (a - z) * (a - z) - (l * l - x * x);
double D = B * B - 4 * A * C;
if (D < 0.0)
return 0;
double sqrtD = std::sqrt(D);
double Y = (-B - sqrtD) / (2 * A);
double Z = a + b * Y;
double theta = atan2(-Z, -(Fd + Y)) * 180.0 / M_PI;
return theta;
}
My approach, the second one previously described in this story, can also be implemented as simply as:
double IK_second_appraoch (
double L, double l,
double Fd, double Ed,
double x, double y, double z)
{
// from the left triangle:
double d = y - Ed + Fd;
double W2 = z*z + d*d;
if (W2 <= 1e-6) return NAN;
double W = std::sqrt(W2);
double alpha = std::asin(d / W) * 180.0 / M_PI ;
// applying the law of triangles to the right triangle:
double A2 = l * l - x * x;
double numerator = -A2 + W * W + L * L;
double denominator = 2.0 * L * W;
double cos_omega = numerator / denominator;
double omega = std::acos(cos_omega) * 180.0 / M_PI;
// Finally
double theta = 90 + alpha - omega;
return theta;
}
This simple test measures the Root-mean-square deviation between the two approaches:
#include <iostream>
#include <iomanip>
#include <cmath>
const double end_effector = 1.5;
const double base = 4.5;
const double lower_arm = 6.;
const double upper_arm = 2.5;
const double sqrt3 = sqrt(3);
int main()
{
double Fd = sqrt(3) * base / 6;
double Ed = sqrt(3) * end_effector / 6;
double error_acc = 0.;
int n = 0;
for (double z = -3.5, r = 0.1, angle = 0.; z >= -5.5; z -= 0.1, angle += 0.1, n++)
{
double x = r * cos(angle);
double y = r * sin(angle);
if (z >= -4)
{
r += 0.1;
}
else
{
r -= 0.1;
}
auto theta_1 = IK_first_approach(upper_arm, lower_arm, Fd, Ed, x, y, z);
auto theta_2 = IK_second_approach(upper_arm, lower_arm, Fd, Ed, x, y, z);
auto diff = std::abs(theta_1 - theta_2);
if (diff > 1e-6) {
break;
}
error_acc += diff * diff;
}
double rmsd = std::sqrt(error_acc / n);
std::cout << "RMSD: " << rmsd << std::fixed << std::setprecision(2) << "\n";
return 0;
}

Conclusion
The trajectories performed by delta robots are mesmerizing, combining speed and softness. This elegance comes with a price: computing their kinematics is much harder than computing the kinematics of a Cartesian robot. This story tries to make it easier by explaining how to obtain the inverse kinematics using two approaches.
How to contribute
If you enjoyed this tutorial and want to contribute, check a charity institution near you and provide your assistance with money and/or time. No citation is needed. You needn’t let me know either.
Have a question? Drop a message and I will reply as soon as possible.
Regards,
Luiz
Demystifying the Delta Robot Inverse Kinematics was originally published in Level Up Coding on Medium, where people are continuing the conversation by highlighting and responding to this story.
This content originally appeared on Level Up Coding - Medium and was authored by Luiz doleron | Luiz d'Oleron
Luiz doleron | Luiz d'Oleron | Sciencx (2025-07-16T14:35:17+00:00) Demystifying the Delta Robot Inverse Kinematics. Retrieved from https://www.scien.cx/2025/07/16/demystifying-the-delta-robot-inverse-kinematics/
Please log in to upload a file.
There are no updates yet.
Click the Upload button above to add an update.