Module: MJSite
-
class MJSite : public MJObject<mjsSite>
- #include <MJSite.h>
Represents a MuJoCo site, which is a reference point attached to a body.
The
MJSite
class provides functionality to manage a ‘site’ in MuJoCo. A ‘site’ represents a point in MuJoCo where one may query dynamic information (such as position, orientation, velocity…) and apply forces and torques.Public Functions
-
MJSite(mjsSite *site, MJBody &body)
Constructs an
MJSite
object with a given MuJoCo site object and the body where it’s attached.- Parameters:
site – Pointer to the MuJoCo site.
body – Reference to the body the site is attached to.
-
inline MJBody &getBody()
Retrieves the body the site is attached to.
- Returns:
A reference to the attached
MJBody
object.
-
void setPositionRelativeToBody(const Eigen::Vector3d &position)
Sets the position of the site relative to the body it’s attached to.
- Parameters:
position – The 3D position vector relative to the body, in the body reference frame.
-
void setAttitudeRelativeToBody(const Eigen::MRPd &attitude)
Sets the attitude (orientation) of the site relative to the body it’s attached to.
- Parameters:
attitude – The orientation represented as Modified Rodrigues Parameters (MRP) from the body reference frame.
-
void writeFwdKinematicsMessage(mjModel *model, mjData *data, uint64_t CurrentSimNanos)
Writes the frame state message (
stateOutMsg
) based on the state of the site.Sets the position, velocity, orientation, and angular rate of the site in the inertial frame, as parsed from the given MuJoCo model and data.
- Parameters:
model – Pointer to the MuJoCo model.
data – Pointer to the MuJoCo simulation data.
CurrentSimNanos – The current simulation time in nanoseconds.
Public Members
-
Message<SCStatesMsgPayload> stateOutMsg
Message to output site frame state.
-
MJSite(mjsSite *site, MJBody &body)