UMjPhysicsEngine¶
Core physics engine component that owns the MuJoCo simulation lifecycle.
Manages mjSpec compilation, mjModel/mjData ownership, the async physics loop, and callback registration for pre/post step hooks.
| Attribute | Value |
|---|---|
| Kind | Class |
| UE Macro | UCLASS |
| Inherits | UActorComponent |
| Blueprint Spawnable | ✅ Yes |
Properties¶
Public Properties¶
| Property | Type | Description |
|---|---|---|
m_spec |
mjSpec* |
Pointer to the MuJoCo specification structure. |
m_vfs |
mjVFS |
MuJoCo Virtual File System instance. |
m_model |
mjModel* |
Pointer to the compiled MuJoCo model. |
m_data |
mjData* |
Pointer to the active MuJoCo simulation data. |
AsyncPhysicsFuture |
TFuture<void> |
Future for the async physics thread, used to wait for exit in EndPlay. |
FMujocoStepCallback |
using |
Delegate for custom physics stepping. |
FMujocoPostStepCallback |
using |
Delegate called immediately after mj_step (or custom step). |
PendingStateVector |
TArray<double> |
Plain-data copy of the state to restore. |
Options |
FMuJoCoOptions | Simulation Options (Timestep, Gravity, etc.). |
SimSpeedPercent |
float |
Simulation speed percentage (0-100). 100 = realtime, 50 = half speed. |
bIsPaused |
bool |
If true, the simulation loop skips stepping the physics. |
bSaveDebugXml |
bool |
If true, saves compiled scene XML and MJB to Saved/URLab/ on each compile. |
ControlSource |
EControlSource | Global default control source (ZMQ or UI). |
m_MujocoComponents |
TArray<UMjQuickConvertComponent*> | List of custom physics components registered with this manager. |
m_articulations |
TArray<AMjArticulation*> | List of articulations (multi-body structures) registered with this manager. |
m_heightfieldActors |
TArray<AMjHeightfieldActor*> | List of heightfield actors registered with this manager. |
m_ArticulationMap |
TMap |
O(1) articulation lookup. Key = actor name. |
m_LastCompileError |
FString |
Error string from the most recent Compile() call. Empty on success. |
AsyncPhysicsFuture¶
Future for the async physics thread, used to wait for exit in EndPlay.
- Type: TFuture
Options¶
Simulation Options (Timestep, Gravity, etc.).
- Type: FMuJoCoOptions
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Options
SimSpeedPercent¶
Simulation speed percentage (0-100). 100 = realtime, 50 = half speed.
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Options
bIsPaused¶
If true, the simulation loop skips stepping the physics.
- Type: bool
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Status
bSaveDebugXml¶
If true, saves compiled scene XML and MJB to Saved/URLab/ on each compile.
- Type: bool
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Debug
ControlSource¶
Global default control source (ZMQ or UI).
- Type: EControlSource
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Runtime
m_MujocoComponents¶
List of custom physics components registered with this manager.
- Type: TArray<UMjQuickConvertComponent*>
m_articulations¶
List of articulations (multi-body structures) registered with this manager.
- Type: TArray<AMjArticulation*>
m_heightfieldActors¶
List of heightfield actors registered with this manager.
- Type: TArray<AMjHeightfieldActor*>
m_LastCompileError¶
Error string from the most recent Compile() call. Empty on success.
- Type: FString
Functions¶
Public Functions¶
General¶
| Function | Returns | Description |
|---|---|---|
Compile() |
void | Compiles the aggregated mjSpec into an mjModel and initializes mjData. |
PreCompile() |
void | Scans the scene for MuJoCo components and articulations to populate m_spec. |
PostCompile() |
void | Finalizes setup after compilation (actuator maps, PostSetup calls). |
ApplyOptions() |
void | Applies the settings from Options to m_model->opt. |
RunMujocoAsync() |
void | Starts the asynchronous thread for stepping the MuJoCo simulation. |
SetPaused() |
void | Pauses or Resumes the physics simulation. |
IsRunning() |
bool |
Checks if the simulation is currently running (initialized and not paused). |
IsInitialized() |
bool |
Checks if the MuJoCo model is compiled and data is allocated. |
GetSimTime() |
float |
Gets the current MuJoCo simulation time in seconds. |
GetTimestep() |
float |
Gets the simulation timestep from Options (dt). |
ResetSimulation() |
void | Resets the MuJoCo simulation data to initial state. |
StepSync() |
void | Steps the simulation synchronously on the calling thread. |
CompileModel() |
bool |
Re-runs Compile() and restarts the async simulation loop. |
CaptureSnapshot() |
UMjSimulationState* | Captures a full state snapshot of the current simulation. |
RestoreSnapshot() |
void | Schedules a simulation state restore for the next physics step. |
SetControlSource() |
void | Sets the global default control source. |
GetControlSource() |
EControlSource | Gets the current control source. |
GetArticulation() |
AMjArticulation* | Gets a registered articulation by its Actor name. |
GetAllArticulations() |
TArray<AMjArticulation*> | Gets all registered articulations. |
GetAllQuickComponents() |
TArray<UMjQuickConvertComponent*> | Gets all registered QuickConvert components. |
GetAllHeightfields() |
TArray<AMjHeightfieldActor*> | Gets all registered Heightfield actors. |
GetLastCompileError() |
FString |
Returns the error string from the most recent failed compile. |
RegisterPreStepCallback() |
void | Register a callback to be invoked before each physics step. |
RegisterPostStepCallback() |
void | Register a callback to be invoked after each physics step. |
ClearCallbacks() |
void | Clear all registered pre/post step callbacks. |
Compile¶
Compiles the aggregated mjSpec into an mjModel and initializes mjData.
- Signature:
Compile()
PreCompile¶
Scans the scene for MuJoCo components and articulations to populate m_spec.
- Signature:
PreCompile()
PostCompile¶
Finalizes setup after compilation (actuator maps, PostSetup calls).
- Signature:
PostCompile()
RunMujocoAsync¶
Starts the asynchronous thread for stepping the MuJoCo simulation.
- Signature:
RunMujocoAsync()
IsRunning¶
Checks if the simulation is currently running (initialized and not paused).
- Signature:
IsRunning() - Returns: bool
IsInitialized¶
Checks if the MuJoCo model is compiled and data is allocated.
- Signature:
IsInitialized() - Returns: bool
GetSimTime¶
Gets the current MuJoCo simulation time in seconds.
- Signature:
GetSimTime() - Returns: float
GetTimestep¶
Gets the simulation timestep from Options (dt).
- Signature:
GetTimestep() - Returns: float
StepSync¶
Steps the simulation synchronously on the calling thread.
- Signature:
StepSync(int32NumSteps)
CompileModel¶
Re-runs Compile() and restarts the async simulation loop.
- Signature:
CompileModel() - Returns: bool
CaptureSnapshot¶
Captures a full state snapshot of the current simulation.
- Signature:
CaptureSnapshot() - Returns: UMjSimulationState*
RestoreSnapshot¶
Schedules a simulation state restore for the next physics step.
- Signature:
RestoreSnapshot(UMjSimulationState* Snapshot)
SetControlSource¶
Sets the global default control source.
- Signature:
SetControlSource(EControlSource NewSource)
GetControlSource¶
Gets the current control source.
- Signature:
GetControlSource() - Returns: EControlSource
GetArticulation¶
Gets a registered articulation by its Actor name.
- Signature:
GetArticulation(const FString&ActorName) - Returns: AMjArticulation*
GetAllArticulations¶
Gets all registered articulations.
- Signature:
GetAllArticulations() - Returns: TArray<AMjArticulation*>
GetAllQuickComponents¶
Gets all registered QuickConvert components.
- Signature:
GetAllQuickComponents() - Returns: TArray<UMjQuickConvertComponent*>
GetAllHeightfields¶
Gets all registered Heightfield actors.
- Signature:
GetAllHeightfields() - Returns: TArray<AMjHeightfieldActor*>
GetLastCompileError¶
Returns the error string from the most recent failed compile.
- Signature:
GetLastCompileError() - Returns: FString
RegisterPreStepCallback¶
Register a callback to be invoked before each physics step.
- Signature:
RegisterPreStepCallback(FPhysicsCallbackCallback)
RegisterPostStepCallback¶
Register a callback to be invoked after each physics step.
- Signature:
RegisterPostStepCallback(FPhysicsCallbackCallback)