Rotations and Poses¶
mink represents rotations and rigid transforms using Lie groups:
SO3for 3D rotationsSE3for 3D rigid body transforms (rotation + translation)
These classes are used throughout mink to represent frame poses, specify targets, and compute pose errors consistently.
This page focuses on how to use these objects.
Conventions¶
Quaternions¶
mink uses MuJoCo’s quaternion convention: scalar-first quaternions
(qw, qx, qy, qz) (also written wxyz).
Composition and action via @¶
mink overloads the @ operator:
T1 @ T2composes two transformations.T @ papplies a transformation to a pointp.Similarly for rotations:
R1 @ R2andR @ v.
This mirrors common robotics notation.
Composition follows standard robotics conventions: A @ B means “apply B,
then A”.
SO3: Rotations¶
Creating rotations¶
Use the exponential map for axis-angle rotations:
import numpy as np
import mink
# Rotation from a tangent vector (axis-angle, radians).
R = mink.SO3.exp(np.array([0.0, 0.0, np.pi / 2]))
Convenience constructors exist for common axes and roll/pitch/yaw:
Rz = mink.SO3.from_z_radians(np.pi / 2)
Rrpy = mink.SO3.from_rpy_radians(roll=0.1, pitch=0.2, yaw=-0.3)
Identity and normalization:
R = mink.SO3.identity()
R = R.normalize()
Applying and composing¶
Apply a rotation to a vector:
v = np.array([1.0, 0.0, 0.0])
v_rot = Rz @ v
Compose rotations (right-multiplication):
R = mink.SO3.from_z_radians(0.3) @ mink.SO3.from_x_radians(-0.2)
Log/Exp (tangent space)¶
log() maps a rotation to a 3D tangent vector (axis-angle),
and exp() maps a tangent vector back to a rotation:
omega = R.log() # shape (3,)
R_recovered = mink.SO3.exp(omega)
These are useful for expressing small rotation errors and for interpolation.
SE3: Rigid Body Transformations¶
Creating transforms¶
An SE3 stores rotation + translation. Use:
from_rotation_and_translation()from_translation()from_rotation()
import numpy as np
import mink
R = mink.SO3.from_z_radians(np.pi / 4)
t = np.array([0.2, 0.0, 0.1])
T = mink.SE3.from_rotation_and_translation(R, t)
Example: building a pose target¶
The following example shows how to construct a nearby pose target in the world frame using SE(3) composition.
T_current = configuration.get_transform_frame_to_world("ee", "site")
T_target = mink.SE3.from_translation(np.array([0.0, 0.0, 0.1])) @ T_current
frame_task.set_target(T_target)
Composition: world vs local updates¶
The most common source of confusion is where an increment is applied.
Let T be a pose. Consider a small translation transform Δ:
Δ = mink.SE3.from_translation(np.array([0.0, 0.0, 0.1]))
Left-multiplying applies the increment in the world frame:
T_world = Δ @ T
Right-multiplying applies the increment in the local frame:
T_local = T @ Δ
This is the same pattern used in the quickstart when composing translations in world coordinates and rotations in the end-effector’s local frame.
Applying a transform¶
p = np.array([0.0, 0.0, 0.0])
p_world = T @ p
Access rotation and translation:
R = T.rotation()
t = T.translation()
Pose differences and task errors (right-minus)¶
For SE3, the tangent vector is ordered as
\((v_x, v_y, v_z, \omega_x, \omega_y, \omega_z)\),
i.e., translation first, then rotation.
For IK, mink represents pose errors using the right-minus operator (also called a body-frame error):
In code, this corresponds to rminus():
e = T.rminus(T_target) # shape (6,) for SE3
Intuitively, T.rminus(T_target) answers the question:
From my current pose
T, what small motion (twist) should I apply to myself to reachT_target?
The resulting error is expressed in the current (body) frame: translations are along the frame’s local axes, and rotations are about its local axes. This matches mink’s body-frame Jacobians, which map joint velocities to body-frame twists.
By contrast, T_target.rminus(T) would express the error in the target
frame, answering “where is the robot relative to the target?”. While this is a
valid quantity, it is not the convention used by mink’s inverse kinematics.
In particular, FrameTask uses:
which is a 6D twist error consistent with mink’s body-frame Jacobians.
Internally, FrameTask uses jlog() to
linearize the log-map error; most users do not need to call it directly.
Interpolation¶
You can interpolate on the manifold using:
T_mid = T0.interpolate(T1, alpha=0.5)
This is useful for smooth target trajectories without linearizing rotations.
Further Reading¶
For Lie group fundamentals and Jacobians (left/right Jacobians, plus/minus), see: