mujoco_api
Socket-based client interface to the MuJoCo server backend.
This module defines the low-level communication layer used to exchange data with an external MuJoCo simulation server. It includes command and error constants, lightweight data containers for MuJoCo model and runtime state, and the mjInterface client class used to connect to the server, load models, control simulation execution, and get or set kinematic, dynamic, sensor, and visualization data.
- class robotblockset.mujoco.mujoco_api.mjInfo(nq, nv, na, njnt, nbody, ngeom, nsite, ntendon, nu, neq, nkey, nmocap, nsensor, nsensordata, nmat, ncam, timestep, apirate, sensor_type=None, sensor_datatype=None, sensor_objtype=None, sensor_objid=None, sensor_dim=None, sensor_adr=None, sensor_noise=None, jnt_type=None, jnt_bodyid=None, jnt_qposadr=None, jnt_dofadr=None, jnt_range=None, geom_type=None, geom_bodyid=None, eq_type=None, eq_obj1id=None, eq_obj2id=None, actuator_trntype=None, actuator_trnid=None, actuator_ctrlrange=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjState(nq, nv, na, time, qpos=None, qvel=None, act=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjApplied(nv=0, nbody=0, time=0, qfrc_applied=None, xfrc_applied=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjOneBody(bodyid=0, isfloating=0, time=0, linacc=0, angacc=0, contactforce=0, pos=None, quat=None, linvel=None, angvel=None, force=None, torque=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjMocap(nmocap, time, pos=None, quat=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjDynamics(nv, na, time, qacc=None, actdot=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjSensor(nsensordata, time, sensordata=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjBody(nbody, time, pos=None, mat=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjGeom(ngeom, time, pos=None, mat=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjSite(nsite, time, pos=None, mat=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjTendon(ntendon, time, length=None, velocity=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjActuator(nu, time, length=None, velocity=None, force=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjForce(nv, time, nonconstraint=None, constraint=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjContact(ncon, time, dist=None, pos=None, frame=None, force=None, geom1=None, geom2=None)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjCamera(ncam, time, cam_xpos, cam_xmat, cam_mode, cam_bodyid, cam_targetbodyid, cam_pos, cam_quat, cam_poscom0, cam_pos0, cam_mat0, cam_fovy, cam_ipd)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjGLCamera(nglcam, time, fixedcamid, type, trackbodyid, lookat, distance, azimuth, elevation, pos, forward, up, frustum_center, frustum_bottom, frustum_top, frustum_near, frustum_far)[source]
Bases:
object
- class robotblockset.mujoco.mujoco_api.mjInterface(host='localhost', port=50000)[source]
Bases:
objectCreation of MuJoCo interface
- onebody = <robotblockset.mujoco.mujoco_api.mjOneBody object>
- mj_get_state() mjState[source]
Read model state
- Returns:
——-
structure mjState –
- nqint
number of data in qpos
- nvint
number of data in qvel
- naint
number of data in act
- timefloat)
simulation time
- qposarray [nq]
generalized positions
- qvelarray [nv]
generalized velocities
- actarray [na]
actuator activations
- mj_get_control() mjControl[source]
Read control signals
- Returns:
——–
structure mjControl – nu (int) : number of data in ctrl time (float) : simulation time ctrl[nu] (float): control array
- mj_get_applied() mjApplied[source]
Read applied forces
- Returns:
——–
structure mjApplied – nv (int) : number of data in forces nbody (int) : id of body time (float) : simulation time qfrc[nv] (float): applied generalized forces xfrc[nv] (float): Cartesian F/T applied to body
- mj_get_onebody(bodyid: int) mjOneBody[source]
Read information about one body
- Parameters:
-----------
(int) (bodyid)
- Returns:
——–
structure mjOneBody – bodyid; (int) : body id, provided by user get only: isfloating (int) : 1 if body is floating, 0 otherwise time (float) : simulation time linacc[3] (float): linear acceleration angacc[3] (float): angular acceleration contactforce[3] (float) : net force from all contacts on this body
get for all bodies; set for floating bodies only – pos[3] (float) : position quat[4] (float) : orientation quaternion linvel[3] (float): linear velocity angvel[3] (float): angular velocity
get and set for all bodies – force[3] (float) : Cartesian force applied to body CoM torque[3] (float): Cartesian torque applied to body
- mj_get_mocap() mjMocap[source]
Read mocaps
- Returns:
——–
structure mjMocap – nmocap (int) : number of mocap bodies time (float) : simulation time pos[nmocap][3] (float) : positions quat[nmocap][4] (float): quaternion orientations
- mj_get_dynamics() mjDynamics[source]
Read forward dynamics
- Returns:
——–
structure mjDynamics – nv (int) : number of generalized velocities na (int) : number of actuator activations time (float) : simulation time qacc[nv] (float) : generalized accelerations actdot[na] (float): time-derivatives of actuator activations
- mj_get_sensor() mjSensor[source]
Read sensor data from the simulator.
Use the sensor descriptors available in
mjInfoto decode the returned values.- Returns:
Sensor data structure with:
nsensordata: number of sensor valuestime: simulation timesensordata: sensor data array
- Return type:
- mj_get_body() mjBody[source]
Read body positions
- Returns:
——–
structure mjBody – nbody (int) : number of bodies time (float) : simulation time pos[nbody][3] (float): positions mat[nbody][9] (float): frame orientations
- mj_get_geom() mjGeom[source]
Read geom positions
- Returns:
——–
structure mjGeom – ngeom (int) : number of geoms time (float) : simulation time pos[ngeom][3] (float): positions mat[ngeom][9] (float): frame orientations
- mj_get_site() mjSite[source]
Read site positions
- Returns:
——–
structure mjSite – nsite (int) : number of bodies time (float) : simulation time pos[nsite][3] (float): positions mat[nsite][9] (float): frame orientations
- mj_get_tendon() mjTendon[source]
Read tendons data
- Returns:
——–
structure mjTendon – ntendon (int) : number of tendons time (float) : simulation time length[ntendon] (float) : tendon lengths velocity[ntendon] (float): tendon velocities
- mj_get_actuator() mjActuator[source]
Read tendons data
- Returns:
——–
structure mjTendon – nu (int) : number of actuators time (float) : simulation time length[nu] (float) : actuator lengths velocity[nu] (float): actuator velocities force[nu] (float) : actuator forces
- mj_get_force() mjForce[source]
Read tendons data
- Returns:
——–
structure mjTendon – nv (int) : number of generalized velocities/forces time (float) : simulation time nonconstraint[nv] (float): sum of all non-constraint forces constraint[nv] (float) : constraint forces (including contacts)
- mj_get_contact() mjContact[source]
Read tendons data
- Returns:
——–
structure mjTendon – ncon (int) : number of detected contacts time (float) : simulation time dist[ncon : contact normal distance pos[ncon][3] (float) : contact position in world frame frame[ncon][9] (float): contact frame relative to world frame (0-2: normal) force[ncon][3] (float): contact force in contact frame geom1[ncon] (float) : id of 1st contacting geom geom2[ncon] (float) : id of 2nd contacting geom (force: 1st -> 2nd)
- mj_get_glcamera() mjGLCamera[source]
Read GL camera data
- Returns:
——–
structure mjGLCamera
- mj_set_state(state: mjState)[source]
Set simulator state
- Parameters:
-----------
state (mjState) – structure mjState
- Returns:
——–
int – API return code
- mj_set_control(control: mjControl)[source]
Set control signals
- Parameters:
-----------
control (mjControl) – structure mjControl
- Returns:
——–
int – API return code
- mj_set_applied(applied: mjApplied)[source]
Set applied forces
- Parameters:
-----------
applied (mjApplied) – structure mjApplied
- Returns:
——–
int – API return code
- mj_set_onebody(onebody: mjOneBody)[source]
Set one body data
- Parameters:
-----------
onebody (mjOneBody) – structure mjOneBody
- Returns:
——–
int – API return code
- mj_set_mocap(mocap: mjMocap)[source]
Set mocap positions
- Parameters:
-----------
mocap (mjMocap) – structure mjMocap
- Returns:
——–
int – API return code
- mj_load(model_filename: str = None) int[source]
Show text message in simulator
- Parameters:
-----------
message (string) – message, None: clear currently shown message
- Returns:
——–
int – API return code
- mj_connect()[source]
Connect to Haptix simulator
- Parameters:
-----------
ip (string) – host IP
- Returns:
——–
int – API return code
- mj_result()[source]
Return the last API result code.
- Returns:
Last result code reported by the MuJoCo interface.
- Return type:
str
- mj_connected()[source]
Return the connection status.
- Returns:
1if connected to the simulator, otherwise0.- Return type:
int
- mj_info()[source]
Get static properties of current model
- Returns:
——–
myInfo (structure) – nq (int) : number of generalized positions nv (int) : number of generalized velocities na (int) : number of actuator activations njnt (int) : number of joints nbody (int) : number of bodies ngeom (int) : number of geoms nsite (int) : number of sites ntendon (int) : number of tendons nu (int) : number of actuators/controls neq (int) : number of equality constraints nkey (int) : number of keyframes nmocap (int) : number of mocap bodies nsensor (int) : number of sensors nsensordata (int) : number of elements in sensor data array nmat (int) : number of materials timestep (float) : simulation timestep apirate (float) : API update rate sensor_type[nsensor] (int) : sensor type sensor_datatype[nsensor] (int) : type of sensorized object sensor_objtype[nsensor] (int) : type of sensorized object sensor_objid[nsensor] (int) : id of sensorized object sensor_dim[nsensor] (int) : number of sensor outputs sensor_adr[nsensor] (int) : address in sensor data array sensor_noise[nsensor] (float) : noise standard deviation jnt_type[njnt] (int) : joint type (mjtJoint) jnt_bodyid[njnt] (int) : id of body to which joint belongs jnt_qposadr[njnt] (int) : address of joint position data in qpos jnt_dofadr[njnt] (int) : address of joint velocity data in qvel jnt_range[njnt][2] (float) : joint range (0,0): no limits geom_type[ngeom] (int) : geom type (mjtGeom) geom_bodyid[ngeom] (int) : id of body to which geom is attached eq_type[neq] (int) : equality constraint type (mjtEq) eq_obj1id[neq] (int) : id of constrained object eq_obj2id[neq] (int) : id of 2nd constrained object -1 if not applicable actuator_trntype[nu] (int) : transmission type (mjtTrn) actuator_trnid[nu][2] (int) : transmission target id actuator_ctrlrange[nu][2](float): actuator control range (0,0): no limits
- mj_step() int[source]
Advance simulation if paused, no effect if running
- Returns:
——–
int – API return code
- mj_update(control: mjControl) int[source]
Advance the simulation and refresh sensor data.
The method sends the control command, advances the simulation, and returns the refreshed sensor data structure received from the simulator.
- mj_reset(keyframe: int = None) int[source]
Reset simulation to specified key frame
- Parameters:
-----------
keyframe (int, optional) – key frame; -1: reset to model reference configuration
- Returns:
——–
int – API return code
- mj_equality(eqid: int, state: int) int[source]
Modify state of specified equality constraint
- Parameters:
-----------
eqid (int) – equality id
state (int) – equality constraint, 1: enable, 0: disable
- Returns:
——–
int – API return code
- mj_message(message: str = None) int[source]
Show text message in simulator
- Parameters:
-----------
message (str, optional) – message, None: clear currently shown message
- Returns:
——–
int – API return code
- mj_name2id(typ: str, name: str) int[source]
Return the id of an object with the specified type and name.
Valid object types are
body,geom,site,joint,tendon,sensor,actuator, andequality.- Parameters:
typ (str) – Object type.
name (str) – Object name.
- Returns:
Object id. Returns
-1if not found and-2on error.- Return type:
int
Functions
|
Classes
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
Creation of MuJoCo interface |
|
|
|
|
|
|
|
|
|
|
|