Python inverse kinematics for articulated robot models, based on Pinocchio.
pip install pin-pink
On Raspberry Pi, you will need to install from source.
Pink solves differential inverse kinematics by weighted tasks. A task is defined by a residual function
In differential inverse kinematics, we compute a velocity
where
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 body 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:
- Arms: Kinova Gen2, UR3
- Humanoids: JVRC-1, SigmaBan
- Wheeled biped: Upkie
- Wheeled: Omnidirectional robot
Check out the examples folder for more.
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.
Software:
- Jink.jl: Julia package for differential multi-task inverse kinematics.
- pymanoid: precursor to Pink based on OpenRAVE.
Technical notes:
- Inverse kinematics: a general introduction to differential inverse kinematics.
- Jacobian of a kinematic task and derivatives on manifolds.