Barriers implement inequality constraints in the inverse kinematics problem. Each barrier defines a scalar function \(h: \mathcal{Q} \rightarrow \mathbb{R}\) that must remain positive (\(h(q) \geq 0\)), creating a boundary that the solver must respect. This approach is mathematically equivalent to control barrier functions (CBFs) [Ames et al., 2019], which have been widely adopted in robotics for safety-critical control.
The barrier formulation creates a continuous constraint boundary that prevents the system from entering prohibited regions of the configuration space. In the optimization problem, these constraints are typically enforced through linearization at each step:
where \(\alpha\) is a gain parameter that controls how aggressively the system is pushed away from the constraint boundary.
All barriers follow a consistent mathematical formulation while adapting to specific constraint types, enabling systematic enforcement of safety and feasibility requirements.
Base Barrier
The foundation for all barrier constraints, defining the core mathematical properties and interface.
- class JaxBarrier(dim, model, vector_gain, gain_fn, mask_idxs, safe_displacement_gain)
A base class for implementing barrier functions in JAX.
This class provides a framework for creating barrier functions that can be used in optimization problems, particularly for constraint handling in robotics applications.
A barrier function is defined mathematically as a function:
\[h(q) \geq 0\]where the constraint is satisfied when h(q) is non-negative. As h(q) approaches zero, the barrier “activates” to prevent constraint violation. In optimization problems, the barrier helps enforce constraints by adding a penalty term that increases rapidly as the system approaches constraint boundaries.
- Parameters:
safe_displacement_gain (
float
) – The gain for computing safe displacements.
- compute_barrier(data)
Compute the barrier function value.
This method calculates the value of the barrier function h(q) at the current state. The barrier is active when h(q) is close to zero and satisfied when h(q) > 0.
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
The computed barrier value.
- compute_safe_displacement(data)
Compute a safe displacement to move away from constraint boundaries.
When the barrier function value is close to zero, this method computes a displacement in joint space that helps move the system away from the constraint boundary:
\[\Delta q_{safe} = \alpha \nabla h(q)\]- where:
\(\alpha\) is the safe_displacement_gain
\(\nabla h(q)\) is the gradient of the barrier function
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
A joint displacement vector to move away from constraint boundaries.
- class Barrier(name, gain, gain_fn=None, safe_displacement_gain=0, mask=None)
A generic barrier class that wraps atomic barrier implementations.
This class provides a high-level interface for barrier functions, allowing for easy integration into optimization problems. Barrier functions are used to enforce constraints by creating a potential field that pushes the system away from constraint boundaries.
In optimization problems, barriers are typically integrated as inequality constraints or as penalty terms in the objective function:
\[\min_{q} f(q) \quad \text{subject to} \quad h(q) \geq 0\]or as a penalty term:
\[\min_{q} f(q) - \lambda \log(h(q))\]where \(\lambda\) is a weight parameter.
- Parameters:
safe_displacement_gain – The gain for computing safe displacements.
Joint Barrier
Enforces joint limit constraints, preventing the robot from exceeding mechanical limits.
- class JaxJointBarrier(dim, model, vector_gain, gain_fn, mask_idxs, safe_displacement_gain, q_min, q_max, qmask_idxs)
A JAX implementation of a joint barrier function.
This class extends the JaxBarrier to specifically handle joint limits in a robotic system. It computes barrier values based on the current joint positions relative to their minimum and maximum limits.
The joint barrier enforces that joint positions remain within their specified limits:
\[\begin{split}h_{min}(q) &= q - q_{min} \geq 0 \\ h_{max}(q) &= q_{max} - q \geq 0\end{split}\]- where:
\(q\) is the joint position vector
\(q_{min}\) is the vector of minimum joint limits
\(q_{max}\) is the vector of maximum joint limits
- compute_jacobian(data)
Compute the Jacobian of the joint barrier function.
For joint barriers, the Jacobian has a simple form: - For lower limits (\(q - q_{min}\)): \(J = I\) (identity matrix) - For upper limits (\(q_{max} - q\)): \(J = -I\) (negative identity matrix)
These are combined into a single Jacobian matrix, with appropriate adjustments for masked joints and floating base.
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
The Jacobian matrix of the barrier function.
- class JointBarrier(name, gain, gain_fn=None, safe_displacement_gain=0, q_min=None, q_max=None, mask=None)
A high-level joint barrier class that wraps the JaxJointBarrier implementation.
This class provides an interface for creating and managing joint barriers, including methods for updating joint limits and handling model-specific details.
Joint barriers are one of the most common constraint types in robotics, ensuring that joint positions respect their mechanical limits. They can be incorporated into optimization problems to prevent solutions that would require impossible joint configurations.
The barrier function is formulated to create a potential field that increases as joints approach their limits, effectively pushing the optimization away from invalid regions.
- Parameters:
name (
str
) – The name of the barrier.gain (
ndarray
|Array
|float
) – The gain for the barrier function.gain_fn (
Callable
[[float
],float
] |None
) – A function to compute the gain dynamically.safe_displacement_gain (
float
) – The gain for computing safe displacements.q_min (
Sequence
|None
) – The minimum joint limits.q_max (
Sequence
|None
) – The maximum joint limits.mask (
Sequence
[int
] |None
) – A sequence of integers to mask certain joints.
- JaxComponentType
alias of
JaxJointBarrier
- property q_min: Array
Get the minimum joint limits.
- Returns:
The minimum joint limits.
- Raises:
ValueError – If q_min is not defined.
- update_q_min(q_min)
Update the minimum joint limits.
- property q_max: Array
Get the maximum joint limits.
- Returns:
The maximum joint limits.
- Raises:
ValueError – If q_max is not defined.
- update_q_max(q_max)
Update the maximum joint limits.
- update_model(model)
Update the barrier with a new model.
This method updates internal parameters based on the new model, including dimensions and joint limits if not previously set.
- Parameters:
model (
Model
) – The new MuJoCo model.
Base Body Barrier
The foundation for barriers applied to specific bodies, geometries, or sites in the robot model. This abstract class provides common functionality for all object-specific barriers.
Frame task implementation.
- class JaxObjBarrier(dim, model, vector_gain, gain_fn, mask_idxs, safe_displacement_gain, obj_id, obj_type)
A JAX implementation of an object-specific barrier function.
This class extends JaxBarrier to provide barrier functions that are specific to a particular object (body, geometry, or site) in the robot model.
Object barriers define constraints on properties of specific objects, such as their position, orientation, or other attributes. The general form is:
\[h(q) = g(p(q)) \geq 0\]- where:
\(p(q)\) is some property of the object (e.g., position)
\(g(\cdot)\) is a function that converts this property into a barrier value
- Parameters:
obj_id (
int
) – The ID of the object (body, geometry, or site) to which this barrier applies.obj_type (
mjtObj
) – The type of the object (mjOBJ_BODY, mjOBJ_GEOM, or mjOBJ_SITE).
- get_pos(data)
Get the position of the object in the world frame.
This method returns the position based on the object type (body, geom, or site).
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
A 3D vector representing the object’s position in the world frame.
- get_rotation(data)
Get the rotation of the object in the world frame.
This method returns the rotation based on the object type (body, geom, or site).
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
An SO3 object representing the object’s rotation in the world frame.
- get_frame(data)
Get the full pose (position and rotation) of the object in the world frame.
This method combines the position and rotation to return a complete pose.
- Parameters:
data (
Data
) – The MuJoCo simulation data.- Return type:
- Returns:
An SE3 object representing the object’s pose in the world frame.
- class ObjBarrier(name, gain, obj_name, obj_type=<mjtObj.mjOBJ_BODY: 1>, gain_fn=None, safe_displacement_gain=0, mask=None)
A generic object barrier class that wraps atomic object barrier implementations.
This class provides a high-level interface for object-specific barrier functions, which can be applied to bodies, geometries, or sites in the robot model.
Object barriers create constraints that depend on specific robot parts, such as: - Position limits for end effectors - Orientation constraints for specific links - Workspace boundaries for manipulators
The barrier function ensures that these constraints are satisfied during optimization by creating a potential field that increases as the system approaches constraint boundaries.
- Parameters:
name (
str
) – The name of the barrier.gain (
ndarray
|Array
|float
) – The gain for the barrier function.obj_name (
str
) – The name of the object (body, geometry, or site) to which this barrier applies.obj_type (
mjtObj
) – The type of the object (mjOBJ_BODY, mjOBJ_GEOM, or mjOBJ_SITE).gain_fn (
Callable
[[float
],float
] |None
) – A function to compute the gain dynamically.safe_displacement_gain (
float
) – The gain for computing safe displacements.mask (
Sequence
[int
] |None
) – A sequence of integers to mask certain dimensions.
- property obj_name: str
Get the name of the object to which this barrier applies.
- Returns:
The name of the object.
- property obj_id: int
Get the ID of the body to which this barrier applies.
- Returns:
The ID of the body.
- Raises:
ValueError – If the body ID is not available.
- property obj_type: mjtObj
Get the type of the object associated with the barrier..
- Returns:
The MuJoCo object type (mjOBJ_BODY, mjOBJ_GEOM, or mjOBJ_SITE).
- update_model(model)
Update the model and retrieve the object ID.
- Parameters:
model (
Model
) – The MuJoCo model.- Returns:
The updated model.
- Raises:
ValueError – If the object with the specified name is not found.
Body Position Barrier
Enforces position constraints on specific bodies, geometries, or sites, useful for defining workspace limits.
- class JaxPositionBarrier(dim, model, vector_gain, gain_fn, mask_idxs, safe_displacement_gain, obj_id, obj_type, p_min, p_max, limit_type_mask_idxs)
A JAX implementation of a position barrier function for a specific object (body, geometry, or site).
This class extends JaxObjBarrier to provide position-specific barrier functions.
The position barrier enforces that an object’s position remains within specified bounds:
\[\begin{split}h_{min}(q) &= p(q) - p_{min} \geq 0 \\ h_{max}(q) &= p_{max} - p(q) \geq 0\end{split}\]- where:
\(p(q)\) is the position of the object
\(p_{min}\) is the minimum allowed position
\(p_{max}\) is the maximum allowed position
The barrier can enforce minimum bounds, maximum bounds, or both, depending on the limit_type.
- class PositionBarrier(name, gain, obj_name, obj_type=<mjtObj.mjOBJ_BODY: 1>, p_min=None, p_max=None, limit_type='both', gain_fn=None, safe_displacement_gain=0, mask=None)
A position barrier class that wraps the JAX position barrier implementation.
This class provides a high-level interface for position-specific barrier functions.
Position barriers create virtual boundaries in the workspace, ensuring that parts of the robot remain within specified regions. They can be used to: - Constrain an end effector to a specific workspace - Keep the robot away from obstacles - Enforce operational space constraints
The barrier is formulated as:
\[\begin{split}h(q) = \begin{cases} p(q) - p_{min} & \text{for minimum limits} \\ p_{max} - p(q) & \text{for maximum limits} \\ [p(q) - p_{min}, p_{max} - p(q)] & \text{for both limits} \end{cases}\end{split}\]- Parameters:
p_min (ArrayOrFloat | None) – The minimum allowed position.
p_max (ArrayOrFloat | None) – The maximum allowed position.
limit_type (str) – The type of limit to apply (‘min’, ‘max’, or ‘both’).
- JaxComponentType
alias of
JaxPositionBarrier
- property limit_type: :class:`mjinx.typing.PositionLimitType`
Get the type of limit applied to the position barrier.
- Returns:
The limit type.
- update_p_min(p_min)
Update the minimum allowed position.
- Parameters:
p_min (
mjinx.typing.ArrayOrFloat
) – The new minimum position.- Raises:
ValueError – If the dimension of p_min is incorrect.
- update_p_max(p_max)
Update the maximum allowed position.
- Parameters:
p_max (
mjinx.typing.ArrayOrFloat
) – The new maximum position.- Raises:
ValueError – If the dimension of p_max is incorrect.
Self Collision Barrier
Prevents different parts of the robot from colliding with each other, essential for complex manipulators.
- class JaxSelfCollisionBarrier(dim, model, vector_gain, gain_fn, mask_idxs, safe_displacement_gain, d_min_vec, collision_pairs, n_closest_pairs)
A JAX implementation of a self-collision barrier function.
This class extends JaxBarrier to provide barrier functions that prevent self-collisions between different parts of the robot. It identifies potential collision pairs and computes barrier values based on their distances.
The self-collision barrier enforces minimum distances between collision pairs:
\[h(q) = d(q) - d_{min} \geq 0\]- where:
\(d(q)\) is the minimum distance between collision geometries
\(d_{min}\) is the minimum allowed distance threshold
The barrier activates when geometries come closer than the specified threshold, creating a repulsive effect that prevents collisions while maintaining smoothness for optimization.
- Parameters:
collision_pairs (
list
[mjinx.typing.CollisionPair
]) – A list of geometry pairs to check for collisions.min_distance – The minimum allowed distance between geometries.
n_closest_pairs (
int
) – The number of closest collision pairs to consider.
- compute_jacobian(data)
Compute the Jacobian of the barrier function with respect to joint positions.
For collision barriers, the Jacobian captures how changes in joint positions affect the distances between collision pairs:
\[J = \frac{\partial d(q)}{\partial q}\]This is computed analytically using the contact normals and point Jacobians:
\[J = n^T (J_{p2} - J_{p1})\]- where:
\(n\) is the contact normal
\(J_{p1}\) and \(J_{p2}\) are the Jacobians of the contact points
- Parameters:
data (
Data
) – The MuJoCo simulation data containing the current state of the system.- Return type:
- Returns:
The Jacobian matrix of shape (n_collision_pairs, n_joints) where each entry (i,j) represents how the i-th collision distance changes with respect to the j-th joint position.
- class SelfCollisionBarrier(name, gain, gain_fn=None, safe_displacement_gain=0, d_min=0, collision_bodies=(), excluded_collisions=(), n_closest_pairs=-1)
A self-collision barrier class that wraps the JAX self-collision barrier implementation.
This class provides a high-level interface for self-collision barrier functions.
- Parameters:
name (
str
) – The name of the barrier.gain (
mjinx.typing.ArrayOrFloat
) – The gain for the barrier function.gain_fn (
Callable
[[float
],float
] |None
) – A function to compute the gain dynamically.safe_displacement_gain (
float
) – The gain for computing safe displacements. Defaults to identity functiond_min (
float
) – The minimum allowed distance between collision pairs. Defaults to zero.collision_bodies (
Sequence
[mjinx.typing.CollisionBody
]) – A sequence of bodies to check for collisions. Defaults to zero.excluded_collisions (
Sequence
[tuple
[mjinx.typing.CollisionBody
,mjinx.typing.CollisionBody
]]) – A sequence of body pairs to exclude from collision checking. Defaults to no excluded pairs.n_closest_pairs (
int
) – amount of closest pairs to consider. Defaults to all pairs considered.
- JaxComponentType
alias of
JaxSelfCollisionBarrier
- validate_body_pair(body1_id, body2_id)
Validate if a pair of bodies should be considered for collision checking.
- Parameters:
body1_id (
int
) – The ID of the first body.body2_id (
int
) – The ID of the second body.
- Return type:
bool
- Returns:
True if the pair is valid for collision checking, False otherwise.
- body2id(body)
Convert a body identifier to its corresponding ID in the model.
- Parameters:
body (
mjinx.typing.CollisionBody
) – The body identifier (either an integer ID or a string name).- Returns:
The integer ID of the body.
- Raises:
ValueError – If the body identifier is invalid.
- update_model(model)
Update the model and generate collision pairs.
- Parameters:
model (
Model
) – The MuJoCo model.