Limits#
Definition#
All kinematic limits derive from the Limit base class.
- class mink.limits.limit.Constraint#
Linear inequality constraint of the form \(G(q) \Delta q \leq h(q)\).
Inactive if G and h are None.
- G: ndarray | None#
Alias for field number 0
- h: ndarray | None#
Alias for field number 1
- property inactive: bool#
Returns True if the constraint is inactive.
- class mink.limits.limit.Limit#
Abstract base class for kinematic limits.
Subclasses must implement the
compute_qp_inequalities()method which takes in the current robot configuration and integration time step and returns an instance ofConstraint.- abstract compute_qp_inequalities(configuration: Configuration, dt: float) Constraint#
Compute limit as linearized QP inequalities of the form:
\[G(q) \Delta q \leq h(q)\]where \(q \in {\cal C}\) is the robot’s configuration and \(\Delta q \in T_q({\cal C})\) is the displacement in the tangent space at \(q\).
- Parameters:
configuration (Configuration) – Robot configuration \(q\).
dt (float) – Integration time step in [s].
- Returns:
Pair \((G, h)\).
- Return type:
Configuration limits#
Joint position limit.
- class mink.limits.configuration_limit.ConfigurationLimit#
Inequality constraint on joint positions in a robot model.
Floating base joints are ignored.
- compute_qp_inequalities(configuration: Configuration, dt: float) Constraint#
Compute the configuration-dependent joint position limits.
The limits are defined as:
\[{q \ominus q_{min}} \leq \Delta q \leq {q_{max} \ominus q}\]where \(q \in {\cal C}\) is the robot’s configuration and \(\Delta q \in T_q({\cal C})\) is the displacement in the tangent space at \(q\). See the Derivations section for more information.
- Parameters:
configuration (Configuration) – Robot configuration \(q\).
dt (float) – Integration timestep in [s].
- Returns:
Pair \((G, h)\) representing the inequality constraint as \(G \Delta q \leq h\), or
Noneif there is no limit.- Return type:
Velocity limits#
Joint velocity limit.
- class mink.limits.velocity_limit.VelocityLimit#
Inequality constraint on joint velocities in a robot model.
Floating base joints are ignored.
- indices#
Tangent indices corresponding to velocity-limited joints. Shape (nb,).
- Type:
numpy.ndarray
- limit#
Maximum allowed velocity magnitude for velocity-limited joints, in [m]/[s] for slide joints and [rad]/[s] for hinge joints. Shape (nb,).
- Type:
numpy.ndarray
- projection_matrix#
Projection from tangent space to subspace with velocity-limited joints. Shape (nb, nv) where nb is the dimension of the velocity-limited subspace and nv is the dimension of the tangent space.
- Type:
numpy.ndarray | None
- compute_qp_inequalities(configuration: Configuration, dt: float) Constraint#
Compute the configuration-dependent joint velocity limits.
The limits are defined as:
\[-v_{\text{max}} \cdot dt \leq \Delta q \leq v_{\text{max}} \cdot dt\]where \(v_{max} \in {\cal T}\) is the robot’s velocity limit vector and \(\Delta q \in T_q({\cal C})\) is the displacement in the tangent space at \(q\). See the Derivations section for more information.
- Parameters:
configuration (Configuration) – Robot configuration \(q\).
dt (float) – Integration timestep in [s].
- Returns:
Pair \((G, h)\) representing the inequality constraint as \(G \Delta q \leq h\), or
Noneif there is no limit. G has shape (2nb, nv) and h has shape (2nb,).- Return type:
Collision avoidance limits#
Collision avoidance limit.
- mink.limits.collision_avoidance_limit.compute_contact_normal_jacobian(model: MjModel, data: MjData, geom1_id: int, geom2_id: int, fromto: ndarray, normal: ndarray, jac1: ndarray, jac2: ndarray) ndarray#
Compute the contact normal Jacobian between two geoms.
- Parameters:
model (MjModel)
data (MjData)
geom1_id (int)
geom2_id (int)
fromto (ndarray)
normal (ndarray)
jac1 (ndarray)
jac2 (ndarray)
- Return type:
ndarray
- class mink.limits.collision_avoidance_limit.CollisionAvoidanceLimit#
Normal velocity limit between geom pairs.
- model#
MuJoCo model.
- geom_pairs#
Set of collision pairs in which to perform active collision avoidance. A collision pair is defined as a pair of geom groups. A geom group is a set of geom names. For each geom pair, the solver will attempt to compute joint velocities that avoid collisions between every geom in the first geom group with every geom in the second geom group. Self collision is achieved by adding a collision pair with the same geom group in both pair fields.
- gain#
Gain factor in (0, 1] that determines how fast the geoms are allowed to move towards each other at each iteration. Smaller values are safer but may make the geoms move slower towards each other.
- minimum_distance_from_collisions#
The minimum distance to leave between any two geoms. A negative distance allows the geoms to penetrate by the specified amount.
- collision_detection_distance#
The distance between two geoms at which the active collision avoidance limit will be active. A large value will cause collisions to be detected early, but may incur high computational cost. A negative value will cause the geoms to be detected only after they penetrate by the specified amount.
- bound_relaxation#
An offset on the upper bound of each collision avoidance constraint.
- compute_qp_inequalities(configuration: Configuration, dt: float) Constraint#
Compute limit as linearized QP inequalities of the form:
\[G(q) \Delta q \leq h(q)\]where \(q \in {\cal C}\) is the robot’s configuration and \(\Delta q \in T_q({\cal C})\) is the displacement in the tangent space at \(q\).
- Parameters:
configuration (Configuration) – Robot configuration \(q\).
dt (float) – Integration time step in [s].
- Returns:
Pair \((G, h)\).
- Return type: