Add multirotor/thruster actuator, multirotor asset and manager-based ARL drone task
Description
This PR introduces multirotor and thruster support and adds a manager-based example/task for the ARL drone. The change contains a new low-level thruster actuator model, a new Multirotor articulation asset class + configs, new thrust actions, and a manager-based drone task (ARL drone) with MDP configs and RL agent configs.
Motivation and context
- Provides a reusable multirotor abstraction and a parameterized thruster actuator model so we can simulate multirotor vehicles (quad/hex/other).
- Adds a manager-based ARL drone task and configuration files to enable repro and training workflows for the ARL drone platform.
- Consolidates drone-specific code and prepares the repo for future control/sensor improvements.
Type of change
- New feature (non-breaking addition of new functionality)
- Documentation update (added docs/comments where applicable)
Files changed (high-level summary)
- New/major files added:
- source/isaaclab/isaaclab/actuators/thruster.py (new thruster actuator model)
- source/isaaclab/isaaclab/assets/articulation/multirotor.py (new multirotor articulation)
- source/isaaclab/isaaclab/assets/articulation/multirotor_cfg.py
- source/isaaclab/isaaclab/assets/articulation/multirotor_data.py
- source/isaaclab/isaaclab/envs/mdp/actions/thrust_actions.py
- source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py and ARL drone URDF + asset files as a submodule
- source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_ntnu/* (new task code, commands, observations, rewards, state-based control configs and agent configs)
- Modified:
- source/isaaclab/isaaclab/actuators/actuator_cfg.py (register thruster config)
- source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py (register thrust actions)
- small edits to various utils and types, and docs/make.bat
- Total diff (branch vs main when I checked): 33 files changed, ~2225 insertions, 65 deletions
Dependencies
- No new external top-level dependencies introduced. The branch adds assets (binary
.zip) — ensure Git LFS is used if you want large assets tracked by LFS. - The new drone task references standard repo-internal packages and Isaac Sim; no external pip packages required beyond the repo standard.
Checklist (status)
- [x] I have read and understood the contribution guidelines
- [x] I have run the
pre-commitchecks with./isaaclab.sh --format - [x] I have made corresponding changes to the documentation
- [x] My changes generate no new warnings
- [x] I have added tests that prove my fix is effective or that my feature works
- [ ] I have updated the changelog and the corresponding version in the extension's
config/extension.tomlfile - [x] I have added my name to the
CONTRIBUTORS.mdor my name already exists there
@AntoineRichard @ooctipus would be great if you could give the PR another pass through and give your okay
Greptile Overview
Greptile Summary
This PR introduces comprehensive multirotor support for Isaac Lab, adding a low-level thruster actuator model, a Multirotor articulation asset class, thrust actions, and a manager-based ARL drone task.
Key additions:
-
Thruster actuator model (
thruster.py): Implements first-order motor dynamics with asymmetric rise/fall time constants, RK4/Euler integration, and thrust-to-RPM conversion. Well-tested with edge case coverage. -
Multirotor asset (
multirotor.py,multirotor_data.py): ExtendsArticulationto support thrusters with allocation matrices for control distribution.MultirotorDataproperly inherits fromArticulationData. -
Thrust actions (
thrust_actions.py): Action term for processing thrust commands with scale/offset/clip transformations. - ARL drone task: Manager-based RL environment with MDP configurations (commands, observations, rewards) and agent configs for multiple RL frameworks.
Critical issue found:
-
state_based_control_env_cfg.py:63-69- All command ranges are set to(0.0, 0.0), meaning the drone always targets the same position/orientation with no variation. This makes training completely ineffective since the policy never learns to reach different goals. Must be fixed before training.
Other observations:
- The
yaw_alignedreward assumes target yaw is always 0, but the command config includes a yaw range (currently 0.0, 0.0). If you enable yaw variation, the reward should read the target yaw from commands instead of hardcoding 0. -
ARL_ROBOT_1_CFGhas a TODO comment about motor/propeller specifications that should be completed. - Comprehensive test coverage demonstrates robustness of the thruster implementation.
Confidence Score: 2/5
- This PR has solid implementation but contains a critical configuration bug that breaks training
- Score reflects one critical blocker: the task configuration has all command ranges set to (0.0, 0.0), making the training environment non-functional. The core thruster/multirotor implementation is well-designed and thoroughly tested, but the example task cannot train agents without fixing the command ranges. This is a simple config fix but essential for the PR's stated goal of enabling training workflows.
- Pay immediate attention to
state_based_control_env_cfg.py- the zero command ranges must be fixed before any training attempts. The core implementation files (thruster.py, multirotor.py) are solid.
Important Files Changed
File Analysis
| Filename | Score | Overview |
|---|---|---|
| source/isaaclab/isaaclab/actuators/thruster.py | 4/5 | Implements low-level thruster dynamics with first-order motor model, RK4/Euler integration, and asymmetric rise/fall time constants - comprehensive and well-tested |
| source/isaaclab/isaaclab/assets/articulation/multirotor.py | 4/5 | Extends Articulation for multirotor vehicles with thruster support, allocation matrix, and combined wrench application - properly inherits from parent |
| source/isaaclab/isaaclab/envs/mdp/actions/thrust_actions.py | 4/5 | Implements thrust action term with scale/offset/clip transformations - handles both float and dict configs |
| source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/state_based_control/config/arl_robot_1/state_based_control_env_cfg.py | 1/5 | Drone task config with CRITICAL ISSUE: all command ranges set to (0.0, 0.0) making training ineffective - drone always targets same pose |
| source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/rewards.py | 3/5 | Drone reward functions (distance, velocity penalties, yaw alignment) - yaw_aligned assumes target yaw is always 0 which may not match command |
| source/isaaclab_assets/isaaclab_assets/robots/arl_robot_1.py | 4/5 | ARL Robot 1 config with thruster parameters and allocation matrix for quadrotor - has TODO for motor/propeller specs |
Sequence Diagram
sequenceDiagram
participant Env as ManagerBasedRLEnv
participant Action as ThrustAction
participant Multirotor as Multirotor Asset
participant Thruster as Thruster Actuator
participant PhysX as PhysX Simulation
Note over Env,PhysX: Simulation Step
Env->>Action: process_actions(raw_actions)
Action->>Action: Apply scale/offset/clip
Note over Action: processed_actions = raw * scale + offset
Env->>Action: apply_actions()
Action->>Multirotor: set_thrust_target(processed_actions)
Note over Multirotor: Store in _data.thrust_target
Env->>Multirotor: write_data_to_sim()
Multirotor->>Multirotor: _apply_actuator_model()
loop For each thruster actuator
Multirotor->>Thruster: compute(control_action)
Note over Thruster: Read thrust_target
Thruster->>Thruster: Clamp to thrust_range
Thruster->>Thruster: Select tau (inc/dec)
Thruster->>Thruster: Compute mixing factor
Thruster->>Thruster: Integrate (Euler/RK4)
Note over Thruster: curr_thrust updated
Thruster-->>Multirotor: Return applied_thrust
Multirotor->>Multirotor: Update computed_thrust, applied_thrust
end
Multirotor->>Multirotor: _apply_combined_wrench()
Multirotor->>Multirotor: _combine_thrusts()
Note over Multirotor: wrench = allocation_matrix @ thrusts
Multirotor->>PhysX: apply_forces_and_torques_at_position()
Note over PhysX: Apply force/torque to base link
PhysX-->>Multirotor: Physics update
Multirotor->>Multirotor: update(dt)
Note over Multirotor: Read state from PhysX
@grzemal when running the example task, I get a lot of following warning
2025-12-17 09:50:35 [102,769ms] [Warning] [omni.usd] Warning: in GetInstanceIndices at line 2190 of /builds/omniverse/usd-ci/USD/pxr/usdImaging/usdImaging/pointInstancerAdapter.cpp -- ProtoIndex 1 out of bounds (prototypes size = 1) for (/Visuals/Command/body_pose, /Visuals/Command/body_pose.proto1_mesh_id0)
did you also experience them?
@grzemal when running the example task, I get a lot of following warning
2025-12-17 09:50:35 [102,769ms] [Warning] [omni.usd] Warning: in GetInstanceIndices at line 2190 of /builds/omniverse/usd-ci/USD/pxr/usdImaging/usdImaging/pointInstancerAdapter.cpp -- ProtoIndex 1 out of bounds (prototypes size = 1) for (/Visuals/Command/body_pose, /Visuals/Command/body_pose.proto1_mesh_id0)did you also experience them?
@pascal-roth just double-checked and i do not get such a warning, the only warning which I get and it is related to the Visual/Command :
2025-12-17T11:44:32Z [12,876ms] [Warning] [omni.physx.fabric.plugin] FabricManager::initializePointInstancer mismatched prototypes on point instancer: /Visuals/Command/goal_pose
@grzemal when running the example task, I get a lot of following warning
2025-12-17 09:50:35 [102,769ms] [Warning] [omni.usd] Warning: in GetInstanceIndices at line 2190 of /builds/omniverse/usd-ci/USD/pxr/usdImaging/usdImaging/pointInstancerAdapter.cpp -- ProtoIndex 1 out of bounds (prototypes size = 1) for (/Visuals/Command/body_pose, /Visuals/Command/body_pose.proto1_mesh_id0)did you also experience them?
@pascal-roth just double-checked and i do not get such a warning, the only warning which I get and it is related to the
Visual/Command:2025-12-17T11:44:32Z [12,876ms] [Warning] [omni.physx.fabric.plugin] FabricManager::initializePointInstancer mismatched prototypes on point instancer: /Visuals/Command/goal_pose
hm weird, then that must have something to do with the asset. Could anyone try on their PC to check if the same happens when they init the submodule? @Mayankm96 @ooctipus @AntoineRichard