Skip to content

Conversation

@Zwoelf12
Copy link

Description

This PR extends 3760 by introducing a navigation tasks for the ARL robot. The PR adds a confined cluttered environment, adds acceleration, velocity and position controllers + configs, extends the MDP and RL configs and adds a Variational Auto Encoder to generate image latents for observations. The PR depends on the MultiMeshRayCasterCamera introduced in PR 3298 (currently not merged in IsaacLab).

Changes

Type of Change

  • New feature (non-breaking change which adds functionality)
  • Documentation update (added docs/comments where applicable)

Files changed (high-level summary)

  • New files added:
    • source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/* (new task code and config, obstacle scene code and config)
    • source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/vae_model.pt
    • source/isaaclab/isaaclab/controllers/lee_acceleration_control_cfg.py
    • source/isaaclab/isaaclab/controllers/lee_acceleration_control.py
    • source/isaaclab/isaaclab/controllers/lee_velocity_control_cfg.py
    • source/isaaclab/isaaclab/controllers/lee_velocity_control.py
    • source/isaaclab/isaaclab/controllers/lee_position_control_cfg.py
    • ource/isaaclab/isaaclab/controllers/lee_position_control.py
  • Modified:
    • source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/* (added navigation specifics)
    • source/isaaclab/isaaclab/envs/mdp/actions/actions_cfg.py (added new action config)
    • source/isaaclab/isaaclab/envs/mdp/actions/thrust_actions.py (introduced new navigation action handling controller application)
  • Total diff (branch vs main, includes also unmerged changes of PR 3760 and PR 3298): 74 files changed, 8029 insertions, 88 deletions

Dependencies

  • The new drone task references standard repo-internal packages and Isaac Sim; no external pip packages required beyond the repo standard.

Checklist

  • I have read and understood the contribution guidelines
  • I have run the pre-commit checks with ./isaaclab.sh --format
  • I have made corresponding changes to the documentation
  • My changes generate no new warnings
  • 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.toml file
  • I have added my name to the CONTRIBUTORS.md or my name already exists there

kellyguo11 and others added 30 commits September 8, 2025 16:44
Signed-off-by: James Tigue <166445701+jtigue-bdai@users.noreply.github.com>
Signed-off-by: Mihir Kulkarni <mihirk284@gmail.com>
Signed-off-by: Mihir Kulkarni <mihirk284@gmail.com>
Signed-off-by: Mihir Kulkarni <mihirk284@gmail.com>
@github-actions github-actions bot added documentation Improvements or additions to documentation enhancement New feature or request asset New asset feature or request labels Oct 30, 2025
@Zwoelf12 Zwoelf12 changed the title Add multirotor vision-based navigation task Add multirotor vision-based navigation task and acceleration, velocity and position controllers Oct 30, 2025
Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This PR introduces a comprehensive multirotor vision-based navigation task for the ARL robot, extending IsaacLab's drone simulation capabilities. The changes add a new MultiMeshRayCasterCamera sensor for vision-based obstacle detection, three Lee geometric controllers (acceleration, velocity, position) for hierarchical drone control, and a thruster actuator system with realistic motor dynamics. The implementation includes a complete navigation environment with procedurally generated obstacle courses, VAE-based image latent encoding for efficient visual observations, and curriculum learning support. The changes establish a new package structure under manager_based/drone_arl/ with separate navigation and state-based control variants, comprehensive RL configurations for multiple frameworks (RSL-RL, RL-Games, SKRL), and proper integration with the existing IsaacLab framework while maintaining backward compatibility.

Important Files Changed

Filename Score Overview
source/isaaclab/isaaclab/utils/math.py 2/5 Adds inertia aggregation function with significant logic errors in physics calculations
source/isaaclab/isaaclab/envs/mdp/actions/thrust_actions.py 3/5 Introduces thrust and navigation actions with potential numerical instability from matrix inversion
source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/commands/drone_pose_command.py 3/5 Implements drone pose commands with inconsistent error calculation logic
.gitmodules 3/5 Adds external git submodule dependency requiring careful security and maintenance consideration
source/isaaclab/isaaclab/sensors/ray_caster/multi_mesh_ray_caster.py 4/5 Complex multi-mesh ray casting implementation with sophisticated memory management and cleanup logic
source/isaaclab/isaaclab/controllers/lee_acceleration_control.py 4/5 Implements Lee geometric controller with proper SE(3) control but includes some duplicated utilities
source/isaaclab/isaaclab/controllers/lee_velocity_control.py 4/5 Adds velocity controller with JIT functions that may duplicate existing math utilities
source/isaaclab/isaaclab/assets/articulation/multirotor.py 4/5 Comprehensive multirotor asset implementation with proper thruster management and error handling
source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/vae_model.pt 4/5 Pre-trained VAE model properly managed with Git LFS for vision-based navigation
source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/navigation/config/arl_robot_1/navigation_env_cfg.py 4/5 Comprehensive navigation environment configuration with sophisticated multi-component setup
All other files 4-5/5 Various infrastructure additions, configurations, and utilities that are well-structured and follow established patterns

Confidence score: 3/5

  • This PR requires careful review due to several complex implementations with potential issues in critical physics and control components
  • Score reduced due to significant logic errors in math utilities, potential numerical instabilities in action processing, and complex multi-mesh ray casting implementation that needs thorough validation
  • Pay close attention to math.py inertia calculations, thrust_actions.py matrix operations, and the new multi-mesh ray casting system's memory management and cleanup logic

Sequence Diagram

sequenceDiagram
    participant User
    participant Environment as ManagerBasedRLEnv
    participant Scene as InteractiveScene
    participant Multirotor as Multirotor
    participant Thruster as ThrusterActuator
    participant RayCaster as MultiMeshRayCasterCamera
    participant Controller as LeeVelController
    participant CommandManager as CommandManager
    participant RewardManager as RewardManager

    User->>Environment: env.reset()
    Environment->>Scene: reset scene
    Scene->>Multirotor: reset multirotor state
    Scene->>RayCaster: reset sensors
    Environment->>CommandManager: generate target pose
    CommandManager-->>Environment: target pose command

    loop Training/Simulation Step
        User->>Environment: env.step(action)
        
        Environment->>Environment: process_actions(action)
        Environment->>Controller: compute(velocity_command)
        Controller->>Controller: compute body wrench
        Controller-->>Environment: wrench_command
        
        Environment->>Multirotor: set_thrust_target(thrust_commands)
        Multirotor->>Thruster: compute actuator model
        Thruster->>Thruster: apply thrust dynamics
        Thruster-->>Multirotor: applied_thrust
        Multirotor->>Multirotor: _apply_combined_wrench()
        
        Environment->>Scene: step physics simulation
        Scene->>Scene: physics step
        
        Environment->>RayCaster: update depth camera
        RayCaster->>RayCaster: raycast against obstacles
        RayCaster-->>Environment: depth images
        
        Environment->>Environment: compute observations
        note over Environment: Extract VAE latents from depth
        
        Environment->>RewardManager: compute rewards
        RewardManager->>RewardManager: distance_to_goal_exp_curriculum
        RewardManager->>RewardManager: velocity_to_goal_reward
        RewardManager-->>Environment: reward values
        
        Environment->>Environment: check terminations
        note over Environment: Check collisions, timeouts
        
        Environment-->>User: obs, reward, done, info
    end
Loading

73 files reviewed, 77 comments

Edit Code Review Agent Settings | Greptile

"""Default force direction in body-local frame for thrusters. Defaults to Z-axis (upward)."""

allocation_matrix: list[list[float]] | None = None
"""allocation matrix for control allocation"""
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: Missing period at end of docstring for consistency with other docstrings

#
# SPDX-License-Identifier: BSD-3-Clause

"""Drone NTNU navigation environments."""
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: The docstring mentions 'NTNU' but the package path indicates 'ARL' robot - should this be 'Drone ARL navigation environments.'? Is the reference to NTNU intentional or should it match the ARL naming convention used in the package path?

#
# SPDX-License-Identifier: BSD-3-Clause

"""Configurations for drone NTNU navigation environments."""
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: The docstring refers to 'NTNU' but the directory structure and PR description indicate this is for 'ARL' navigation environments

.. code-block:: bash

# Usage
./isaaclab.sh -p source/extensions/omni.isaac.lab/test/sensors/check_multi_mesh_ray_caster.py --headless
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

syntax: Path in usage comment is incorrect - should match actual file location

mass_props=sim_utils.MassPropertiesCfg(mass=0.5),
collision_props=sim_utils.CollisionPropertiesCfg(),
visual_material=sim_utils.PreviewSurfaceCfg(
diffuse_color=(0.0 + i / args_cli.num_objects, 0.0, 1.0 - i / args_cli.num_objects)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: Potential division by zero when args_cli.num_objects is 0

},
)

if args_cli.asset_type == "allegro_hand":
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: Using args_cli.asset_type before AppLauncher initialization could potentially cause issues. Consider moving asset configuration after line 34. Is there a specific reason the asset configurations need to be defined before the AppLauncher initialization?

countdown -= 1
continue

data = scene["ray_caster"].data.ray_hits_w.cpu().numpy() # noqa: F841
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: The assigned data variable is unused. Consider either using the data for processing or removing the assignment entirely.

Comment on lines +249 to +302
triggered = True
countdown = 42

# Simulate physics
while simulation_app.is_running():

if count % 500 == 0:
# reset counter
count = 0
# reset the scene entities
# root state
root_state = scene["asset"].data.default_root_state.clone()
root_state[:, :3] += scene.env_origins
scene["asset"].write_root_pose_to_sim(root_state[:, :7])
scene["asset"].write_root_velocity_to_sim(root_state[:, 7:])

if isinstance(scene["asset"], Articulation):
# set joint positions with some noise
joint_pos, joint_vel = (
scene["asset"].data.default_joint_pos.clone(),
scene["asset"].data.default_joint_vel.clone(),
)
joint_pos += torch.rand_like(joint_pos) * 0.1
scene["asset"].write_joint_state_to_sim(joint_pos, joint_vel)
# clear internal buffers
scene.reset()
print("[INFO]: Resetting Asset state...")

if isinstance(scene["asset"], Articulation):
# -- generate actions/commands
targets = scene["asset"].data.default_joint_pos + 5 * (
torch.rand_like(scene["asset"].data.default_joint_pos) - 0.5
)
# -- apply action to the asset
scene["asset"].set_joint_position_target(targets)
# -- write data to sim
scene.write_data_to_sim()
# perform step
sim.step()
# update sim-time
sim_time += sim_dt
count += 1
# update buffers
scene.update(sim_dt)

if not triggered:
if countdown > 0:
countdown -= 1
continue

data = scene["ray_caster"].data.ray_hits_w.cpu().numpy() # noqa: F841
triggered = True
else:
continue
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: The triggered and countdown logic appears to serve no functional purpose in the simulation loop. Consider removing this code or clarifying its intent. What is the intended purpose of the triggered/countdown mechanism?

Comment on lines +145 to +149
base_link_position = ObsTerm(
func=mdp.generated_drone_commands,
params={"command_name": "target_pose", "asset_cfg": SceneEntityCfg("robot")},
noise=Unoise(n_min=-0.1, n_max=0.1),
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: observation term name base_link_position is misleading since it uses generated_drone_commands function which likely returns command/target information, not actual position. Should this observation term be renamed to better reflect that it contains target/command data rather than actual position?


@configclass
class NavigationVelocityFloatingObstacleEnvCfg(ManagerBasedRLEnvCfg):
"""Configuration for the locomotion velocity-tracking environment."""
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

style: class docstring mentions 'locomotion velocity-tracking' but this is a navigation task with obstacle avoidance

Copy link
Contributor

@greptile-apps greptile-apps bot left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Greptile Overview

Greptile Summary

This review covers only the changes made since the last review, not the entire PR. The most recent change refactors the curriculum system in source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py from terrain-based navigation to obstacle density management for drone navigation tasks. The modification removes the terrain_levels_vel function that was designed for ground-based terrain navigation and introduces two new functions: get_obstacle_curriculum_state for centralized state management and obstacle_density_curriculum for dynamically adjusting obstacle complexity based on drone performance. This change aligns with the PR's vision-based navigation focus, where obstacle density rather than terrain levels is the primary difficulty parameter. The new system stores curriculum state directly on the environment instance and adjusts difficulty based on goal achievement versus collision rates, supporting the overall drone navigation task architecture.

Important Files Changed

Filename Score Overview
source/isaaclab_tasks/isaaclab_tasks/manager_based/drone_arl/mdp/curriculums.py 4/5 Refactored curriculum system from terrain-based to obstacle density management for drone navigation

Confidence score: 4/5

  • This change is generally safe to merge with minimal risk of breaking existing functionality
  • Score reflects solid refactoring that removes unused terrain functionality and adds appropriate obstacle management, though the direct state storage approach needs attention
  • Pay close attention to the state storage pattern using env._obstacle_curriculum_state which bypasses typical encapsulation

1 file reviewed, 1 comment

Edit Code Review Agent Settings | Greptile

Comment on lines +101 to +104
difficulty_levels[env_ids] += move_up.long() - move_down.long()
difficulty_levels[env_ids] = torch.clamp(
difficulty_levels[env_ids], min=curriculum_state["min_difficulty"], max=curriculum_state["max_difficulty"] - 1
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

logic: : The max difficulty clamp uses max_difficulty - 1 instead of max_difficulty, which means the actual maximum achievable difficulty is one less than the specified maximum. Is this intentional to leave room for future expansion, or should it clamp to the full max_difficulty value? Is there a specific reason the maximum difficulty is clamped to max_difficulty - 1 rather than the full max_difficulty value?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

asset New asset feature or request documentation Improvements or additions to documentation enhancement New feature or request

Projects

None yet

Development

Successfully merging this pull request may close these issues.

8 participants