Skip to content

UMjPDController

Proportional-Derivative controller running at MuJoCo physics rate.

Treats incoming control values as position targets and computes: torque = Kp * (target - qpos) - Kv * qvel torque = clamp(torque, -TorqueLimit, +TorqueLimit) This runs every physics step (e.g. 1000Hz at dt=0.001), producing fresh torque from live joint state. Use with motor actuators in the MJCF. Designed for sim2sim transfer from policies trained with motor+PD (RoboJuDo, Isaac). Gains should match the training configuration.

Attribute Value
Kind Class
UE Macro UCLASS
Inherits UMjArticulationController
Blueprint Spawnable ✅ Yes

Properties

Public Properties

Property Type Description
Kp TArray<float> Proportional gains, one per bound actuator (in binding order).
Kv TArray<float> Derivative gains, one per bound actuator.
TorqueLimits TArray<float> Torque limits (symmetric), one per bound actuator.
DefaultKp float Default Kp for actuators without explicit gain.
DefaultKv float Default Kv for actuators without explicit gain.
DefaultTorqueLimit float Default torque limit for actuators without explicit limit.
bEnabled bool Is this controller active? If false, ApplyControls falls through to default path.

Kp

Proportional gains, one per bound actuator (in binding order).

  • Type: TArray
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

Kv

Derivative gains, one per bound actuator.

  • Type: TArray
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

TorqueLimits

Torque limits (symmetric), one per bound actuator.

  • Type: TArray
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

DefaultKp

Default Kp for actuators without explicit gain.

  • Type: float
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

DefaultKv

Default Kv for actuators without explicit gain.

  • Type: float
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

DefaultTorqueLimit

Default torque limit for actuators without explicit limit.

  • Type: float
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|PD Controller

bEnabled

Is this controller active? If false, ApplyControls falls through to default path.

  • Type: bool
  • Editor: ✏️ EditAnywhere
  • Blueprint: 🔵 ReadWrite
  • Category: MuJoCo|Controller

Protected Properties

Property Type Description
Bindings TArray<FActuatorBinding> Actuator→DOF bindings, populated by Bind().

Bindings

Actuator→DOF bindings, populated by Bind().

Functions

Public Functions

General

Function Returns Description
Bind() void Called once after the MuJoCo model compiles. Resolves actuator→DOF
ComputeAndApply() void Called every physics step from AMjArticulation::ApplyControls().
IsBound() bool Has Bind() been called successfully?
GetNumBindings() int32 Number of bound actuators.
GetBindings() const TArray<FActuatorBinding>& Access bindings (for gain configuration by name).
Bind

Called once after the MuJoCo model compiles. Resolves actuator→DOF

  • Signature: Bind(mjModel* m, mjData* d, const TMapUMjActuator\*>& ActuatorIdMap)
ComputeAndApply

Called every physics step from AMjArticulation::ApplyControls().

  • Signature: ComputeAndApply(mjModel* m, mjData* d, uint8 Source)
IsBound

Has Bind() been called successfully?

  • Signature: IsBound()
  • Returns: bool
GetNumBindings

Number of bound actuators.

  • Signature: GetNumBindings()
  • Returns: int32
GetBindings

Access bindings (for gain configuration by name).

MuJoCo|PD Controller

Function Returns Description
SetGains() void Set all gains at once. Arrays must match binding count.
SetGains

Set all gains at once. Arrays must match binding count.

  • Signature: SetGains(const TArray<float>& NewKp, const TArray<float>& NewKv, const TArray<float>& NewTorqueLimits)
  • Blueprint: 🔵 Callable