Python inverse kinematics based on Pinocchio
APACHE-2.0 License
Python inverse kinematics for articulated robot models, based on Pinocchio.
For best performance we recommended installing Pink from Conda:
conda install -c conda-forge pink
You can also install it from PyPI:
pip install pin-pink
Pink solves differential inverse kinematics by weighted tasks. A task is defined by a residual function $e(q)$ of the robot configuration $q \in \mathcal{C}$ to be driven to zero. For instance, putting a foot position $p_{foot}(q)$ at a given target $p_{foot}^{\star}$ can be described by the position residual:
$$ e(q) = p_{foot}^{\star} - p_{foot}(q) $$
In differential inverse kinematics, we compute a velocity $v \in \mathfrak{c}$ that satisfies the first-order differential equation:
$$ J_e(q) v = \dot{e}(q) = -\alpha e(q) $$
where $J_e(q) := \frac{\partial e}{\partial q}$ is the task Jacobian. We can define multiple tasks, but some of them will come into conflict if they can't be all fully achieved at the same time. Conflicts are resolved by casting all objectives to a common unit, and weighing these normalized objectives relative to each other. We also include configuration and velocity limits, making our overall optimization problem a quadratic program:
$$ \begin{align} \underset{v \in \mathfrak{c}}{\text{minimize}} \ & \sum_{\text{task } e} \Vert J_e(q) v + \alpha e(q) \Vert^2_{W_e} \ \text{subject to} \ & v_{\text{min}}(q) \leq v \leq v_{\text{max}}(q) \end{align} $$
Pink provides an API to describe the problem as tasks with targets, and automatically build and solve the underlying quadratic program.
Here is the example of a biped robot that controls the position and orientation of its base, left and right contact frames. A fourth "posture" task, giving a preferred angle for each joint, is added for regularization:
from pink.tasks import FrameTask, PostureTask
tasks = {
"base": FrameTask(
"base",
position_cost=1.0, # [cost] / [m]
orientation_cost=1.0, # [cost] / [rad]
),
"left_contact": FrameTask(
"left_contact",
position_cost=[0.1, 0.0, 0.1], # [cost] / [m]
orientation_cost=0.0, # [cost] / [rad]
),
"right_contact": FrameTask(
"right_contact",
position_cost=[0.1, 0.0, 0.1], # [cost] / [m]
orientation_cost=0.0, # [cost] / [rad]
),
"posture": PostureTask(
cost=1e-3, # [cost] / [rad]
),
}
Orientation (similarly position) costs can be scalars or 3D vectors. They specify how much each radian of angular error "costs" in the overall normalized objective. When using 3D vectors, components are weighted anisotropically along each axis of the body frame.
Aside from their costs, most tasks take a second set of parameters called target. For example, a frame task aims for a target transform, while a posture task aims for a target configuration vector. Targets are set by the set_target
function:
tasks["posture"].set_target(
[1.0, 0.0, 0.0, 0.0] + # floating base quaternion
[0.0, 0.0, 0.0] + # floating base position
[0.0, 0.2, 0.0, 0.0, -0.2, 0.0] # joint angles
)
Body tasks can be initialized, for example, from the robot's neutral configuration:
import pink
from robot_descriptions.loaders.pinocchio import load_robot_description
robot = load_robot_description("upkie_description")
configuration = pink.Configuration(robot.model, robot.data, robot.q0)
for body, task in tasks.items():
if type(task) is FrameTask:
task.set_target(configuration.get_transform_frame_to_world(body))
A task can be added to the inverse kinematics once both its cost and target (if applicable) are defined.
Pink solves differential inverse kinematics, meaning it outputs a velocity that steers the robot towards achieving all tasks at best. If we keep integrating that velocity, and task targets don't change over time, we will converge to a stationary configuration:
dt = 6e-3 # [s]
for t in np.arange(0.0, 42.0, dt):
velocity = solve_ik(configuration, tasks.values(), dt, solver="quadprog")
configuration.integrate_inplace(velocity, dt)
time.sleep(dt)
If task targets are continuously updated, there will be no stationary solution to converge to, but the model will keep on tracking each target at best. Note that solve_ik
will take care of both configuration and velocity limits read from the robot model.
Basic examples to get started:
Pink works with all kinds of robot morphologies:
Check out the examples directory for more code.
Pink implements differential inverse kinematics, a first-order algorithm that converges to the closest optimum of its cost function. It is a local method that does not solve the more difficult problem of global inverse kinematics. That is, it may converge to a global optimum, or to a local one stuck to some configuration limits. This behavior is illustrated in the simple pendulum with configuration limit example.
Install the library and use it! Report bugs in the issue tracker. If you are a developer with some robotics experience looking to hack on open source, check out the contribution guidelines.
If you use Pink in your scientific works, please cite it e.g. as follows:
@software{pink2024,
title = {{Pink: Python inverse kinematics based on Pinocchio}},
author = {Caron, Stéphane and De Mont-Marin, Yann and Budhiraja, Rohan and Bang, Seung Hyeon and Domrachev, Ivan and Nedelchev, Simeon},
license = {Apache-2.0},
url = {https://github.com/stephane-caron/pink},
version = {3.0.0},
year = {2024}
}
Software:
Technical notes: