platforms_pymujoco

PyMuJoCo Platforms Module.

This module provides platform implementations for the Python MuJoCo simulator, mirroring the platform interface in robotblockset.platforms.

class robotblockset.mujoco.platforms_pymujoco.platform_pymujoco(platform_name: str, scene: mujoco_scene | None = None, **kwargs: Any)[source]

Bases: platform

PyMuJoCo-backed mobile platform interface operating on a mujoco_scene.

Initialize a PyMuJoCo platform interface.

Parameters:
  • platform_name (str) – Base name of the platform model in MuJoCo.

  • scene (mujoco_scene, optional) – MuJoCo scene instance to control. Must be provided.

  • **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: mujoco_scene | None = None, **kwargs: Any) None[source]

Initialize a PyMuJoCo platform interface.

Parameters:
  • platform_name (str) – Base name of the platform model in MuJoCo.

  • scene (mujoco_scene, optional) – MuJoCo scene instance to control. Must be provided.

  • **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() None[source]

Initialize MuJoCo handles and cached sensor indices.

Return type:

None

simtime() float[source]

Return the current simulation time from the MuJoCo simulator.

Returns:

The current simulation time in seconds since an arbitrary point (see ResetTime).

Return type:

float

GetState() None[source]

Update platform state from MuJoCo data buffers.

Return type:

None

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.

Stop() None[source]

Stop platform motion and clear velocity commands.

Return type:

None

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.tsamp is 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(ide: Sequence[int]) ndarray[source]

Return joint positions for auxiliary joints by index.

Parameters:

ide (Sequence[int]) – Joint indices in self.data.qpos.

Returns:

Joint positions for the requested indices.

Return type:

JointConfigurationType

GetSensor(*ide: str | int) ndarray[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

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 x has 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:
Returns:

Mocap pose in the requested representation, or None if unavailable.

Return type:

PoseOutputType or None

GetObjectData(ide: str | int) Any[source]

Return raw MuJoCo body data for a body name/id.

Parameters:

ide (ObjectIdType) – Body name or id.

Returns:

Raw MuJoCo body data object.

Return type:

Any

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 None when 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 x has 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_pymujoco.tiagobase(platform_name: str = 'tiagobase', scene: mujoco_scene | None = None, **kwargs: Any)[source]

Bases: platform_pymujoco, tiagobase_spec

PyMuJoCo platform wrapper for the PAL Robotics Tiago Base.

Create a TiagoBase platform backed by PyMuJoCo.

Parameters:
  • platform_name (str, optional) – Base name of the platform in the MuJoCo model.

  • scene (mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.

  • **kwargs (Any) – Additional keyword arguments passed to platform_pymujoco, including optional joint, actuator, base-body, and sensor names.

__init__(platform_name: str = 'tiagobase', scene: mujoco_scene | None = None, **kwargs: Any) None[source]

Create a TiagoBase platform backed by PyMuJoCo.

Parameters:
  • platform_name (str, optional) – Base name of the platform in the MuJoCo model.

  • scene (mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.

  • **kwargs (Any) – Additional keyword arguments passed to platform_pymujoco, including optional joint, actuator, base-body, and sensor names.

class robotblockset.mujoco.platforms_pymujoco.mir100_pymujoco(platform_name: str = 'mir', scene: mujoco_scene | None = None, **kwargs: Any)[source]

Bases: platform_pymujoco, mir100_spec

PyMuJoCo platform wrapper for the MiR100 mobile base.

Create a MiR100 platform backed by PyMuJoCo.

Parameters:
  • platform_name (str, optional) – Base name of the platform in the MuJoCo model.

  • scene (mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.

  • **kwargs (Any) – Additional keyword arguments passed to platform_pymujoco, including optional joint, actuator, base-body, and sensor names.

__init__(platform_name: str = 'mir', scene: mujoco_scene | None = None, **kwargs: Any) None[source]

Create a MiR100 platform backed by PyMuJoCo.

Parameters:
  • platform_name (str, optional) – Base name of the platform in the MuJoCo model.

  • scene (mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.

  • **kwargs (Any) – Additional keyword arguments passed to platform_pymujoco, including optional joint, actuator, base-body, and sensor names.

Classes

mir100_pymujoco([platform_name, scene])

PyMuJoCo platform wrapper for the MiR100 mobile base.

platform_pymujoco(platform_name[, scene])

PyMuJoCo-backed mobile platform interface operating on a mujoco_scene.

tiagobase([platform_name, scene])

PyMuJoCo platform wrapper for the PAL Robotics Tiago Base.