Module: MJJoint

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

Represents a MuJoCo joint.

The MJJoint class provides basic functionality to handle joints in MuJoCo. This is a base class for more specific joint types.

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.

void configure(const mjModel *m)

Configures the joint within a given MuJoCo model.

Parameters:

m – Pointer to the MuJoCo model used for configuration.

Protected Functions

void checkInitialized()

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.

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.

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.

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.

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

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.

Not fully supported.

Public Functions

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

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.

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.

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