Module: MJSpec

Variables

template<class>
bool dependent_false = false
class MJSpec
#include <MJSpec.h>

A wrapper for a MuJoCo mjSpec, which represents a high-level model specification.

The MJSpec class manages a pair of MuJoCo models and data objects, for which it supports recompilation.

This class keeps tracks of Basilisk wrappers for the MuJoCo bodies, actuators, and equalities of an MJScene.

Public Functions

MJSpec(MJScene &scene, std::string xmlString, const std::vector<std::string> &files = {})

Constructs an MJSpec object.

Parameters:
  • scene – Reference to the MJScene managing this spec.

  • xmlString – The XML string defining the MuJoCo model.

  • files – Optional list of additional files to load.

MJSpec(const MJSpec&) = delete
MJSpec(MJSpec&&) = delete
MJSpec &operator=(const MJSpec&) = delete
MJSpec &operator=(MJSpec&&) = delete
inline MJScene &getScene()

Retrieves the scene that this model specification represents.

Returns:

Reference to the MJScene.

inline void markAsNeedingToRecompileModel()

Declares that the mjModel should recompiled because we performed an action that rendered the current mjModel stale.

mjModel *getMujocoModel()

Retrieves the MuJoCo model (mjModel object).

Returns:

Pointer to the MuJoCo model.

mjData *getMujocoData()

Retrieves the MuJoCo data (mjData object).

Returns:

Pointer to the MuJoCo data.

inline mjSpec *getMujocoSpec()

Retrieves the raw MuJoCo model specification (mjSpec object).

Returns:

Pointer to the MuJoCo specification.

bool recompileIfNeeded()

Recompiles the model if needed.

Returns:

True if recompilation occurred, false otherwise.

void configure()

Configures all bodies, actuators, and equalities with the current model.

inline std::list<MJBody> &getBodies()

Retrieves the list of all bodies in the simulation.

Returns:

Reference to the list of MJBody objects.

inline std::vector<std::unique_ptr<MJActuator>> &getActuators()

Retrieves the list of all actuators in the simulation.

Returns:

Reference to the vector of unique pointers to MJActuator objects.

inline std::list<MJEquality> &getEqualities()

Retrieves the list of equalities in the simulation.

Note that this not include constraint equalities automatically created for all scalar joints in the simulation.

Returns:

Reference to the list of MJEquality objects.

bool hasActuator(const std::string &name)

Checks if an actuator exists with the given name.

Parameters:

name – The name of the actuator.

Returns:

True if the actuator exists, false otherwise.

template<typename T>
T &getActuator(const std::string &name)

Retrieves an actuator by name and casts it to the specified type.

Template Parameters:

T – The expected type of the actuator.

Parameters:

name – The name of the actuator.

Throws:

std::invalid_argument – If the actuator does not exist or has a different type.

Returns:

Reference to the actuator of type T.

MJSingleActuator &addSingleActuator(const std::string &name, const std::string &site, const Eigen::Vector6d &gear)

Adds a single-input actuator (MJSingleActuator).

This actuator will impart a force and/or torque at the given site.

The gear argument defines how the single input of the actuator (the control value of this actuator is a single value) maps into a force and/or torque. For example:

  • For gear={1,0,0,0,0,0} and ctrl=10, the actuator will impart 10 N of force along the X-axis of the site reference frame.

  • For gear={1,0,0,0,1,0} and ctrl=10, the actuator will impart 10 N of force along the X-axis of the site reference frame and 10 Nm of torque along the Y-axis of the same reference frame.

Parameters:
  • name – The name of the actuator.

  • site – The site to attach the actuator.

  • gear – The gear parameters for the actuator.

Returns:

Reference to the created MJSingleActuator.

template<typename T>
inline T &addCompositeActuator(const std::string &name, const std::string &site)

Adds a composite actuator to the specification.

Composite actuators are those composed by more than one single actuator.

Template Parameters:

T – The type of composite actuator to add. Supported types are MJForceActuator, MJTorqueActuator, MJForceTorqueActuator.

Parameters:
  • name – The name of the actuator.

  • site – The site to attach the actuator.

Returns:

Reference to the created actuator of type T.

Protected Functions

void loadBodies()

Load bodies in spec into MJBody.

void loadActuators()

Load actuators in spec into MJActuator.

void loadEqualities()

Load equalities in spec into MJEquality.

template<typename T>
std::unique_ptr<T> createActuator(const std::string &name, const std::string &siteHint, std::unordered_map<std::string, MJActuatorObject> &existingActuators)

Creates an actuator of type T, where T must be one of: MJForceActuator, MJTorqueActuator, or MJForceTorqueActuator.

The actuator will be composed of a collection of the MJActuatorObject given in existingActuators, if they are available. Otherwise, new MJActuatorObject will be created at the given site.

Template Parameters:

T – The type of actuator to add. Supported types are MJForceActuator, MJTorqueActuator, MJForceTorqueActuator.

Parameters:
  • name – The name of the actuator.

  • siteHint – The site to attach the actuator.

  • existingActuators – Colleciton of existing MJActuatorObject to use.

Returns:

Reference to the created actuator of type T.

Protected Attributes

std::unique_ptr<mjSpec, MJBasilisk::detail::mjSpecDeleter> spec

MuJoCo spec.

std::unique_ptr<mjModel, MJBasilisk::detail::mjModelDeleter> model

MuJoCo model.

std::unique_ptr<mjData, MJBasilisk::detail::mjDataDeleter> data

MuJoCo data.

std::unique_ptr<mjVFS, MJBasilisk::detail::mjVFSDeleter> virtualFileSystem

MuJoCo virtual file system.

MJScene &scene

Reference to the associated scene.

std::vector<std::unique_ptr<MJActuator>> actuators

List of actuators.

std::list<MJBody> bodies

List of bodies.

std::list<MJEquality> equalities

List of equalities.

bool shouldRecompile = false

A number of operations on the mjSpec (like adding elements) will require that we recompile the mjModel. If this flag is true when getMujocoModel()/getMujocoData() is called, then they will be recompiled before returning. However, also read the docstring for shouldRecompileWhenAsked.

bool shouldRecompileWhenAsked = true

If we are going to make a series of operations that should trigger a recompile, but we want to avoid having to recompile until they are all done, then we can switch this flag, which will prevent any recompilation when calling getMujocoModel()/getMujocoData().

struct NoRecompileGuard
#include <MJSpec.h>

Guard to temporarily disable model recompilation.

Disables automatic recompilation of the MuJoCo model during its lifetime. Can be used when one wants to take one or several actions that would normally trigger a model recompilation, but for efficiency recompilation is supressed until a later moment.

Public Functions

inline NoRecompileGuard(MJSpec &spec)

Constructs the guard and disables recompilation.

Parameters:

spec – Reference to the MJSpec object.

inline ~NoRecompileGuard()

Restores the previous recompilation flag state.

Public Members

MJSpec &spec

Reference to the MJSpec object.

bool prevShouldRecompileWhenAsked

Previous state of recompilation flag.

namespace Eigen

Typedefs

using Vector6d = Eigen::Matrix<double, 6, 1>