robots_pymujoco_sim
Robot interfaces for synchronous Python MuJoCo scenes.
This module provides RobotBlockSet robot backends built on scene_pymujoco_sim, including the generic synchronous PyMuJoCo robot interface, concrete robot wrappers, and an internal joint-control variant.
- class robotblockset.mujoco.robots_pymujoco_sim.robot_pymujoco(robot_name: str, scene: mujoco_scene = None, tsamp: float = 0.0, **kwargs: Any)[source]
Bases:
robotSynchronous PyMuJoCo-backed robot interface operating on a
mujoco_scene.- Attributes:
scene (
mujoco_scene) – MuJoCo scene object that owns the model and data.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 robot interface backed by a MuJoCo scene.
- Parameters:
robot_name (str) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.tsamp (float, optional) – Requested control sampling period in seconds.
**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,
"auto"to use model-based names, or"gen"to generate names from robot_name.- ActuatorNameslist[str] or str, optional
Explicit actuator names, or
"auto"to use model-based names.- FlangeNamestr, optional
Name of the flange or end-effector body/site.
- TCPNamestr, optional
Name of the tool center point body/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.
- Returns:
This constructor initializes the synchronous PyMuJoCo robot interface in place.
- Return type:
None
- __init__(robot_name: str, scene: mujoco_scene = None, tsamp: float = 0.0, **kwargs: Any) None[source]
Create a robot interface backed by a MuJoCo scene.
- Parameters:
robot_name (str) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.tsamp (float, optional) – Requested control sampling period in seconds.
**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,
"auto"to use model-based names, or"gen"to generate names from robot_name.- ActuatorNameslist[str] or str, optional
Explicit actuator names, or
"auto"to use model-based names.- FlangeNamestr, optional
Name of the flange or end-effector body/site.
- TCPNamestr, optional
Name of the tool center point body/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.
- Returns:
This constructor initializes the synchronous PyMuJoCo robot interface in place.
- Return type:
None
- 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.
- property t: float
Get the elapsed time since the robot was initiated.
- Returns:
Time difference in seconds.
- Return type:
float
- property c: ndarray
Coriolis, centrifugal, gravitational joint torques
- Returns:
Joint force/torque bias (gravity, …).
- Return type:
JointTorqueType
- property H: ndarray
Inertia matrix H(q) in joint space.
- Returns:
Symmetric inertia matrix in joint space.
- Return type:
np.ndarray
- property M: ndarray
Inertia matrix H(q) in task space.
- Returns:
Symmetric inertia matrix in task space.
- Return type:
np.ndarray
- simtime() float[source]
Returns the current simulation timefrom MuJoCO simulator.
- Returns:
The current simulation time in seconds since an arbitrary point (see ResetTime).
- Return type:
float
- GetState() None[source]
Update robot state from MuJoCo data buffers.
Notes
Joint, Cartesian, force-torque, and object-following state are updated from the current scene buffers.
- isActive() bool[source]
Check whether the simulator is running.
- Returns:
Trueif the scene is not paused.- 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.
- 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) after commanding the robot to move.
- 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 advances the synchronous simulator for the requested wait time.
- SetStrategy(strategy: str) None[source]
Set the control strategy.
- Parameters:
strategy (str) – Requested control strategy.
Notes
The synchronous PyMuJoCo 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(ide: Sequence[int]) ndarray[source]
Return joint positions for auxiliary joints by index.
- Parameters:
ide (Sequence[int]) – Joint-position indices to read.
- Returns:
Joint positions for the selected indices.
- Return type:
JointConfigurationType
- GetSensor(ide: str | int = None) ndarray[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 or full sensor data.
- Return type:
np.ndarray
- 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
Note
When mocap body names are used, mocap bodies have to be 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 (str | int) – Mocap body name or id.
out (str, optional) – Output pose format.
- Returns:
Mocap body pose in the requested format, or
Noneif the mocap body could not be resolved.- Return type:
Pose3DType | HomogeneousMatrixType | Vector3DType | RotationMatrixType | None
- GetObjectData(ide: str | int) Any[source]
Return raw MuJoCo body data for a body name or id.
- Parameters:
ide (str | int) – Body name or id.
- Returns:
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, or geom in the requested format.
- Parameters:
typ (str) – Object type; one of
"body","site", or"geom".ide (str | int) – Object name or id.
out (str, optional) – Output pose format.
- Returns:
Object pose in the requested format, or
Noneiftypis not supported.- Return type:
Pose3DType | HomogeneousMatrixType | Vector3DType | RotationMatrixType | None
- 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.
- Parameters:
ide (str | int) – Body name or id.
x (Pose3DType | HomogeneousMatrixType | RotationMatrixType | Vector3DType | QuaternionType | ArrayLike) – Body pose, position, orientation, or homogeneous transform.
- Raises:
ValueError – If the pose shape is not supported.
- SetEquality(ide: str | int, val: int | bool) None[source]
Set an equality constraint activation flag.
- Parameters:
ide (str | int) – Equality constraint name or id.
val (int | bool) – Activation flag value.
- SetBasePlatform(platform: Any, x: ndarray | None = None) None[source]
Attach or detach a base platform.
- Parameters:
platform (Any) – Platform object to attach, or
Noneto detach the current platform.x (Pose3DType | HomogeneousMatrixType | RotationMatrixType | Vector3DType, optional) – Optional platform pose.
- class robotblockset.mujoco.robots_pymujoco_sim.panda(robot_name: str = 'panda', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,panda_specSynchronous PyMuJoCo 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.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'panda', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a Panda robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.fr3(robot_name: str = 'fr3', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,fr3_specSynchronous PyMuJoCo 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.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'fr3', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create an FR3 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.lwr(robot_name: str = 'LWR', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,lwr_specSynchronous PyMuJoCo robot wrapper for the KUKA LWR manipulator.
Create an LWR robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'LWR', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create an LWR robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.iiwa(robot_name: str = 'iiwa14', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,iiwa_specSynchronous PyMuJoCo robot wrapper for the KUKA iiwa manipulator.
Create a KUKA iiwa robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'iiwa14', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a KUKA iiwa robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.ur10(robot_name: str = 'ur10', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,ur10_specSynchronous PyMuJoCo robot wrapper for the Universal Robots UR10 manipulator.
Create a UR10 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'ur10', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a UR10 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.ur10e(robot_name: str = 'ur10e', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,ur10e_specSynchronous PyMuJoCo robot wrapper for the Universal Robots UR10e manipulator.
Create a UR10e robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'ur10e', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a UR10e robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.ur5(robot_name: str = 'ur5', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,ur5_specSynchronous PyMuJoCo robot wrapper for the Universal Robots UR5 manipulator.
Create a UR5 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'ur5', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a UR5 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.ur5e(robot_name: str = 'ur5e', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,ur5e_specSynchronous PyMuJoCo robot wrapper for the Universal Robots UR5e manipulator.
Create a UR5e robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'ur5e', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a UR5e robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.crx20(robot_name: str = 'CRX20', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,crx20_specSynchronous PyMuJoCo robot wrapper for the FANUC CRX-20 manipulator.
Create a CRX20 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'CRX20', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a CRX20 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.hc20(robot_name: str = 'hc20', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujoco,hc20_specSynchronous PyMuJoCo robot wrapper for the Yaskawa HC20 manipulator.
Create an HC20 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'hc20', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create an HC20 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.z1(robot_name: str = 'z1', **kwargs: Any)[source]
Bases:
robot_pymujoco,z1_specSynchronous PyMuJoCo robot wrapper for the Unitree Z1 arm.
Create a Z1 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'z1', **kwargs: Any) None[source]
Create a Z1 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.b2(robot_name: str = 'b2', **kwargs: Any)[source]
Bases:
robot_pymujoco,b2_specSynchronous PyMuJoCo robot wrapper for the Unitree B2 platform-arm system.
Create a B2 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- __init__(robot_name: str = 'b2', **kwargs: Any) None[source]
Create a B2 robot in MuJoCo.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
**kwargs (Any) – Additional keyword arguments passed to robot_pymujoco, including optional joint, actuator, flange, TCP, and sensor names.
- class robotblockset.mujoco.robots_pymujoco_sim.robot_pymujoco_joint_control(robot_name: str = 'Panda', scene: mujoco_scene | None = None, **kwargs: Any)[source]
Bases:
robot_pymujocoSynchronous PyMuJoCo robot interface with internal joint-space impedance control.
- Attributes:
control_target_q (np.ndarray) – Desired joint positions for the internal controller.
control_target_qdot (np.ndarray) – Desired joint velocities for the internal controller.
control_target_trq (np.ndarray) – Desired feed-forward torques for the internal controller.
control_Kp (np.ndarray) – Joint proportional gains.
control_Kd (np.ndarray) – Joint derivative gains.
control_Kg (float) – Gravity-compensation scaling factor.
control_use_H (bool) – Indicates whether the joint-space inertia matrix is used in control.
control_e (np.ndarray) – Current joint-position error.
Create a MuJoCo robot with internal joint impedance control.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to
robot_pymujoco.
- __init__(robot_name: str = 'Panda', scene: mujoco_scene | None = None, **kwargs: Any) None[source]
Create a MuJoCo robot with internal joint impedance control.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.**kwargs (Any) – Additional keyword arguments passed to
robot_pymujoco.
- GoTo_q(q: ndarray, qdot: ndarray | None = None, trq: ndarray | None = None, wait: float | None = None, **kwargs: Any) int[source]
Update internal joint-control targets and wait.
- Parameters:
q (JointConfigurationType) – Desired joint positions.
qdot (JointVelocityType, optional) – Desired joint velocities.
trq (JointTorqueType, optional) – Desired feed-forward joint torques.
wait (float, optional) – Synchronization time after the target update.
- Returns:
Motion result code.
- Return type:
int
Notes
The method updates the internal joint-impedance targets instead of writing actuator commands directly.
- joint_impedance_control(model: mujoco.MjModel, data: mujoco.MjData) None[source]
Perform joint impedance control and write actuator torques.
- Parameters:
model (mujoco.MjModel) – MuJoCo model object.
data (mujoco.MjData) – MuJoCo data object holding the current simulator state.
Notes
The controller is a PD controller with an additional feed-forward term based on MuJoCo joint-bias torques.
- class robotblockset.mujoco.robots_pymujoco_sim.panda_joint_control(robot_name: str = 'Panda', scene: mujoco_scene | None = None, ActuatorNames: List[str] = ['Panda_mot_joint1', 'Panda_mot_joint2', 'Panda_mot_joint3', 'Panda_mot_joint4', 'Panda_mot_joint5', 'Panda_mot_joint6', 'Panda_mot_joint7'], **kwargs: Any)[source]
Bases:
robot_pymujoco_joint_control,panda_specSynchronous PyMuJoCo Panda robot with internal joint-space impedance control.
- Attributes:
All attributes from :class:`robot_pymujoco_joint_control` and
:class:`panda_spec`.
Create a Panda robot with internal joint impedance control.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.ActuatorNames (list[str], optional) – Explicit actuator names for torque control.
**kwargs (Any) – Additional keyword arguments passed to
robot_pymujoco_joint_control.
- __init__(robot_name: str = 'Panda', scene: mujoco_scene | None = None, ActuatorNames: List[str] = ['Panda_mot_joint1', 'Panda_mot_joint2', 'Panda_mot_joint3', 'Panda_mot_joint4', 'Panda_mot_joint5', 'Panda_mot_joint6', 'Panda_mot_joint7'], **kwargs: Any) None[source]
Create a Panda robot with internal joint impedance control.
- Parameters:
robot_name (str, optional) – Base name of the robot model in MuJoCo.
scene (
mujoco_scene, optional) – Scene instance that owns the MuJoCo model and data.ActuatorNames (list[str], optional) – Explicit actuator names for torque control.
**kwargs (Any) – Additional keyword arguments passed to
robot_pymujoco_joint_control.
Classes
|
Synchronous PyMuJoCo robot wrapper for the Unitree B2 platform-arm system. |
|
Synchronous PyMuJoCo robot wrapper for the FANUC CRX-20 manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Franka Research 3 manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Yaskawa HC20 manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the KUKA iiwa manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the KUKA LWR manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Franka Panda manipulator. |
|
Synchronous PyMuJoCo Panda robot with internal joint-space impedance control. |
|
Synchronous PyMuJoCo-backed robot interface operating on a |
|
Synchronous PyMuJoCo robot interface with internal joint-space impedance control. |
|
Synchronous PyMuJoCo robot wrapper for the Universal Robots UR10 manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Universal Robots UR10e manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Universal Robots UR5 manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Universal Robots UR5e manipulator. |
|
Synchronous PyMuJoCo robot wrapper for the Unitree Z1 arm. |