Skip to content

Conversation

@dengyuchenkit
Copy link

@dengyuchenkit dengyuchenkit commented Jan 14, 2026

Description

This PR adds support to load a USD background in locomanipulation SDG pipeline.

  1. Add parameter to load NuRec asset: usd file for rendering, mesh for collision detection, and occupancy map for path planning.
  2. Instantiates the first table in the freespace of the background occupancy map. It resets robot/object position according to table position. It also writes the default state for robot/object state, so these states are correct when resetting scene due to termination.
  3. Add a NavigationScene data wrapper class for navigation scenes, so that when setup_navigation_scene fails, it returns None, instead of (None, None, ..)
  4. Add a termination condition object_too_far_from_robot, to check if robot picks up the wheel.

It was tested by:

Generate locomanipulation SDG data with the hand_hold-endeavor-wormhole dataset at: https://huggingface.co/datasets/nvidia/PhysicalAI-Robotics-NuRec/tree/main

./isaaclab.sh -p scripts/imitation_learning/locomanipulation_sdg/generate_data.py \
   --device cpu \
   --kit_args="--enable isaacsim.replicator.mobility_gen" \
   --task="Isaac-G1-SteeringWheel-Locomanipulation" \
   --dataset ./datasets/generated_dataset_g1_locomanip.hdf5 \
   --num_runs 1 \
   --lift_step 60 \
   --navigate_step 130 \
   --enable_pinocchio \
   --output_file ./datasets/generated_dataset_g1_locomanipulation_sdg.hdf5 \
   --enable_cameras \
   --background_usd_path <PATH_TO_USD_ASSET>/stage.usdz \
   --background_occupancy_yaml_file <PATH_TO_USD_ASSET>/occupancy_map.yaml

Type of change

  • New feature (non-breaking change which adds functionality)

Screenshots

locomanipulation_sdg_usd_background1 locomanipulation_sdg_usd_background2

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

@github-actions github-actions bot added the isaac-mimic Related to Isaac Mimic team label Jan 14, 2026
@greptile-apps
Copy link
Contributor

greptile-apps bot commented Jan 14, 2026

Greptile Summary

This PR adds support for loading USD background scenes in the locomanipulation SDG pipeline. It enables instantiating packing tables within background freespace and projecting initial robot/object states from input episodes into the environment.

Key changes:

  • Added command-line arguments for --background_usd_path, --background_occupancy_yaml_file, and --high_res_video
  • Refactored scene setup to conditionally handle background assets vs. default environment
  • Implemented state projection functions to transform robot and object poses into the new environment
  • Enhanced navigation scene setup with fixture randomization in background freespace
  • Added termination condition for detecting failed object pickups (object_too_far)
  • Improved occupancy map handling to treat unknown areas as occupied
  • Added bounds checking for path planning endpoints

Critical Issues Found:

  • Multiple functions (project_robot_state_into_env, project_object_state_into_env) reference global variable input_episode_data without it being passed as a parameter, causing NameError at runtime
  • NavigationScene class lacks @dataclass decorator but is instantiated with keyword arguments
  • Argparse type=bool doesn't work correctly - should use action="store_true"
  • Background path check uses != "" instead of is not None for None default values

Confidence Score: 0/5

  • This PR contains critical bugs that will cause runtime failures
  • Multiple NameError exceptions will occur due to missing function parameters, NavigationScene instantiation will fail without @dataclass, and argparse boolean handling is broken. These are blocking issues that prevent the feature from working.
  • Pay close attention to scripts/imitation_learning/locomanipulation_sdg/generate_data.py which contains all the critical bugs

Important Files Changed

Filename Overview
scripts/imitation_learning/locomanipulation_sdg/generate_data.py Multiple critical bugs: global variable usage without parameters, incorrect argparse type, missing @dataclass decorator, and wrong None check
source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/envs/g1_locomanipulation_sdg_env.py Added background asset loading and camera configuration methods, restructured scene setup to be conditional on background asset presence
source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/occupancy_map_utils.py Changed occupancy mask logic to treat unknown areas as occupied and refactored bounds checking into separate method
source/isaaclab_mimic/isaaclab_mimic/locomanipulation_sdg/path_utils.py Added bounds checking for end point pixels before path planning to prevent index out of bounds errors

Sequence Diagram

sequenceDiagram
    participant User
    participant Main
    participant Env as G1LocomanipulationSDGEnv
    participant Scene as setup_navigation_scene
    participant Fixtures as SceneFixtures
    participant Occupancy as OccupancyMap
    participant PathPlanner as plan_path
    participant StateProj as project_*_state_into_env
    
    User->>Main: Run with --background_usd_path & --background_occupancy_yaml_file
    Main->>Env: Create environment with cfg
    Env->>Env: add_background_asset(background_usd_path)
    Env->>Env: add_robot_pov_cam(height, width)
    Env->>Env: _setup_background_mesh()
    Note over Env: Hide mesh, enable collision
    
    Main->>Scene: setup_navigation_scene(env, input_episode_data)
    Scene->>Env: get_background_fixture()
    Env-->>Scene: background_fixture with occupancy_map
    
    alt Background exists
        Scene->>Occupancy: Get background occupancy map
        Scene->>Fixtures: Randomize start, end, obstacles in freespace
        loop For each fixture
            Fixtures->>Fixtures: place_randomly()
            Fixtures->>Scene: sync_simulation_state()
            Scene->>Occupancy: merge_occupancy_maps()
        end
    else No background
        Scene->>Occupancy: Create empty occupancy map
        Scene->>Fixtures: Randomize end and obstacles only
    end
    
    Scene->>StateProj: project_robot_state_into_env()
    StateProj->>Env: Transform and write robot pose/joints
    Scene->>StateProj: project_object_state_into_env()
    StateProj->>Env: Transform and write object pose
    
    Scene->>PathPlanner: plan_path(start, end, occupancy_map)
    PathPlanner-->>Scene: base_path (waypoints)
    
    alt Path valid (>2 points)
        Scene-->>Main: NavigationScene
        Main->>Main: Execute state machine with navigation
    else Path invalid
        Scene-->>Main: None (failure)
        Main->>Main: Retry with different demo
    end
Loading

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.

9 files reviewed, 6 comments

Edit Code Review Agent Settings | Greptile

@dengyuchenkit dengyuchenkit force-pushed the ydeng/usd_background branch 2 times, most recently from 84b712f to 500a157 Compare January 20, 2026 22:05
@github-actions github-actions bot added the documentation Improvements or additions to documentation label Jan 20, 2026


def sync_simulation_state(env: LocomanipulationSDGEnv) -> None:
"""Push USD pose updates into physics, advance the sim, and sync back."""
Copy link
Contributor

Choose a reason for hiding this comment

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

can you please follow the docstring style for arguments as well? we have some guidelines documented here - https://isaac-sim.github.io/IsaacLab/main/source/refs/contributing.html

return torch.any(
torch.max(torch.norm(net_contact_forces[:, :, sensor_cfg.body_ids], dim=-1), dim=1)[0] > threshold, dim=1
)
)
Copy link
Contributor

Choose a reason for hiding this comment

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

please run the formatter with ./isaaclab.sh -f

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

Labels

documentation Improvements or additions to documentation isaac-mimic Related to Isaac Mimic team

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants