MJJoint

class MJJoint : public MJObject<mjsJoint>
#include <MJJoint.h>

Represents a MuJoCo joint.

Each joint owns its own StateData for position and velocity (one or more, depending on joint type).

Subclassed by MJBallJoint, MJFreeJoint, MJScalarJoint

Public Functions

inline MJJoint(mjsJoint *joint, MJBody &body)

Constructs an MJJoint with a given joint and the body it’s attached to.

Parameters:
  • joint – Pointer to the MuJoCo joint.

  • body – Reference to the body the joint is associated with.

MJJoint(const MJJoint&) = delete
MJJoint(MJJoint&&) = delete
MJJoint &operator=(const MJJoint&) = delete
MJJoint &operator=(MJJoint&&) = delete
inline virtual ~MJJoint()

Virtual destructor for MJJoint.

inline MJBody &getBody()

Retrieves the body that this joint is attached to.

Returns:

Reference to the MJScene.

void configure(const mjModel *m)

Configures the joint within a given MuJoCo model.

Parameters:

m – Pointer to the MuJoCo model used for configuration.

virtual void registerStates(DynParamRegisterer registerer) = 0

Registers this joint’s qpos/qvel StateData on the manager.

Each joint type registers state objects sized for its DOFs. Names are scoped via registerer’s prefix so collisions across joints are impossible.

virtual void setStateInMujoco(mjData *d) const = 0

Sets mjData::qpos and mjData::qvel from the joint’s owned state values at this joint’s address.

virtual void getStateFromMujoco(const mjData *d) = 0

Gets the joint’s slice of mjData::qpos/mjData::qvel and stores it in the joint’s owned states. Used at initialization to seed states from the values declared in the XML.

virtual void setDerivativesFromMujoco(const mjData *d) = 0

Sets the joint’s qpos and qvel state derivatives from the current mjData::qvel and mjData::qacc.

inline size_t getQposAdr() const

Returns this joint’s address into mjData::qpos.

inline size_t getQvelAdr() const

Returns this joint’s address into mjData::qvel.

Protected Functions

void checkInitialized() const

Checks if the joint has been properly initialized.

Throws an exception if initialization has not been completed.

Protected Attributes

MJBody &body

Reference to the body the joint is attached to.

std::optional<size_t> qposAdr

Address for position in the state vector.

std::optional<size_t> qvelAdr

Address for velocity in the state vector.

class MJScalarJoint : public MJJoint
#include <MJJoint.h>

Represents a scalar joint in MuJoCo.

The MJScalarJoint class provides additional functionality for single degree-of-freedom joints, both linear and angular. The position and velocity of this joint can be set.

Owns a 1x1 StateData for position and a 1x1 StateData for velocity.

If constrainedStateInMsg is linked, the value in this message will be read and applied to an MJSingleJointEquality such that the joint is constrained to hold a specific state. This can be used to enforce joints to follow a specific path, while letting the MuJoCo engine figure out the necessary force/torque to produce this path.

Public Functions

MJScalarJoint(mjsJoint *joint, MJBody &body)

Constructs an MJScalarJoint with a given joint and body.

Parameters:
  • joint – Pointer to the MuJoCo joint.

  • body – Reference to the body the joint is associated with.

Eigen::Vector3d getAxis() const

Returns the axis of rotation for hinge joints and the direction of translation for slide joints.

Returned vector is normalized.

bool isHinge() const

Returns true if this is a rotational joint, false if it’s a translational slide joint.

void setPosition(double value)

Sets the position of the joint.

For revolute joints, this is the angle (in radians) of the joint with respect to its zero-pose.

For linear joints, this is the displacement (in meters) of the joint with respect to its zero-pose.

Parameters:

value – The desired position value.

void setVelocity(double value)

Sets the velocity of the joint.

For revolute joints, this is the angular rate (in radians per second).

For linear joints, this is the displacement rate (in meters per second).

Parameters:

value – The desired velocity value.

MJSingleJointEquality getConstrainedEquality()

Returns the equality constraint object associated with this scalar joint.

The returned MJSingleJointEquality can be used to enforce a specific state for the joint within the MuJoCo simulation. This is typically used when the joint is constrained to follow a particular position or velocity, as specified by an input message or control logic.

Returns:

The MJSingleJointEquality object for this joint.

void configure(const mjModel *model)

Configures the scalar joint within the given MuJoCo model.

Parameters:

model – Pointer to the MuJoCo model.

void updateConstrainedEquality()

Updates the constrained equality associated with the joint.

If constrainedStateInMsg is connected, then activates the equality constraint of this joint and sets its ‘offset’ to the value in the message.

void writeJointStateMessage(uint64_t CurrentSimNanos)

Writes the joint state message based on the current simulation state.

Parameters:

CurrentSimNanos – The current simulation time in nanoseconds.

virtual void registerStates(DynParamRegisterer registerer) override

Registers this joint’s qpos/qvel StateData on the manager.

Each joint type registers state objects sized for its DOFs. Names are scoped via registerer’s prefix so collisions across joints are impossible.

virtual void setStateInMujoco(mjData *d) const override

Sets mjData::qpos and mjData::qvel from the joint’s owned state values at this joint’s address.

virtual void getStateFromMujoco(const mjData *d) override

Gets the joint’s slice of mjData::qpos/mjData::qvel and stores it in the joint’s owned states. Used at initialization to seed states from the values declared in the XML.

virtual void setDerivativesFromMujoco(const mjData *d) override

Sets the joint’s qpos and qvel state derivatives from the current mjData::qvel and mjData::qacc.

Public Members

Message<ScalarJointStateMsgPayload> stateOutMsg

Message to output joint position state.

Message<ScalarJointStateMsgPayload> stateDotOutMsg

Message to output joint velocity state.

ReadFunctor<ScalarJointStateMsgPayload> constrainedStateInMsg

Functor to read constrained state input.

Protected Attributes

StateData *qposState = nullptr

1x1 joint position state.

StateData *qvelState = nullptr

1x1 joint velocity state.

MJSingleJointEquality constrainedEquality

An equality used to enforce a specific state for the joint.

class MJBallJoint : public MJJoint
#include <MJJoint.h>

Represents a ball joint in MuJoCo.

Owns a 4x1 QuaternionStateData for the orientation and a 3x1 StateData for the body angular velocity. Not fully supported elsewhere yet.

Public Functions

virtual void registerStates(DynParamRegisterer registerer) override

Registers this joint’s qpos/qvel StateData on the manager.

Each joint type registers state objects sized for its DOFs. Names are scoped via registerer’s prefix so collisions across joints are impossible.

virtual void setStateInMujoco(mjData *d) const override

Sets mjData::qpos and mjData::qvel from the joint’s owned state values at this joint’s address.

virtual void getStateFromMujoco(const mjData *d) override

Gets the joint’s slice of mjData::qpos/mjData::qvel and stores it in the joint’s owned states. Used at initialization to seed states from the values declared in the XML.

virtual void setDerivativesFromMujoco(const mjData *d) override

Sets the joint’s qpos and qvel state derivatives from the current mjData::qvel and mjData::qacc.

inline MJJoint(mjsJoint *joint, MJBody &body)

Use constructor from MJJoint

MJJoint(const MJJoint&) = delete

Use constructor from MJJoint

MJJoint(MJJoint&&) = delete

Use constructor from MJJoint

Protected Attributes

QuaternionStateData *qposState = nullptr

4x1 quaternion (w,x,y,z).

StateData *qvelState = nullptr

3x1 body angular velocity.

class MJFreeJoint : public MJJoint
#include <MJJoint.h>

Represents a free joint in MuJoCo.

The MJFreeJoint class provides additional functionality for joints with three translational and three rotational degrees of freedom, including setting position, velocity, attitude, and attitude rate.

Owns four StateDatas translation pos/vel (3x1 each) and attitude quaternion + angular velocity. This is split so the adaptive integrator can scale tolerances independently for orbital translation and rotation.

Public Functions

void setPosition(const Eigen::Vector3d &position)

Sets the position of the free joint.

Parameters:

position – The desired 3D position vector with respect to the inertial frame.

void setVelocity(const Eigen::Vector3d &velocity)

Sets the translational velocity of the free joint.

Parameters:

velocity – The desired 3D velocity vector with respect to the inertial frame.

void setAttitude(const Eigen::MRPd &attitude)

Sets the attitude (orientation) of the free joint.

Parameters:

attitude – The orientation represented as Modified Rodrigues Parameters (MRP) with respect to the inertial frame.

void setAttitudeRate(const Eigen::Vector3d &attitudeRate)

Sets the attitude rate (angular velocity) of the free joint.

Todo:

Verify if this matches the expected attitude rate conventions with Basilisk.

Parameters:

attitudeRate – The desired 3D attitude rate vector with respect to the inertial frame.

virtual void registerStates(DynParamRegisterer registerer) override

Registers this joint’s qpos/qvel StateData on the manager.

Each joint type registers state objects sized for its DOFs. Names are scoped via registerer’s prefix so collisions across joints are impossible.

virtual void setStateInMujoco(mjData *d) const override

Sets mjData::qpos and mjData::qvel from the joint’s owned state values at this joint’s address.

virtual void getStateFromMujoco(const mjData *d) override

Gets the joint’s slice of mjData::qpos/mjData::qvel and stores it in the joint’s owned states. Used at initialization to seed states from the values declared in the XML.

virtual void setDerivativesFromMujoco(const mjData *d) override

Sets the joint’s qpos and qvel state derivatives from the current mjData::qvel and mjData::qacc.

inline MJJoint(mjsJoint *joint, MJBody &body)

Use constructor from MJJoint

MJJoint(const MJJoint&) = delete

Use constructor from MJJoint

MJJoint(MJJoint&&) = delete

Use constructor from MJJoint

Protected Attributes

StateData *qposTranslationState = nullptr

3x1 inertial position.

QuaternionStateData *qposAttitudeState = nullptr

4x1 attitude quaternion.

StateData *qvelTranslationState = nullptr

3x1 inertial velocity.

StateData *qvelAttitudeState = nullptr

3x1 body angular velocity.