robots_mujoco
Robot interfaces for the socket-based MuJoCo backend.
This module provides RobotBlockSet robot backends that communicate with an external MuJoCo simulator through mjInterface, together with concrete robot wrappers for supported manipulators and mobile platforms.
- class robotblockset.mujoco.robots_mujoco.robot_mujoco(robot_name: str, scene: mjInterface | None = None, host: str = 'localhost', port: int = 50000, **kwargs: Any)[source]
Bases:
robotMuJoCo-backed robot interface using the socket-based server API.
- Attributes:
scene (mjInterface) – Socket-based MuJoCo interface used to exchange state and commands.
BaseName (str) – Base model name used to derive joint, actuator, and sensor names.
JointNames (list[str]) – Ordered list of robot joint names.
ActuatorNames (list[str]) – Ordered list of actuator names used for joint commands.
MocapNames (list[str]) – Names of MuJoCo mocap bodies associated with the scene.
Create a MuJoCo-backed robot interface.
- Parameters:
robot_name (str) – Base name of the robot 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] or str, optional
Explicit joint names, or
"gen"to generate names from robot_name.- ActuatorNameslist[str], optional
Explicit actuator names.
- FlangeNamestr, optional
Name of the flange or end-effector body.
- TCPNamestr, optional
Name of the tool center point body or site.
- 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 Cartesian position.
- SensorOriNamestr, optional
Sensor name used to read Cartesian orientation.
- SensorLinVelNamestr, optional
Sensor name used to read Cartesian linear velocity.
- SensorRotVelNamestr, optional
Sensor name used to read Cartesian 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__(robot_name: str, scene: mjInterface | None = None, host: str = 'localhost', port: int = 50000, **kwargs: Any) None[source]
Create a MuJoCo-backed robot interface.
- Parameters:
robot_name (str) – Base name of the robot 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] or str, optional
Explicit joint names, or
"gen"to generate names from robot_name.- ActuatorNameslist[str], optional
Explicit actuator names.
- FlangeNamestr, optional
Name of the flange or end-effector body.
- TCPNamestr, optional
Name of the tool center point body or site.
- 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 Cartesian position.
- SensorOriNamestr, optional
Sensor name used to read Cartesian orientation.
- SensorLinVelNamestr, optional
Sensor name used to read Cartesian linear velocity.
- SensorRotVelNamestr, optional
Sensor name used to read Cartesian 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.
Notes
The method resolves joint, actuator, site, sensor, and mocap handles and then initializes the RobotBlockSet state.
- GetState() None[source]
Update robot state from MuJoCo data buffers.
Notes
Joint, Cartesian, force-torque, and object-following state are updated from the current simulator buffers.
- isReady() bool[source]
Return whether the simulator connection is active.
- Returns:
Trueif the MuJoCo connection is active.- Return type:
bool
- isActive() bool[source]
Check whether the simulator is advancing in time.
- Returns:
Trueif the simulator time is progressing.- Return type:
bool
- Restart(qpos: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, u: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...] | None = None, reset: bool = True, keyframe: int | None = None) None[source]
Restart the simulation.
- Parameters:
qpos (ArrayLike, optional) – Full generalized-position vector to apply after reset.
u (ArrayLike, optional) – Joint command vector to apply after reset.
reset (bool, optional) – If
True, reset the simulator before applying state updates.keyframe (int, optional) – Keyframe index used for simulator reset.
Notes
The method optionally resets the simulator, applies state and control vectors, clears joint velocities, and resets RobotBlockSet timing and targets.
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Update joint positions and wait.
This method sets the commanded joint positions (q), velocities (qdot), and torques (trq), then sends them to the robot and waits for the specified time (wait).
- Parameters:
q (JointConfigurationType) – Desired joint positions (nj,).
qdot (JointVelocityType, optional) – Desired joint velocities (nj,).
trq (JointTorqueType, optional) – Desired joint torques (nj,).
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
Notes
The method sends the joint command to MuJoCo, updates the RobotBlockSet command state, and synchronizes with the requested wait time.
- SetStrategy(strategy: str) None[source]
Set the control strategy.
- Parameters:
strategy (str) – Requested control strategy.
Notes
The socket-based MuJoCo wrapper currently keeps a single joint-position strategy and accepts this method for compatibility.
- SendRobot_u(u: ndarray) None[source]
Send joint commands to MuJoCo actuators.
- Parameters:
u (JointConfigurationType) – Joint command vector.
- SendCtrl(u: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Send a full control vector to the MuJoCo actuators.
- Parameters:
u (ArrayLike) – Full actuator control vector.
- 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 to assign.
- GetAuxJointPos(idx: Sequence[int]) ndarray | None[source]
Return joint positions for auxiliary joints by index.
- Parameters:
idx (Sequence[int]) – Joint-position indices to read.
- Returns:
Joint positions for the selected indices, if available.
- Return type:
np.ndarray | None
- GetSensor(ide: str | int = None) ndarray | None[source]
Read sensor data by name or id, or return the full sensor array.
- Parameters:
ide (str | int, optional) – Optional sensor name or id.
- Returns:
Selected sensor data, full sensor data, or
Noneif the sensor could not be resolved.- Return type:
np.ndarray | None
- GetContacts(ide: str | int = None) ndarray | None[source]
Return contact forces for a geom or for all contacts.
- Parameters:
ide (str | int, optional) – Optional geom name or id.
- Returns:
Contact forces in world coordinates, or
Noneif no contacts are present.- Return type:
np.ndarray | None
- SetRobotPose(x: ndarray) None[source]
Set the robot base pose.
- Parameters:
x (Union[Pose3DType, HomogeneousMatrixType]) – The pose of the base (7,) or (4, 4).
- Return type:
None
- Raises:
ValueError – If the base pose shape is not recognized.
- SetMocapPose(ide: str | int, x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Set pose of a mocap body
- Parameters:
ide (Union[str, int]) – mocap body name or id
x (Union[Pose3DType, HomogeneousMatrixType, RotationMatrixType, Vector3DType, QuaternionType, ArrayLike]) – mocap pose
- Raises:
ValueError – Wrong pose shape
- GetMocapPose(ide: str | int, out: str = 'x') ndarray | None[source]
Return mocap body pose in the requested output format.
- GetObjectPose(typ: str, ide: str | int, out: str = 'x') ndarray | None[source]
Return the pose of a body/site/geom in the requested format.
- SetObjectPose(ide: str | int, x: ndarray | List[float] | List[int] | Tuple[float, ...] | Tuple[int, ...]) None[source]
Set a MuJoCo body pose from a spatial representation.
- SetEquality(ide: str | int, val: int | bool) None[source]
Set an equality constraint activation flag.
- SetBasePlatform(platform: Any, x: ndarray | None = None) None[source]
Attach or detach a base platform.
Attach or detach a base platform and optionally set its pose.
- class robotblockset.mujoco.robots_mujoco.panda(robot_name: str = 'panda', **kwargs: Any)[source]
Bases:
robot_mujoco,panda_specMuJoCo robot wrapper for the Franka Panda manipulator.
Create a Panda robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_mujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'panda', **kwargs: Any) None[source]
Create a Panda robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_mujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_mujoco.fr3(robot_name: str = 'fr3', **kwargs: Any)[source]
Bases:
robot_mujoco,fr3_specMuJoCo robot wrapper for the Franka Research 3 manipulator.
Create an FR3 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_mujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'fr3', **kwargs: Any) None[source]
Create an FR3 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_mujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_mujoco.lwr(robot_name: str = 'LWR', **kwargs: Any)[source]
Bases:
robot_mujoco,lwr_specMuJoCo robot wrapper for the KUKA LWR manipulator.
Create an LWR robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.iiwa(robot_name: str = 'iiwa14', **kwargs: Any)[source]
Bases:
robot_mujoco,iiwa_specMuJoCo robot wrapper for the KUKA iiwa manipulator.
Create a KUKA iiwa robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.ur10(robot_name: str = 'ur10', **kwargs: Any)[source]
Bases:
robot_mujoco,ur10_specMuJoCo robot wrapper for the Universal Robots UR10 manipulator.
Create a UR10 robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.ur10e(robot_name: str = 'ur10e', **kwargs: Any)[source]
Bases:
robot_mujoco,ur10e_specMuJoCo robot wrapper for the Universal Robots UR10e manipulator.
Create a UR10e robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.ur5(robot_name: str = 'ur5', **kwargs: Any)[source]
Bases:
robot_mujoco,ur5_specMuJoCo robot wrapper for the Universal Robots UR5 manipulator.
Create a UR5 robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.ur5e(robot_name: str = 'ur5e', **kwargs: Any)[source]
Bases:
robot_mujoco,ur5e_specMuJoCo robot wrapper for the Universal Robots UR5e manipulator.
Create a UR5e robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.crx20(robot_name: str = 'CRX20', **kwargs: Any)[source]
Bases:
robot_mujoco,crx20_specMuJoCo robot wrapper for the FANUC CRX-20 collaborative manipulator.
Create a CRX20 robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.hc20(robot_name: str = 'hc20', **kwargs: Any)[source]
Bases:
robot_mujoco,hc20_specMuJoCo robot wrapper for the Yaskawa HC20 manipulator.
Create an HC20 robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.z1(robot_name: str = 'z1', **kwargs: Any)[source]
Bases:
robot_mujoco,z1_specMuJoCo robot wrapper for the Unitree Z1 arm.
Create an Z1 robot in MuJoCo.
- class robotblockset.mujoco.robots_mujoco.b2(robot_name: str = 'b2', **kwargs: Any)[source]
Bases:
robot_mujoco,b2_specMuJoCo robot wrapper for the Unitree B2 platform-arm system.
Create an B2 robot in MuJoCo.
Classes
|
MuJoCo robot wrapper for the Unitree B2 platform-arm system. |
|
MuJoCo robot wrapper for the FANUC CRX-20 collaborative manipulator. |
|
MuJoCo robot wrapper for the Franka Research 3 manipulator. |
|
MuJoCo robot wrapper for the Yaskawa HC20 manipulator. |
|
MuJoCo robot wrapper for the KUKA iiwa manipulator. |
|
MuJoCo robot wrapper for the KUKA LWR manipulator. |
|
MuJoCo robot wrapper for the Franka Panda manipulator. |
|
MuJoCo-backed robot interface using the socket-based server API. |
|
MuJoCo robot wrapper for the Universal Robots UR10 manipulator. |
|
MuJoCo robot wrapper for the Universal Robots UR10e manipulator. |
|
MuJoCo robot wrapper for the Universal Robots UR5 manipulator. |
|
MuJoCo robot wrapper for the Universal Robots UR5e manipulator. |
|
MuJoCo robot wrapper for the Unitree Z1 arm. |