Home MuJoCo Basics
Post
Cancel

MuJoCo Basics

Overview of mjModel and mjData

  • mjModel: Holds static information about the simulation model (e.g., geometry, joint limits, sensor definitions). Think of it as a blueprint for the robot/environment.
  • mjData: Holds dynamic state information for the simulation (e.g., joint positions, velocities, applied forces). It tracks how the simulation evolves over time.

mjModel

FunctionDescriptionExample Usage
mj_name2idConverts a name (e.g., of a joint, body, or sensor) to its corresponding ID.joint_id = mj_name2id(model, mjOBJ_JOINT, "joint1")
mj_id2nameConverts an ID to its corresponding name.joint_name = mj_id2name(model, mjOBJ_JOINT, joint_id)
mj_getGeomIdRetrieves the ID of a geometry by name.geom_id = mj_getGeomId(model, "geom1")
mj_getBodyIdRetrieves the ID of a body by name.body_id = mj_getBodyId(model, "robot_body")
mj_getJointIdRetrieves the ID of a joint by name.joint_id = mj_getJointId(model, "joint1")
mj_getSiteIdRetrieves the ID of a site by name.site_id = mj_getSiteId(model, "end_effector_site")
mj_printModelDumps the entire model structure to a file.mj_printModel(model, "model.txt")
mj_setGeomMassDynamically changes the mass of a geometry.mj_setGeomMass(model, geom_id, 1.5)
mj_setBodyMassDynamically changes the mass of a body.mj_setBodyMass(model, body_id, 10.0)
mj_setLengthRangeSets the length range of a tendon.mj_setLengthRange(model, tendon_id, 0.1, 0.5)
  • Use mj_name2id and mj_id2name to access objects in your model dynamically, when you don’t hardcode object IDs.
  • Functions like mj_setGeomMass and mj_setBodyMass allow you to tweak physical properties during runtime.

Attributes

FunctionDescriptionExample Usage
qpos0Default joint positions (initial state).print(model.qpos0)
qpos_springRest positions of joints with springs.print(model.qpos_spring)
jnt_rangeJoint position limits, given as [min, max] for each joint.joint_limits = model.jnt_range
jnt_typeType of each joint (hinge, slide, etc.).print(model.jnt_type)
body_posPositions of all bodies in the model’s local frame.body_positions = model.body_pos
body_quatOrientations of bodies in quaternion format.body_orientations = model.body_quat
geom_posPositions of geometries relative to their parent body.geom_positions = model.geom_pos
geom_sizeDimensions of geometries (e.g., radius for spheres, size for boxes).geom_sizes = model.geom_size
geom_typeType of each geometry (sphere, box, capsule, etc.).print(model.geom_type)
dof_dampingDamping coefficients for degrees of freedom (DOF).damping_values = model.dof_damping
dof_armatureArmature values for rotational DOF.armature_values = model.dof_armature
actuator_ctrlrangeControl range ([min, max]) for each actuator.ctrl_ranges = model.actuator_ctrlrange
actuator_forcerangeForce range ([min, max]) for each actuator.force_ranges = model.actuator_forcerange
actuator_trntypeType of actuator transmission (joint, tendon, etc.).print(model.actuator_trntype)
sensor_typeType of each sensor (force, torque, etc.).sensor_types = model.sensor_type
sensor_dimDimension of each sensor output (e.g., 3 for a 3D force sensor).sensor_dimensions = model.sensor_dim
sensor_addrIndex in the sensordata array where each sensor’s data starts.print(model.sensor_addr)

The mjOBJ_JOINT is a constant identifier in MuJoCo that represents the object type “joint”.

Some common object types and their constants include:

  • mjOBJ_BODY: Refers to a body.
  • mjOBJ_JOINT: Refers to a joint.
  • mjOBJ_GEOM: Refers to a geometry.
  • mjOBJ_SITE: Refers to a site.
  • mjOBJ_SENSOR: Refers to a sensor.
  • mjOBJ_ACTUATOR: Refers to an actuator.
  • mjOBJ_TENDON: Refers to a tendon.

mjData

FunctionDescriptionExample Usage
mj_resetDataResets the simulation to the initial state.mj_resetData(model, data)
mj_stepAdvances the simulation by one timestep.mj_step(model, data)
mj_forwardComputes forward dynamics without advancing time.mj_forward(model, data)
mj_inverseComputes inverse dynamics (forces needed for desired accelerations).mj_inverse(model, data)
mj_applyFTApplies a force/torque to a body at a specific point.mj_applyFT(model, data, force, torque, body_id, point)
mj_getControlRetrieves the current control inputs.controls = mj_getControl(data)
mj_setControlSets the control inputs for actuators.mj_setControl(data, control_values)
mj_contactForceReturns the forces at a specific contact point.force = mj_contactForce(model, data, contact_id)
mj_timeReturns the current simulation time.current_time = mj_time(data)
mj_energyPosComputes the system’s potential energy.potential_energy = mj_energyPos(model, data)
mj_energyVelComputes the system’s kinetic energy.kinetic_energy = mj_energyVel(model, data)
  • Use mj_step to progress the simulation. You can modify data (e.g., joint positions or control inputs) before calling mj_step.
  • mj_contactForce is useful for analyzing interaction forces in contact-rich environments.

Attributes

FunctionDescriptionExample Usage
qposJoint positions, representing the current state of the system.print(data.qpos)
qvelJoint velocities.print(data.qvel)
qaccJoint accelerations.print(data.qacc)
ctrlControl inputs applied to actuators.data.ctrl[:] = [0.1, 0.2, 0.3]
qfrc_appliedForces applied directly to joints.data.qfrc_applied[joint_id] = 1.0
xfrc_appliedExternal forces/torques applied to bodies.data.xfrc_applied[body_id][:3] = [1.0, 0.0, 0.0]
xposGlobal positions of bodies in the simulation.print(data.xpos[body_id])
xquatGlobal orientations of bodies in quaternion format.print(data.xquat[body_id])
xmatGlobal orientations of bodies in rotation matrix format.print(data.xmat[body_id])
cvelCombined spatial velocity (angular + linear) for all bodies in the local frame.spatial_velocity = data.cvel[body_id] \angular_velocity = data.cvel[body_id][:3]\ linear_velocity = data.cvel[body_id][3:]
geom_xposGlobal positions of geometries.print(data.geom_xpos[geom_id])
geom_xmatGlobal orientations of geometries.print(data.geom_xmat[geom_id])
sensordataSensor data output.print(data.sensordata)
subtree_comCenter of mass of each kinematic subtree.print(data.subtree_com[body_id])
subtree_massMass of each kinematic subtree.print(data.subtree_mass[body_id])
cfrc_extContact forces/torques acting on bodies.print(data.cfrc_ext[body_id])
cfrc_intInternal forces/torques acting on bodies.print(data.cfrc_int[body_id])
ten_lengthCurrent lengths of tendons.print(data.ten_length[tendon_id])
ten_velocityVelocities of tendons.print(data.ten_velocity[tendon_id])

Other MuJoCo Functions

FunctionDescriptionExample Usage
mj_loadXMLLoads an XML model into MuJoCo.model = mj_loadXML("model.xml")
mj_makeDataCreates a new mjData object for the loaded model.data = mj_makeData(model)
mj_deleteModelFrees memory allocated for mjModel.mj_deleteModel(model)
mj_deleteDataFrees memory allocated for mjData.mj_deleteData(data)
mjv_updateSceneUpdates the visual representation of the model.mjv_updateScene(model, data, options, scene, camera)
mjr_renderRenders the scene to a viewport.mjr_render(viewport, scene)
This post is licensed under CC BY 4.0 by the author.