Tasks and Limits

The Getting Started drove a robot arm to a target pose. That works because it makes hidden assumptions: the target is reachable, joint limits are never approached, and the arm has enough freedom to satisfy all constraints.

In practice, these assumptions fail. When they do, naive IK will drive joints into hard limits, produce unstable motion, or sacrifice important objectives to satisfy arbitrary ones. Tasks and limits are mink’s way of making these trade-offs explicit and controllable. This page builds on the quickstart, showing what breaks and how to fix it. We’ll stick with the same Panda arm throughout.

What Is a Task?

In mink, a task expresses something the robot should try to do, not something it must do.

Examples:

  • Move an end-effector to a pose (FrameTask)

  • Keep joints near a nominal configuration (PostureTask)

  • Regulate the center of mass (ComTask)

Tasks are soft: they can be violated when necessary. When multiple tasks conflict, mink resolves them by minimizing a weighted sum of their errors.

Tasks vs. Limits

Tasks describe preferences. Limits describe hard boundaries.

  • Tasks can be violated

  • Limits cannot

Examples of limits:

  • Joint position bounds (ConfigurationLimit)

  • Velocity limits (VelocityLimit)

  • Collision avoidance (CollisionAvoidanceLimit)

Under the hood, tasks become quadratic objectives in a QP, while limits become inequality constraints. The solver finds joint velocities that best satisfy the tasks while strictly respecting all limits.

Note

ConfigurationLimit is applied automatically when you don’t pass a custom limits list. All other limits must be added explicitly.

A Single Task in Isolation

Here’s where we left off — a FrameTask driving the end-effector to a target:

import mujoco
from mink import Configuration, FrameTask, solve_ik

model = mujoco.MjModel.from_xml_path("franka_emika_panda/mjx_scene.xml")
configuration = Configuration(model)
configuration.update_from_keyframe("home")

task = FrameTask(
    frame_name="attachment_site",
    frame_type="site",
    position_cost=1.0,
    orientation_cost=1.0,
)
task.set_target(target_pose)

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

This works when the target is comfortably within the robot’s workspace. But a single task can fail in two opposite ways.

When a Single Task Breaks

Singularities

Consider tracking a target that moves outward, requiring the arm to extend toward its reach limit:

# Move outward toward near-full extension.
start_pos = np.array([0.5, 0.0, 0.4])
end_pos = np.array([0.8, 0.0, 0.4])

As the target moves away from the base, the arm must straighten to reach. Near full extension, the elbow approaches a singularity: joint velocities spike to extreme values, the motion becomes violently unstable, and the simulation can explode entirely.

Without regularization: the arm becomes unstable near full extension.

At a singularity, the Jacobian becomes ill-conditioned: even tiny task-space errors require enormous joint velocities. The problem has no reasonable solution.

Nullspace Drift

The opposite problem occurs when the robot has more degrees of freedom than the task requires. With position-only tracking (orientation_cost=0.0), a 7-DOF arm has four extra degrees of freedom. The solver can move the elbow, rotate the wrist, or contort the arm in any way that doesn’t affect the end-effector position.

This is nullspace drift — motion in degrees of freedom that don’t affect the task. Without guidance, you might see:

  • The elbow drifting to awkward angles

  • Unnecessary joint motion between frames

  • Different runs producing different poses

Position-only tracking: the elbow drifts unpredictably.

Adding Regularization

mink provides three ways to regularize the IK problem:

Numerical damping (always available):

  • solve_ik(..., damping=...) adds a small isotropic term to the Hessian, improving conditioning for all DOFs including floating base.

  • Individual tasks can set lm_damping to add error-dependent Levenberg- Marquardt damping, which behaves more conservatively when targets are infeasible.

Behavioral regularization (recommended in practice):

  • DampingTask: Minimizes joint velocities in the actuated subspace (does not affect floating base). Because the QP solves for Δq, this regularizes per-step motion; for fixed dt, it corresponds to velocity damping.

  • PostureTask: Pulls toward a reference configuration.

The behavioral tasks resolve redundancy and stabilize near singularities by trading tracking error for smaller or more predictable motion. Either can help with both problems, but they bias the solution differently:

Task

Behavior

Best for

DampingTask

Minimizes per-step motion

Numerical stability, when no preferred pose exists

PostureTask

Pulls toward reference configuration

Redundancy resolution, manipulation with a “home” pose

We’ll show DampingTask for singularities and PostureTask for nullspace below, but either can work for both.

Fixing Singularities

DampingTask penalizes large values of Δq:

from mink import DampingTask

task = FrameTask(
    frame_name="attachment_site",
    frame_type="site",
    position_cost=1.0,
    orientation_cost=1.0,
)

# Regularization: prefer smaller joint velocities.
damping_task = DampingTask(model, cost=0.5)

for _ in range(steps):
    vel = solve_ik(configuration, [task, damping_task], dt, "daqp")
    configuration.integrate_inplace(vel, dt)

Near a singularity, the primary task demands huge joint velocities to make progress. The damping task pushes back, forcing the solver to accept some tracking error rather than produce extreme motion:

With regularization: the arm accepts tracking error to stay stable.

Note

Regularization does not keep the arm away from singular configurations — it keeps the commanded velocities bounded by trading off tracking accuracy.

Fixing Nullspace Drift

PostureTask biases toward a reference configuration:

from mink import PostureTask

posture_task = PostureTask(model, cost=0.1)
posture_task.set_target_from_configuration(configuration)  # Use current as reference.

Now the nullspace is filled with a preference: “if you have freedom, use it to stay close to home.”

With posture task: the arm stays close to its reference configuration.

Adding Limits

Regularization keeps the solver well-conditioned, but nothing prevents the robot from violating physical constraints. Without explicit limits, joints can exceed their mechanical range, velocities can spike beyond what motors can deliver, and the robot can collide with itself or the environment.

Limits make these boundaries explicit.

Configuration Limits

ConfigurationLimit keeps joints within their mechanical range. When you pass a custom limits list, you must add it explicitly:

from mink import ConfigurationLimit

limits = [ConfigurationLimit(model)]

for _ in range(steps):
    vel = solve_ik(configuration, [task], dt, "daqp", limits=limits)
    configuration.integrate_inplace(vel, dt)

Velocity Limits

IK computes joint velocities, which you integrate into position commands. Because IK outputs joint velocities that are integrated over dt, velocity limits implicitly bound per-step position changes. If those positions change too quickly between timesteps, the low-level controller will demand high velocities or torques to keep up — leading to jerky motion, excessive wear, or safety faults. VelocityLimit caps the rate of change:

from mink import VelocityLimit

velocity_limits = {
    "joint1": 2.0,  # rad/s
    "joint2": 2.0,
    # ... etc
}
velocity_limit = VelocityLimit(model, velocity_limits)

limits = [ConfigurationLimit(model), velocity_limit]

The tradeoff is tracking accuracy: if the target moves faster than the velocity limits allow, the arm will lag behind. In practice, you tune the limits to match your hardware’s actual capabilities.

Collision Avoidance

CollisionAvoidanceLimit prevents specified geometries from colliding. You define pairs of geom groups that should stay apart:

from mink import CollisionAvoidanceLimit

collision_limit = CollisionAvoidanceLimit(
    model,
    geom_pairs=[(["hand"], ["link4", "link5"])],
    minimum_distance_from_collisions=0.05,
)

limits = [ConfigurationLimit(model), collision_limit]

Warning

Collision avoidance constraints tighten as distances shrink. When geoms are close to the minimum distance, this limit can dominate the solution and prevent other motion. Start with conservative (smaller) minimum distances.

Without collision avoidance, nullspace drift can cause self-collision. With it, the solver keeps the hand away from the arm:

Collision avoidance: the hand stays clear of the upper arm.

Practical Guidelines

When to Use What

Always include:

  • ConfigurationLimit — prevents violating joint limits

  • Some form of regularization (DampingTask or PostureTask) — avoids singularity and nullspace issues

Add when needed:

  • VelocityLimit — when you need smooth, rate-limited motion

  • CollisionAvoidanceLimit — when self-collision or environment collision is possible

Complete Example

Here’s everything together — pose tracking with regularization and limits:

import mujoco
from mink import (
    Configuration,
    ConfigurationLimit,
    FrameTask,
    PostureTask,
    VelocityLimit,
    solve_ik,
)

# Load and configure.
model = mujoco.MjModel.from_xml_path("franka_emika_panda/mjx_scene.xml")
configuration = Configuration(model)
configuration.update_from_keyframe("home")

# Primary task: pose tracking.
task = FrameTask(
    frame_name="attachment_site",
    frame_type="site",
    position_cost=1.0,
    orientation_cost=1.0,
)

# Regularization: bias toward home configuration.
# This handles both singularities (resists extreme velocities near them)
# and nullspace drift (fills unused DOFs with a preference).
posture_task = PostureTask(model, cost=0.1)
posture_task.set_target_from_configuration(configuration)

tasks = [task, posture_task]

# Limits: joint bounds + velocity cap.
velocity_limits = {"joint1": 2.0, "joint2": 2.0, ...}
limits = [
    ConfigurationLimit(model),
    VelocityLimit(model, velocity_limits),
]

# IK loop.
dt = 0.01
for _ in range(steps):
    task.set_target(get_target())  # Update target each step.
    vel = solve_ik(configuration, tasks, dt, "daqp", limits=limits)
    configuration.integrate_inplace(vel, dt)

What’s Next

For more task types, limits, and real-world examples: