This tutorial continues our quest to solve the problem of forward kinematics. After exploring a mathematical solution in The Mathematics of Forward Kinematics, we will see how to translate it into C# for Unity. The next tutorial, An Introduction to Gradient Descent, will finally show the theoretical foundations to solve inverse kinematics.
The other post in this series can be found here:
- Part 1. An Introduction to Procedural Animations
- Part 2. The Mathematics of Forward Kinematics
- Part 3. Implementing Forward Kinematics
- Part 4. An Introduction to Gradient Descent
- Part 5. Inverse Kinematics for Robotic Arms
- Part 6. Inverse Kinematics for Tentacles
- Part 7. Inverse Kinematics for Spider Legs 🚧 (work in progress!)
At the end of this post you can find a link to download all the assets and scenes necessary to replicate this tutorial.
Introduction
In the second part of this tutorial on Inverse Kinematics, The Mathematics of Forward Kinematics, we have formalised how a robotic arm moves. We started with a toy example, made by three joints. When in their resting positions, they assume the configuration seen in the diagram below:
In the diagram, the various represents the Cartesian coordinates or the -th joint. The local angles that indicates how much they rotate from their resting positions are labelled .
When joints rotate, we see the following:
The behaviour of this system has been summarised with the following statements:
- Rotation. The global rotation of a joint is the sum of the rotations of all the previous joints:
- Position. The global position of a joint is given by:
Knowing all of the above, we can start thinking of a possible way to implement these behaviours in Unity.
GameObjects Hierarchy
Unity already comes with a way to implement all the requirements mentioned above: parenting. Setting a game object as a child of another one automatically inherit the position, the rotation and the scale.
If you are familiar with rigging, this should not surprise you. The bones that represent the joints of a humanoid character are parented in such a way that rotations and translations are inherited. The following image, from Unity Animation 3: Character Setup (by Michael Arbuthnot) shows a clear example of this.
While building your hierarchy of joints, you have to make sure that the robotic arm is in resting position when all the local Euler angles are set to zero. In a humanoid character, this usually corresponds to the standard T-stance seen in the picture above.
The Implementation
The parenting option in Unity is, de-facto, solving the problem of forward kinematics for us. Unfortunately this is not enough. We will see in next part of this tutorial, Inverse Kinematics with Gradient Descent, that we actually need a way to test the position of the end effector without actually moving the robotic arm. This forces us to re-implement this basic feature in Unity.
The first step is to store some information on each joint of the robotic arm. This can be done by adding a script, such as RobotJoint
in the example below.
using UnityEngine; public class RobotJoint : MonoBehaviour { public Vector3 Axis; public Vector3 StartOffset; void Awake () { StartOffset = transform.localPosition; } }
You should add RobotJoint
script to each game object that serves as a joint for your robotic arm. Every game object that you want to be rotated by the IK system should have one such script attached to it.
To simplify the calculations, we assume that each joint can only rotate around one its local axes: either X, Y or Z. We indicate that with a variable called Axis
, which has a 1
in the position relative to the rotation axis. If this joint rotates around the Y axis, Axis
would be (0,1,0)
. We will see how this allows us to avoid IF statements.
The actual IK code should be store in a different script, which will serve as an “IK manager”. You can put it inside the root of your robot arm, although it does not really matter where it is. Its purpose will be to perform both the forward and inverse kinematics. To do so, the manager script needs to know where the joints are. This will be possible by storing them inside an array or a list of RobotJoint
s, which will be called Joints
.
The manager script will need a function, called ForwardKinematics
. It takes as input an array of float
s, called angles
. The name is self-explanatory: angles[i]
contains the local rotation for the i-th joint contains in the Joints
list. The function returns the position of the end effector, in global coordinates.
public Vector3 ForwardKinematics (float [] angles) { ... }
The code is a straight forward implementation in C# of the position equation seen before. The rotate
function is implemented with the handy Quaternion.AngleAxis
.
Vector3 prevPoint = Joints[0].transform.position; Quaternion rotation = Quaternion.identity; for (int i = 1; i < Joints.Length; i++) { // Rotates around a new axis rotation *= Quaternion.AngleAxis(angles[i - 1], Joints[i - 1].Axis); Vector3 nextPoint = prevPoint + rotation * Joints[i].StartOffset; prevPoint = nextPoint; } return prevPoint;
❓ Need help with Quaternions?
Rotations in Unity are often described with Euler angles. It’s tree numbers which correspond to the rotations of an object along the X, Y and Z axes. Euler angles represent the roll, pitch e yaw of an object in space. It’s not surprising that they are easy to understand. Mathematically speaking, however, using Euler angles can lead to some nasty problems.
A better way to work with angles is by using quaternions. Quaternions are mathematical objects that can be used to represent rotations. Euler angles, conversely, represent orientations. A quaternion represents a way to go from one orientation to another. Technically speaking, this is a massive oversimplification, but for the purpose of this tutorial is more than enough.
Rotations ⇔ Quaternions
A quaternion can be imagined as a rotation. Rotating an object in space is, mathematically speaking, equivalent to multiply its position by a quaternion. In Unity, you can use the function Quaternion.AngleAxis
to create a rotation around a fixed point. The line Quaternion.AngleAxis(angle, axis);
creates a quaternion that represents a rotation around the axis
axis by angle
degrees. In this context, the value of Axis
can be (1,0,0)
, (0,1,0)
or (0,0,1)
to indicates the X, Y or Z axis respectively. This explains why we have created the Axis
variable in the RobotJoint
class.
Adding rotations ⇔ Multiplying quaternions
Multiplying two quaternions creates a new quaternion, which incorporates both rotations. During each iteration of the for loop, the variable rotation
is multiplied by the current quaternion. This means that it incorporate the rotations for all the joints.
Quaternion * Vector = Rotated Vector
Finally, quaternions are used in this line:
Vector3 nextPoint = prevPoint + rotation * Joints[i].StartOffset;
This maps one to one to:
A multiplication between a quaternion and a vector applies the rotation.
Other resources
- Part 1. An Introduction to Procedural Animations
- Part 2. The Mathematics of Forward Kinematics
- Part 3. Implementing Forward Kinematics
- Part 4. An Introduction to Gradient Descent
- Part 5. Inverse Kinematics for Robotic Arms
- Part 6. Inverse Kinematics for Tentacles
- Part 7. Inverse Kinematics for Spider Legs 🚧 (work in progress!)
Become a Patron!
Patreon You can download the Unity project for this tutorial on Patreon.
Credits for the 3D model of the robotic arm goes to Petr P. A big thanks also goes to Maurizio Scuiar.
Leave a Reply