Module: MJBody

class MJBody : public MJObject<mjsBody>
#include <MJBody.h>

Represents a MuJoCo body object.

The MJBody class manages a body in the MuJoCo simulation, including its joints, sites, and inertial properties.

Public Functions

MJBody(mjsBody *mjsBody, MJSpec &spec)

Constructs an MJBody with a given MuJoCo body object and the spec where it’s created.

Parameters:
  • mjsBody – Pointer to the MuJoCo body.

  • spec – Reference to the MJSpec associated with the body.

MJBody(const MJBody&) = delete
MJBody(MJBody&&) = delete
MJBody &operator=(const MJBody&) = delete
MJBody &operator=(MJBody&&) = delete
void configure(const mjModel *model)

Configures the body within a given MuJoCo model.

Parameters:

model – Pointer to the MuJoCo model used for configuration.

void addSite(std::string name, const Eigen::Vector3d &position, const Eigen::MRPd &attitude = {0., 0., 0.})

Adds a site to the body with a specified name, position, and attitude.

Parameters:
  • name – The name of the site.

  • position – The position of the site relative to the body.

  • attitude – The orientation of the site as Modified Rodrigues Parameters (MRP).

bool hasSite(const std::string &name) const

Checks if the body has a site with a given name.

Parameters:

name – The name of the site to search for.

Returns:

True if the site exists, false otherwise.

MJSite &getSite(const std::string &name)

Retrieves a site by name.

Parameters:

name – The name of the site to retrieve.

Throws:

std::invalid_argument – if the site does not exist.

Returns:

A reference to the MJSite with the specified name.

inline MJSite &getCenterOfMass()

Retrieves the center of mass site of the object.

This site is located at the center of mass of the body (ignoring any child bodies). The frame orientation is the same as the origin site frame orientation.

Returns:

A reference to the center of mass site.

inline MJSite &getOrigin()

Retrieves the origin site.

This site corresponds to the origin (main, base) reference frame of the body. All other sites’ positions, as well as the center of mass, are given with respect to this reference frame.

Returns:

A reference to the origin site.

inline MJSpec &getSpec()

Retrieves the associated MJSpec object.

Returns:

A reference to the MJSpec associated with this body.

MJScalarJoint &getScalarJoint(const std::string &name)

Retrieves a scalar joint by name.

Parameters:

name – The name of the scalar joint.

Throws:
  • std::invalid_argument – if the joint does not exist.

  • std::invalid_argument – if the joint with that name is not a scalar joint.

Returns:

A reference to the MJScalarJoint.

inline bool hasBallJoint()

Checks whether the body has a ball joint.

Returns:

True if the body has a ball joint.

MJBallJoint &getBallJoint()

Retrieves the ball joint of this body, if it exists.

Throws:

std::runtime_error – if the joint does not have a ball joint.

Returns:

A reference to the MJBallJoint.

inline bool isFree()

Checks whether this is a free body.

‘Free’ bodies are those that have a ‘free’ joint, and thus they can move freely in the environment. For these bodies, we can set the position, velocity, attitude, and angular rate. Usually, ‘free’ bodies are those without parent bodies in the simulation (‘top-level’ bodies).

Returns:

True if the body has a free joint.

MJFreeJoint &getFreeJoint()

Retrieves the free joint of this body, if it exists.

Throws:

std::runtime_error – if the joint does not have a free joint.

Returns:

A reference to the MJBallJoint.

void setPosition(const Eigen::Vector3d &position)

Sets the position of the body.

This method may only be called for ‘free’ bodies. Free bodies are those that have a ‘free’ joint.

Parameters:

position – The desired 3D position vector.

Throws:

std::runtime_error – if this body is not free (has no ‘free’ joint).

void setVelocity(const Eigen::Vector3d &velocity)

Sets the translational velocity of the body.

This method may only be called for ‘free’ bodies. Free bodies are those that have a ‘free’ joint.

Parameters:

velocity – The desired 3D velocity vector.

Throws:

std::runtime_error – if this body is not free (has no ‘free’ joint).

void setAttitude(const Eigen::MRPd &attitude)

Sets the orientation (attitude) of the body.

This method may only be called for ‘free’ bodies. Free bodies are those that have a ‘free’ joint.

Parameters:

attitude – The orientation represented as Modified Rodrigues Parameters (MRP).

Throws:

std::runtime_error – if this body is not free (has no ‘free’ joint).

void setAttitudeRate(const Eigen::Vector3d &attitudeRate)

Sets the attitude rate (angular velocity) of the body.

This method may only be called for ‘free’ bodies. Free bodies are those that have a ‘free’ joint.

Parameters:

attitudeRate – The desired 3D attitude rate vector.

Throws:

std::runtime_error – if this body is not free (has no ‘free’ joint).

void writeFwdKinematicsMessages(mjModel *m, mjData *d, uint64_t CurrentSimNanos)

Writes forward kinematics messages based on the current state.

Writes the state (position, attitude, etc.) out messages for all sites in this body.

Parameters:
  • m – Pointer to the MuJoCo model.

  • d – Pointer to the MuJoCo data.

  • CurrentSimNanos – The current simulation time in nanoseconds.

void writeStateDependentOutputMessages(uint64_t CurrentSimNanos)

Writes body-mass-properties and joint-state messages.

Parameters:

CurrentSimNanos – The current simulation time in nanoseconds.

void registerStates(DynParamRegisterer paramManager)

Registers the body’s states with a dynamic parameter registerer.

Currently, only the mass of the body is considered a parameter.

Parameters:

paramManager – The dynamic parameter registerer.

void updateMujocoModelFromMassProps()

Updates the MuJoCo model from the mass properties of the body.

The mass of the body is a state, which may change in time (for example, when a thruster burns fuel). This change in mass must be relayed back to MuJoCo. Calling this method will update the mjModel with the mass value stored in the mass state of this body.

Note that the inertia is also updated (scaled by the change in mass). The center of mass remains constant.

This method will also mark the kinematics and mujoco model ‘const’ as stale.

void updateMassPropsDerivative()

Updates the derivative of the mass state with the information from the connected derivativeMassPropertiesInMsg.

If no such message is connected, then the derivative is assumed to be zero.

void updateConstrainedEqualityJoints()

Updates all constrained equality joints associated with the body.

Calls MJScalarJoint::updateConstrainedEquality for all scalar joints in this body.

Public Members

Message<SCMassPropsMsgPayload> massPropertiesOutMsg

Message to output body mass properties.

ReadFunctor<SCMassPropsMsgPayload> derivativeMassPropertiesInMsg

Functor to read mass properties derivatives.

Protected Attributes

MJSpec &spec

Reference to the spec where this body is defined.

std::list<MJSite> sites

List of sites associated with the body.

std::optional<MJFreeJoint> freeJoint

Optional free joint associated with the body.

std::optional<MJBallJoint> ballJoint

Optional ball joint associated with the body.

std::list<MJScalarJoint> scalarJoints

List of scalar joints associated with the body.

StateData *massState

State data representing the mass of the body.