UMjAdhesionActuator¶
Specific Adhesion Actuator component.
| Attribute | Value |
|---|---|
| Kind | Class |
| UE Macro | UCLASS |
| Inherits | UMjActuator |
| Blueprint Spawnable | ✅ Yes |
Properties¶
Public Properties¶
| Property | Type | Description |
|---|---|---|
gain |
float |
|
Kp |
float |
Proportional gain (Kp) for position servos. |
group |
int32 |
|
nsample |
int32 |
|
interp |
int32 |
|
delay |
float |
|
ctrllimited |
bool |
|
forcelimited |
bool |
|
actlimited |
bool |
|
armature |
float |
|
cranklength |
float |
|
actdim |
int32 |
|
Type |
EMjActuatorType | The type of actuator dynamics (e.g. Motor, Position). |
TransmissionType |
EMjActuatorTrnType | The transmission type connecting the actuator to the system. |
GainType |
EMjGainType | |
BiasType |
EMjBiasType | |
DynType |
EMjDynType | |
MjClassName |
FString |
Optional MuJoCo class name to inherit defaults from (string fallback). |
DefaultClass |
UMjDefault* | Reference to a UMjDefault component for default class inheritance. |
TargetName |
FString |
Name of the target element (Joint, Tendon, Site, etc.) this actuator acts upon. |
SliderSite |
FString |
Name of the slider site for slider-crank transmission. |
RefSite |
FString |
Reference site name. |
gain¶
Override-enabled (
bOverride_gain)
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
Kp¶
Proportional gain (Kp) for position servos.
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator|Parameters
- Notes: Override-enabled (
bOverride_Kp)
group¶
Override-enabled (
bOverride_group)
- Type: int32
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
nsample¶
Override-enabled (
bOverride_nsample)
- Type: int32
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
interp¶
Override-enabled (
bOverride_interp)
- Type: int32
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
delay¶
Override-enabled (
bOverride_delay)
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
ctrllimited¶
Override-enabled (
bOverride_ctrllimited)
- Type: bool
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
forcelimited¶
Override-enabled (
bOverride_forcelimited)
- Type: bool
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
actlimited¶
Override-enabled (
bOverride_actlimited)
- Type: bool
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
armature¶
Override-enabled (
bOverride_armature)
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
cranklength¶
Override-enabled (
bOverride_cranklength)
- Type: float
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
actdim¶
Override-enabled (
bOverride_actdim)
- Type: int32
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|MjActuator
Type¶
The type of actuator dynamics (e.g. Motor, Position).
- Type: EMjActuatorType
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
TransmissionType¶
The transmission type connecting the actuator to the system.
- Type: EMjActuatorTrnType
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
GainType¶
Override-enabled (
bOverride_GainType)
- Type: EMjGainType
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
BiasType¶
Override-enabled (
bOverride_BiasType)
- Type: EMjBiasType
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
DynType¶
Override-enabled (
bOverride_DynType)
- Type: EMjDynType
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
MjClassName¶
Optional MuJoCo class name to inherit defaults from (string fallback).
- Type: FString
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
DefaultClass¶
Reference to a UMjDefault component for default class inheritance.
- Type: UMjDefault*
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
TargetName¶
Name of the target element (Joint, Tendon, Site, etc.) this actuator acts upon.
- Type: FString
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
SliderSite¶
Name of the slider site for slider-crank transmission.
- Type: FString
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
RefSite¶
Reference site name.
- Type: FString
- Editor: ✏️ EditAnywhere
- Blueprint: 🔵 ReadWrite
- Category: MuJoCo|Actuator
Functions¶
Public Functions¶
General¶
| Function | Returns | Description |
|---|---|---|
ImportFromXml() |
void | Imports properties and override flags directly from the raw XML node. |
RegisterToSpec() |
void | Registers this actuator to the MuJoCo spec. |
Bind() |
void | Binds this component to the live MuJoCo simulation. |
GetMjName() |
FString |
Gets the full prefixed name of this actuator as it appears in the compiled MuJoCo model. |
ResolveDesiredControl() |
float |
Resolves the final control value to apply based on the specified source. |
SetNetworkControl() |
void | Sets the control value from the ZMQ networked stream. |
ImportFromXml¶
Imports properties and override flags directly from the raw XML node.
- Signature:
ImportFromXml(const class FXmlNode*Node, const struct FMjCompilerSettings& CompilerSettings)
RegisterToSpec¶
Registers this actuator to the MuJoCo spec.
- Signature:
RegisterToSpec(class FMujocoSpecWrapper& Wrapper,mjsBody*ParentBody)
Bind¶
Binds this component to the live MuJoCo simulation.
- Signature:
Bind(mjModel*Model,mjData*Data,const FString&Prefix)
GetMjName¶
Gets the full prefixed name of this actuator as it appears in the compiled MuJoCo model.
- Signature:
GetMjName() - Returns: FString
ResolveDesiredControl¶
Resolves the final control value to apply based on the specified source.
- Signature:
ResolveDesiredControl(uint8Source) - Returns: float
SetNetworkControl¶
Sets the control value from the ZMQ networked stream.
- Signature:
SetNetworkControl(floatValue)
MuJoCo|Runtime¶
| Function | Returns | Description |
|---|---|---|
SetControl() |
void | Sets the internal control input (ctrl) for this actuator. |
ResetControl() |
void | Resets the control input (ctrl) for this actuator to zero. |
GetControl() |
float |
Gets the current resolved control value being applied. |
GetForce() |
float |
Gets the current force generated by this actuator. |
GetLength() |
float |
Gets the current length of the actuator. |
GetVelocity() |
float |
Gets the current velocity of the actuator. |
GetControlRange() |
FVector2D |
Gets the control range [min, max] from the compiled model. Returns ZeroVector if ctrl is not limited. |
GetActivation() |
float |
Gets the current activation state (for stateful actuators like muscle/intvelocity). Returns 0 if stateless. |
SetGear() |
void | Sets the gear ratio (expert use). |
GetGear() |
TArray<float> |
Gets the gear ratio. |
SetControl¶
Sets the internal control input (ctrl) for this actuator.
- Signature:
SetControl(floatValue) - Blueprint: 🔵 Callable
ResetControl¶
Resets the control input (ctrl) for this actuator to zero.
- Signature:
ResetControl() - Blueprint: 🔵 Callable
GetControl¶
Gets the current resolved control value being applied.
- Signature:
GetControl() - Blueprint: 🔵 Callable
- Returns: float
GetForce¶
Gets the current force generated by this actuator.
- Signature:
GetForce() - Blueprint: 🔵 Callable
- Returns: float
GetLength¶
Gets the current length of the actuator.
- Signature:
GetLength() - Blueprint: 🔵 Callable
- Returns: float
GetVelocity¶
Gets the current velocity of the actuator.
- Signature:
GetVelocity() - Blueprint: 🔵 Callable
- Returns: float
GetControlRange¶
Gets the control range [min, max] from the compiled model. Returns ZeroVector if ctrl is not limited.
- Signature:
GetControlRange() - Blueprint: 🔵 Callable
- Returns: FVector2D
GetActivation¶
Gets the current activation state (for stateful actuators like muscle/intvelocity). Returns 0 if stateless.
- Signature:
GetActivation() - Blueprint: 🔵 Callable
- Returns: float
SetGear¶
Sets the gear ratio (expert use).
- Signature:
SetGear(const TArray<float>&NewGear) - Blueprint: 🔵 Callable