platforms_mujoco
MuJoCo Platforms Module.
This module provides platform implementations for the MuJoCo simulator, mirroring the platform interface in robotblockset.platforms.
- class robotblockset.mujoco.platforms_mujoco.platform_mujoco(platform_name: str, scene: mjInterface | None = None, host: str = 'localhost', port: int = 50000, **kwargs: Any)[source]
Bases:
platformMuJoCo-backed mobile platform interface using the socket-based server API.
Initialize a MuJoCo platform interface.
- Parameters:
platform_name (str) – Base name of the platform model in MuJoCo.
scene (mjInterface, optional) – Existing MuJoCo interface instance. If None, a new connection is created.
host (str, optional) – Hostname of the MuJoCo simulator.
port (int, optional) – Port of the MuJoCo simulator.
**kwargs (Any) – Additional keyword arguments.
Notes
- When constrructing objects of this class, the following keyword arguments are supported for explicit configuration of model element names. If not provided, default names based on the platform name are used.:
- JointNameslist[str], optional
Explicit list of platform joint names.
- ActuatorNameslist[str], optional
Explicit list of actuator names used for velocity commands.
- RobotBaseNamestr, optional
Name of the robot base body used as the platform reference frame.
- SensorJointPosNameslist[str], optional
Sensor names used to read joint positions.
- SensorJointVelNameslist[str], optional
Sensor names used to read joint velocities.
- SensorPosNamestr, optional
Sensor name used to read the platform position.
- SensorOriNamestr, optional
Sensor name used to read the platform orientation.
- SensorLinVelNamestr, optional
Sensor name used to read the platform linear velocity.
- SensorRotVelNamestr, optional
Sensor name used to read the platform angular velocity.
- SensorForceNamestr, optional
Sensor name used to read force measurements.
- SensorTorqueNamestr, optional
Sensor name used to read torque measurements.
- Raises:
Exception – If joint or actuator names do not resolve uniquely in the MJCF model.
- __init__(platform_name: str, scene: mjInterface | None = None, host: str = 'localhost', port: int = 50000, **kwargs: Any) None[source]
Initialize a MuJoCo platform interface.
- Parameters:
platform_name (str) – Base name of the platform model in MuJoCo.
scene (mjInterface, optional) – Existing MuJoCo interface instance. If None, a new connection is created.
host (str, optional) – Hostname of the MuJoCo simulator.
port (int, optional) – Port of the MuJoCo simulator.
**kwargs (Any) – Additional keyword arguments.
Notes
- When constrructing objects of this class, the following keyword arguments are supported for explicit configuration of model element names. If not provided, default names based on the platform name are used.:
- JointNameslist[str], optional
Explicit list of platform joint names.
- ActuatorNameslist[str], optional
Explicit list of actuator names used for velocity commands.
- RobotBaseNamestr, optional
Name of the robot base body used as the platform reference frame.
- SensorJointPosNameslist[str], optional
Sensor names used to read joint positions.
- SensorJointVelNameslist[str], optional
Sensor names used to read joint velocities.
- SensorPosNamestr, optional
Sensor name used to read the platform position.
- SensorOriNamestr, optional
Sensor name used to read the platform orientation.
- SensorLinVelNamestr, optional
Sensor name used to read the platform linear velocity.
- SensorRotVelNamestr, optional
Sensor name used to read the platform angular velocity.
- SensorForceNamestr, optional
Sensor name used to read force measurements.
- SensorTorqueNamestr, optional
Sensor name used to read torque measurements.
- Raises:
Exception – If joint or actuator names do not resolve uniquely in the MJCF model.
- isReady() bool[source]
Check if the platform is connected.
- Returns:
True if the simulator connection is active.
- Return type:
bool
- isActive() bool[source]
Check if the simulator is connected.
- Returns:
True if the simulation is connected.
- Return type:
bool
- Restart(qpos: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, u: ndarray | None = None, reset: bool = True, keyframe: int | None = None) None[source]
Reset the simulation and optionally set joint positions/inputs.
- Parameters:
qpos (ArrayLike, optional) – Joint positions for the platform.
u (JointVelocityType, optional) – Joint velocity command applied after the reset.
reset (bool, optional) – If True, reset the simulation state.
keyframe (int, optional) – Optional keyframe index for reset.
- Set_vel(v: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...], wait: float | None = None) int[source]
Update platform velocities (forward, turn) and wait.
- Parameters:
v (ArrayLike) – Desired planar velocity
[vx, wz].wait (float, optional) – Time to wait (in seconds) to synchronize the command to move. If omitted,
self.tsampis used.
- Returns:
Status of the move (0 for success, non-zero for error).
- Return type:
int
- SendRobot_u(u: ndarray) None[source]
Send joint commands to platform actuators.
- Parameters:
u (JointVelocityType) – Actuator command vector.
- SendCtrl(u: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Send a full control vector to the MuJoCo platform.
- Parameters:
u (ArrayLike) – Full actuator control vector for the MuJoCo scene.
- SendAuxCtrl(idx: Sequence[int], val: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Update selected actuator controls by index.
- Parameters:
idx (Sequence[int]) – Actuator indices to update.
val (ArrayLike) – Control values written to the selected actuators.
- Return type:
None
- GetAuxJointPos(idx: Sequence[int]) ndarray[source]
Return joint positions for auxiliary joints by index.
- Parameters:
idx (Sequence[int]) – Joint indices in the simulator state vector.
- Returns:
Joint positions for the requested indices.
- Return type:
JointConfigurationType
- GetSensor(*ide: str | int) ndarray | None[source]
Read sensor data by name/id or return the full sensor array.
- Parameters:
*ide (str or int) – Optional sensor identifier. When omitted, all sensor samples are returned.
- Returns:
Sensor data slice or full sensor data if no id is provided.
- Return type:
np.ndarray or None
- GetContacts(*ide: str | int) ndarray | None[source]
Return contact forces for a geom or for all contacts.
- Parameters:
*ide (str or int) – Optional geom identifier. When omitted, all contacts are reported.
- Returns:
Contact force array of shape (N,3), or None if no contacts.
- Return type:
np.ndarray or None
- SetMocapPose(ide: str | int, x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Set the pose of a mocap body.
- Parameters:
ide (ObjectIdType) – Mocap body name or index.
x (PoseInputType) – Pose represented as position, quaternion, pose vector, rotation matrix, or homogeneous transform.
- Raises:
ValueError – If
xhas an unsupported shape.
Notes
When mocap body names are used, mocap bodies must be the first bodies in the model.
- GetMocapPose(ide: str | int, out: str = 'x') ndarray | None[source]
Return mocap body pose in the requested output format.
- Parameters:
ide (ObjectIdType) – Mocap body name or id.
out (str, optional) – Output pose format understood by
robotblockset.transformations.map_pose().
- Returns:
Mocap pose in the requested representation, or
Noneif unavailable.- Return type:
PoseOutputType or None
- GetObjectPose(typ: str, ide: str | int, out: str = 'x') ndarray | None[source]
Return the pose of a body/site/geom in the requested format.
- Parameters:
typ (str) – Object type (“body”, “site”, or “geom”).
ide (ObjectIdType) – Object name or id.
out (str, optional) – Output pose format understood by
robotblockset.transformations.map_pose().
- Returns:
Pose of the requested object, or
Nonewhen the object type is unsupported.- Return type:
PoseOutputType or None
- SetObjectPose(ide: str | int, x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Set a body pose from a spatial representation.
- Parameters:
ide (ObjectIdType) – Body name or id.
x (PoseInputType) – Pose represented as position, quaternion, pose vector, rotation matrix, or homogeneous transform.
- Return type:
None
- Raises:
ValueError – If
xhas an unsupported shape.
- SetEquality(ide: str | int, val: int | bool) None[source]
Set an equality constraint activation flag.
- Parameters:
ide (ObjectIdType) – Equality constraint name or id.
val (Union[int, bool]) – Activation flag.
- Return type:
None
- class robotblockset.mujoco.platforms_mujoco.tiagobase(platform_name: str = 'tiagobase', **kwargs: Any)[source]
Bases:
platform_mujoco,tiagobase_specMuJoCo platform wrapper for the PAL Robotics Tiago Base.
Create a TiagoBase platform backed by MuJoCo.
- Parameters:
platform_name (str, optional) – Base name of the platform in the MuJoCo model.
**kwargs (Any) – Additional keyword arguments passed to
platform_mujoco, including optional joint, actuator, base-body, and sensor names.
- __init__(platform_name: str = 'tiagobase', **kwargs: Any) None[source]
Create a TiagoBase platform backed by MuJoCo.
- Parameters:
platform_name (str, optional) – Base name of the platform in the MuJoCo model.
**kwargs (Any) – Additional keyword arguments passed to
platform_mujoco, including optional joint, actuator, base-body, and sensor names.
- class robotblockset.mujoco.platforms_mujoco.mir100(platform_name: str = 'mir', **kwargs: Any)[source]
Bases:
platform_mujoco,mir100_specMuJoCo platform wrapper for the MiR100 mobile base.
Create a MiR100 platform backed by MuJoCo.
- Parameters:
platform_name (str, optional) – Base name of the platform in the MuJoCo model.
**kwargs (Any) – Additional keyword arguments passed to
platform_mujoco, including optional joint, actuator, base-body, and sensor names.
- __init__(platform_name: str = 'mir', **kwargs: Any) None[source]
Create a MiR100 platform backed by MuJoCo.
- Parameters:
platform_name (str, optional) – Base name of the platform in the MuJoCo model.
**kwargs (Any) – Additional keyword arguments passed to
platform_mujoco, including optional joint, actuator, base-body, and sensor names.
Classes
|
MuJoCo platform wrapper for the MiR100 mobile base. |
|
MuJoCo-backed mobile platform interface using the socket-based server API. |
|
MuJoCo platform wrapper for the PAL Robotics Tiago Base. |