Tasks

All kinematic tasks derive from the Task base class.

class mink.tasks.task.Objective

Quadratic objective of the form \(\frac{1}{2} x^T H x + c^T x\).

H: ndarray

Hessian matrix, of shape (n_v, n_v)

c: ndarray

Linear vector, of shape (n_v,).

value(x: ndarray) float

Returns the value of the objective at the input vector.

Parameters:

x (ndarray) –

Return type:

float

class mink.tasks.task.Task

Abstract base class for kinematic tasks.

Subclasses must implement the configuration-dependent task error compute_error() and Jacobian compute_jacobian() functions.

The error function \(e(q) \in \mathbb{R}^{k}\) is the quantity that the task aims to drive to zero (\(k\) is the dimension of the task). It appears in the first-order task dynamics:

\[J(q) \Delta q = -\alpha e(q)\]

The Jacobian matrix \(J(q) \in \mathbb{R}^{k \times n_v}\), with \(n_v\) the dimension of the robot’s tangent space, is the derivative of the task error \(e(q)\) with respect to the configuration \(q \in \mathbb{R}^{n_q}\). The configuration displacement \(\Delta q\) is the output of inverse kinematics; we divide it by dt to get a commanded velocity.

In the first-order task dynamics, the error \(e(q)\) is multiplied by the task gain \(\alpha \in [0, 1]\). This gain can be 1.0 for dead-beat control (i.e. converge as fast as possible), but might be unstable as it neglects our first-order approximation. Lower values cause slow down the task, similar to low-pass filtering.

abstract compute_error(configuration: Configuration) ndarray

Compute the task error at the current configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Task error vector \(e(q)\).

Return type:

ndarray

abstract compute_jacobian(configuration: Configuration) ndarray

Compute the task Jacobian at the current configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Task jacobian \(J(q)\).

Return type:

ndarray

compute_qp_objective(configuration: Configuration) Objective

Compute the matrix-vector pair \((H, c)\) of the QP objective.

This pair is such that the contribution of the task to the QP objective is:

\[\| J \Delta q + \alpha e \|_{W}^2 = \frac{1}{2} \Delta q^T H \Delta q + c^T q\]

The weight matrix \(W \in \mathbb{R}^{k \times k}\) weights and normalizes task coordinates to the same unit. The unit of the overall contribution is [cost]^2.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Pair \((H(q), c(q))\).

Return type:

Objective

Frame task

Frame task implementation.

class mink.tasks.frame_task.FrameTask

Regulate the pose of a frame expressed in the world frame.

frame_name

Name of the frame to regulate, typically the name of body, geom or site in the robot model.

frame_type

The frame type: body, geom or site.

transform_frame_to_world

Target pose of the frame.

set_target(transform_target_to_world: SE3) None

Set the target pose.

Parameters:

transform_target_to_world (SE3) – Transform from the task target frame to the world frame.

Return type:

None

set_target_from_configuration(configuration: Configuration) None

Set the target pose from a given robot configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Return type:

None

compute_error(configuration: Configuration) ndarray

Compute the frame task error.

This error is a twist \(e(q) \in se(3)\) expressed in the local frame, i.e., it is a body twist. It is computed by taking the right-minus difference between the target pose \(T_{0t}\) and current frame pose \(T_{0b}\):

\[e(q) := {}_b \xi_{0b} = -(T_{t0} \ominus T_{b0}) = -\log(T_{t0} \cdot T_{0b}) = -\log(T_{tb}) = \log(T_{bt})\]

where \(b\) denotes our frame, \(t\) the target frame and \(0\) the inertial frame.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Frame task error vector \(e(q)\).

Return type:

ndarray

compute_jacobian(configuration: Configuration) ndarray

Compute the frame task Jacobian.

The derivation of the formula for this Jacobian is detailed in [FrameTaskJacobian].

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Frame task jacobian \(J(q)\).

Return type:

ndarray

Relative frame task

Relative frame task implementation.

class mink.tasks.relative_frame_task.RelativeFrameTask

Regulate the pose of a frame relative to another frame.

frame_name

Name of the frame to regulate, typically the name of body, geom or site in the robot model.

frame_type

The frame type: body, geom or site.

root_name

Name of the frame the task is relative to.

root_type

The root frame type: body, geom or site.

transform_target_to_root

Target pose in the root frame.

Type:

mink.lie.se3.SE3 | None

set_target(transform_target_to_root: SE3) None

Set the target pose in the root frame.

Parameters:

transform_target_to_root (SE3) – Transform from the task target frame to the root frame.

Return type:

None

set_target_from_configuration(configuration: Configuration) None

Set the target pose from a given robot configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Return type:

None

compute_error(configuration: Configuration) ndarray

Compute the task error at the current configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Task error vector \(e(q)\).

Return type:

ndarray

compute_jacobian(configuration: Configuration) ndarray

Compute the task Jacobian at the current configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Task jacobian \(J(q)\).

Return type:

ndarray

Center of mass task

Center-of-mass task implementation.

class mink.tasks.com_task.ComTask

Regulate the center-of-mass (CoM) of a robot.

target_com

Target position of the CoM.

Type:

numpy.ndarray | None

set_target(target_com: ArrayLike) None

Set the target CoM position in the world frame.

Parameters:

target_com (ArrayLike) – Desired center-of-mass position in the world frame.

Return type:

None

set_target_from_configuration(configuration: Configuration) None

Set the target CoM from a given robot configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Return type:

None

compute_error(configuration: Configuration) ndarray

Compute the CoM task error.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Center-of-mass task error vector \(e(q)\).

Return type:

ndarray

compute_jacobian(configuration: Configuration) ndarray

Compute the CoM task Jacobian.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Center-of-mass task jacobian \(J(q)\).

Return type:

ndarray

Posture task

Posture task implementation.

class mink.tasks.posture_task.PostureTask

Regulate the joint angles of the robot towards a desired posture.

A posture is a vector of actuated joint angles. Floating-base coordinates are not affected by this task.

target_q

Target configuration.

Type:

numpy.ndarray | None

set_target(target_q: ArrayLike) None

Set the target posture.

Parameters:

target_q (ArrayLike) – Desired joint configuration.

Return type:

None

set_target_from_configuration(configuration: Configuration) None

Set the target posture from the current configuration.

Parameters:

configuration (Configuration) – Robot configuration \(q\).

Return type:

None

compute_error(configuration: Configuration) ndarray

Compute the posture task error.

The error is defined as:

\[e(q) = q^* \ominus q\]
Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Posture task error vector \(e(q)\).

Return type:

ndarray

compute_jacobian(configuration: Configuration) ndarray

Compute the posture task Jacobian.

The task Jacobian is defined as:

\[J(q) = I_{n_v}\]
Parameters:

configuration (Configuration) – Robot configuration \(q\).

Returns:

Posture task jacobian \(J(q)\).

Return type:

ndarray

Damping task

Damping task implementation.

class mink.tasks.damping_task.DampingTask

Minimize joint velocities.

This task is implemented as a special case of the PostureTask where the gain and target configuration are set to 0 and qpos0 respectively.