Configuration
The configuration module serves as the mathematical foundation of MJINX, providing essential utilities for robot kinematics, transformations, and state management. These core functions enable precise control and manipulation of robotic systems throughout the library.
The module is structured into three complementary categories, each addressing a critical aspect of robot configuration:
Model - Functions for manipulating the MuJoCo model and managing robot state
Lie Algebra - Specialized tools for handling rotations and transformations with mathematical rigor
Collision - Algorithms for detecting and responding to potential collisions
Model
The model operations provide fundamental capabilities for state integration, Jacobian computation, and frame transformations. These functions form the bridge between abstract mathematical representations and the physical robot model.
- update(model, q)
Update the MuJoCo data with new joint positions.
- Parameters:
model (
Model
) – The MuJoCo model.q (
Array
) – The new joint positions.
- Return type:
Data
- Returns:
Updated MuJoCo data.
- get_frame_jacobian_world_aligned(model, data, obj_id, obj_type=<mjtObj.mjOBJ_BODY: 1>)
Compute the Jacobian of an object’s frame with respect to joint velocities.
This function calculates the geometric Jacobian that maps joint velocities to the linear and angular velocities of a specified object (body, geom, or site) in world-aligned coordinates:
\[\begin{split}J = \begin{bmatrix} J_v \\ J_\omega \end{bmatrix}\end{split}\]- where:
\(J_v\) is the 3×nv position Jacobian
\(J_\omega\) is the 3×nv orientation Jacobian
The position Jacobian for revolute joints includes terms for both direct motion and motion due to rotation:
\[J_v = J_{direct} + J_{\omega} \times (p - p_{com})\]- where:
\(p\) is the position of the object
\(p_{com}\) is the center of mass of the subtree
- Parameters:
model (
Model
) – The MuJoCo model.data (
Data
) – The MuJoCo data.obj_id (
int
) – The ID of the object.obj_type (
mjtObj
) – The type of the object (mjOBJ_BODY, mjOBJ_GEOM, or mjOBJ_SITE).
- Return type:
- Returns:
The geometric Jacobian matrix (6×nv).
- get_frame_jacobian_local(model, data, obj_id, obj_type=<mjtObj.mjOBJ_BODY: 1>)
Compute the Jacobian of an object’s frame with respect to joint velocities in local coordinates.
Similar to get_frame_jacobian_world_aligned, but expresses the Jacobian in the local coordinate frame of the object. This is often useful for operational space control and computing task-space errors.
For the local frame Jacobian:
\[\begin{split}J_{local} = \begin{bmatrix} R^T J_v \\ R^T J_\omega \end{bmatrix}\end{split}\]- where:
\(R\) is the rotation matrix of the object
\(J_v\) and \(J_\omega\) are the world-aligned position and orientation Jacobians
- Parameters:
model (
Model
) – The MuJoCo model.data (
Data
) – The MuJoCo data.obj_id (
int
) – The ID of the object.obj_type (
mjtObj
) – The type of the object (mjOBJ_BODY, mjOBJ_GEOM, or mjOBJ_SITE).
- Return type:
- Returns:
The geometric Jacobian matrix in local coordinates (6×nv).
- get_transform_frame_to_world(model, data, frame_id)
Get the transformation from frame to world coordinates.
- Parameters:
model (
Model
) – The MuJoCo model.data (
Data
) – The MuJoCo data.frame_id (
int
) – The ID of the frame.
- Return type:
- Returns:
The SE3 transformation.
- get_transform(model, data, source_id, dest_id)
Get the transformation between two frames.
- Parameters:
model (
Model
) – The MuJoCo model.data (
Data
) – The MuJoCo data.source_id (
int
) – The ID of the source frame.dest_id (
int
) – The ID of the destination frame.
- Return type:
- Returns:
The SE3 transformation from source to destination.
- integrate(model, q0, velocity, dt)
Integrate the joint positions given initial position, velocity, and time step.
For standard joints, integration is linear:
\[q_1 = q_0 + v \cdot dt\]For quaternion-based joints, integration uses the exponential map:
\[q_1 = q_0 \otimes \exp(\frac{v \cdot dt}{2})\]- where:
\(\otimes\) is quaternion multiplication
\(\exp\) is the exponential map from the Lie algebra to the Lie group
This function handles the proper integration for different joint types in the model, ensuring that rotational joints maintain proper constraints (e.g., unit quaternions).
- get_configuration_limit(model, limit)
Get the configuration limits for the model.
Lie Algebra
The Lie algebra operations implement sophisticated mathematical tools for handling rotations, quaternions, and transformations in 3D space. Based on principles from differential geometry, these functions ensure proper handling of the SE(3) and SO(3) Lie groups.
- get_joint_zero(model)
Get the zero configuration for all joints in the model.
- Parameters:
model (
Model
) – The MuJoCo model.- Return type:
- Returns:
An array representing the zero configuration for all joints.
- joint_difference(model, q1, q2)
Compute the difference between two joint configurations.
This function calculates the configuration space difference between two joint states. For standard joints (hinge, slide), this is a simple subtraction. For quaternion-based joints (free, ball), this uses the proper Lie group operations:
\[\begin{split}\Delta q = \begin{cases} q_1 - q_2 & \text{for standard joints} \\ \log(q_1 \cdot q_2^{-1}) & \text{for quaternion joints} \end{cases}\end{split}\]- where:
\(q_1, q_2\) are the two joint configurations
\(\log\) is the logarithmic map from SO(3) or SE(3) to their tangent spaces
- skew_symmetric(v)
Create a skew-symmetric matrix from a 3D vector.
This function takes a 3D vector and returns its corresponding 3x3 skew-symmetric matrix. The skew-symmetric matrix is used in various robotics and physics calculations, particularly for cross products and rotations.
\[\begin{split}[v]_{\times} = \begin{bmatrix} 0 & -v_z & v_y \\ v_z & 0 & -v_x \\ -v_y & v_x & 0 \end{bmatrix}\end{split}\]This matrix has the property that for any vector w, [v]_× w = v × w (cross product).
- attitude_jacobian(q)
Compute the attitude Jacobian for a quaternion.
This function calculates the 4x3 attitude Jacobian matrix for a given unit quaternion. The attitude Jacobian relates angular velocity ω to quaternion rate of change q̇:
\[\dot{q} = \frac{1}{2} E(q) \omega\]where E(q) is the attitude Jacobian:
\[\begin{split}E(q) = \begin{bmatrix} -q_x & -q_y & -q_z \\ q_w & -q_z & q_y \\ q_z & q_w & -q_x \\ -q_y & q_x & q_w \end{bmatrix}\end{split}\]With \(q = [q_w, q_x, q_y, q_z]\) being the quaternion.
- Parameters:
q (
Array
) – A unit quaternion represented as a 4D array [w, x, y, z].- Return type:
- Returns:
A 4x3 attitude Jacobian matrix.
- Ref:
Based on [Jackson et al., 2021]
- jac_dq2v(model, q)
Compute the Jacobian matrix for converting from generalized positions to velocities.
This function calculates the Jacobian matrix J that maps changes in generalized positions (q) to generalized velocities (v):
\[\delta v = J \cdot \delta q\]For standard revolute and prismatic joints, this mapping is simply the identity. For quaternion-based joints (ball, free), the mapping involves the attitude Jacobian:
\[\begin{split}J = \begin{bmatrix} I & 0 \\ 0 & E(q) \end{bmatrix}\end{split}\]where E(q) is the attitude Jacobian for the quaternion component.
- Parameters:
model (
Model
) – A MuJoCo model object (mjx.Model).q (
Array
) – The current generalized positions of the model.
- Returns:
A Jacobian matrix of shape (nq, nv), where nq is the number of position variables and nv is the number of velocity variables.
Collision
The collision operations provide sophisticated algorithms for detecting potential collisions, computing distances between objects, and analyzing contact points. These functions are crucial for implementing safety constraints and realistic physical interactions.
- sorted_pair(x, y)
Return a sorted pair of integers.
- Parameters:
x (
int
) – The first integer.y (
int
) – The second integer.
- Return type:
tuple
[int
,int
]- Returns:
A tuple of the two integers, sorted in ascending order.
- geom_groups(model, collision_pairs)
Group geometry pairs by their collision function characteristics.
Groups collision pairs based on geometry types, mesh properties, and collision dimensions. For mesh geometries, convex functions are executed separately for each distinct mesh in the model since convex functions require static mesh sizes.
This function is greatly inspired by mujoco.mjx._src.collision_driver module.
- Parameters:
model (
Model
) – The MuJoCo model containing geometry information.collision_pairs (
list
[tuple
[int
,int
]]) – List of collision pairs to be grouped.
- Return type:
dict
[FunctionKey
,SimplifiedContact
]- Returns:
Dictionary mapping function keys to simplified contact information.
- compute_collision_pairs(m, d, collision_pairs)
Process and compute collisions between specified geometry pairs.
For each collision pair, this function computes: 1. The minimum distance between geometries 2. The contact point location 3. The contact normal direction
The distance computation depends on the geometry types, but generally follows:
\[d(G_1, G_2) = \min_{p_1 \in G_1, p_2 \in G_2} \|p_1 - p_2\| - (r_1 + r_2)\]- where:
\(G_1, G_2\) are the geometries
\(r_1, r_2\) are their respective radii/margins
\(p_1, p_2\) are points on the geometries
- Parameters:
m (
Model
) – The MuJoCo model containing simulation parameters.d (
Data
) – The MuJoCo data containing current state information.collision_pairs (
list
[tuple
[int
,int
]]) – List of geometry pairs to check for collisions.
- Return type:
- Returns:
Simplified contact information containing collision results.
- get_distance(model, data, collision_pairs)
Compute the distances for the given collision pairs.
This function is greatly inspired by mujoco.mjx._src.collision_driver module.
- geom_point_jacobian(model, data, point, body_id)
Compute the Jacobian of a point on a body with respect to joint velocities.
This function calculates how a specific point on a body moves in world coordinates when joint velocities are applied. For a point p on body b, the Jacobian is:
\[\begin{split}J_p = \begin{bmatrix} J_v \\ J_\omega \end{bmatrix}\end{split}\]- where:
\(J_v\) relates joint velocities to the linear velocity of the point
\(J_\omega\) relates joint velocities to the angular velocity at the point
This Jacobian is essential for many robotics applications, including operational space control, collision avoidance, and contact modeling.