mink

mink (MuJoCo inverse kinematics) is a library for differential inverse kinematics built on top of the MuJoCo physics engine.

Banner for mink

It solves the following problem: given a robot’s current configuration and a set of task-space objectives, compute a joint velocity that best satisfies those objectives while respecting constraints.

Tasks specify what the robot should do—place a foot on a ledge or reach a handhold— while limits specify what it must not do—exceed joint limits or collide with obstacles. At each control step, mink formulates this as a quadratic program and solves for a locally optimal joint velocity.

Differential inverse kinematics is widely used in motion planning, legged control, teleoperation, and motion retargeting.

Why mink?

  • Composable task abstraction Specify multiple task-space objectives—such as placing a foot and regulating the robot’s center of mass—and combine them in a single solve step.

  • Graceful handling of constraints Objectives and constraints are combined in a single optimization problem, enabling principled trade-offs when commands conflict or cannot be fully satisfied.

  • Designed for real-time control A fast, local solver intended to run every control step, making it suitable for real-time control applications.

Minimal example

Drive an end-effector to a target position:

import mujoco
from mink import Configuration, FrameTask, solve_ik

model = mujoco.MjModel.from_xml_path("robot.xml")
configuration = Configuration(model)

task = FrameTask(
    frame_name="end_effector",
    frame_type="site",
    position_cost=1.0,
    orientation_cost=0.0,
)
task.set_target_from_position([0.5, 0.0, 0.3])

for _ in range(max_iters):
    vel = solve_ik(configuration, [task], dt=0.01)
    configuration.integrate_inplace(vel, dt=0.01)