Configuration
Configuration space of a robot model.
The Configuration
class encapsulates a MuJoCo
model
and data,
offering easy access to frame transforms and frame Jacobians. A frame refers to a coordinate
system that can be attached to various parts of the robot, such as a body, geom, or site.
- class mink.configuration.Configuration
Encapsulates a model and data for convenient access to kinematic quantities.
This class provides methods to access and update the kinematic quantities of a robot model, such as frame transforms and Jacobians. It performs forward kinematics at every time step, ensuring up-to-date information about the robot’s state.
Key functionalities include:
Running forward kinematics to update the state.
Checking configuration limits.
Computing Jacobians for different frames.
Retrieving frame transforms relative to the world frame.
Integrating velocities to update configurations.
- update(q: ndarray | None = None) None
Run forward kinematics.
- Parameters:
q (ndarray | None) – Optional configuration vector to override internal data.qpos with.
- Return type:
None
- update_from_keyframe(key_name: str) None
Update the configuration from a keyframe.
- Parameters:
key_name (str) – The name of the keyframe.
- Return type:
None
- check_limits(tol: float = 1e-06, safety_break: bool = True) None
Check that the current configuration is within bounds.
- Parameters:
tol (float) – Tolerance in [rad].
safety_break (bool) – If True, stop execution and raise an exception if the current configuration is outside limits. If False, print a warning and continue execution.
- Return type:
None
- get_frame_jacobian(frame_name: str, frame_type: str) ndarray
Compute the Jacobian matrix of a frame velocity.
Denoting our frame by \(B\) and the world frame by \(W\), the Jacobian matrix \({}_B J_{WB}\) is related to the body velocity \({}_B v_{WB}\) by:
\[{}_B v_{WB} = {}_B J_{WB} \dot{q}\]- Parameters:
frame_name (str) – Name of the frame in the MJCF.
frame_type (str) – Type of frame. Can be a geom, a body or a site.
- Returns:
Jacobian \({}_B J_{WB}\) of the frame.
- Return type:
ndarray
- get_transform_frame_to_world(frame_name: str, frame_type: str) SE3
Get the pose of a frame at the current configuration.
- Parameters:
frame_name (str) – Name of the frame in the MJCF.
frame_type (str) – Type of frame. Can be a geom, a body or a site.
- Returns:
The pose of the frame in the world frame.
- Return type:
- get_transform(source_name: str, source_type: str, dest_name: str, dest_type: str) SE3
Get the pose of a frame with respect to another frame at the current configuration.
- Parameters:
source_name (str) – Name of the frame in the MJCF.
source_type (str) – Source type of frame. Can be a geom, a body or a site.
dest_name (str) – Name of the frame to get the pose in.
dest_type (str) – Dest type of frame. Can be a geom, a body or a site.
- Returns:
The pose of source_name in dest_name.
- Return type:
- integrate(velocity: ndarray, dt: float) ndarray
Integrate a velocity starting from the current configuration.
- Parameters:
velocity (ndarray) – The velocity in tangent space.
dt (float) – Integration duration in [s].
- Returns:
The new configuration after integration.
- Return type:
ndarray
- integrate_inplace(velocity: ndarray, dt: float) None
Integrate a velocity and update the current configuration inplace.
- Parameters:
velocity (ndarray) – The velocity in tangent space.
dt (float) – Integration duration in [s].
- Return type:
None
- property q: ndarray
The current configuration vector.
- property nv: int
The dimension of the tangent space.
- property nq: int
The dimension of the configuration space.