Skip to the content.

Architecture

This page walks the simulator’s components, the per-step pipeline, and the coordinate frames the codebase juggles between.

Components

   PX4 SITL                    rs_isaac_uav_sim
  ──────────                  ──────────────────
                            ┌──────────────────────┐
   ┌─────────┐   HIL_SENSOR │  scene_mavlink_sim   │
   │  px4    │ <─────────── │  (Isaac Sim app)     │
   │         │   HIL_GPS    │                      │
   │  EKF    │ <─────────── │  ┌──────────────┐    │
   │         │              │  │ DroneSimMgr  │    │
   │  ATT    │   HIL_       │  │              │    │
   │  CTRL   │   ACTUATOR   │  │  vehicle.py  │    │
   │         │   _CONTROLS  │  │              │    │
   │  ALLOC  │ ───────────> │  └──────┬───────┘    │
   └─────────┘              │         │            │
                            │  ┌──────▼───────┐    │
                            │  │ MAVLink HIL  │    │
                            │  │ backend      │    │
                            │  │ (TCP server) │    │
                            │  └──────────────┘    │
                            └──────────────────────┘

Per-step pipeline

The Isaac Sim main loop in scene_mavlink_sim.py is just:

while simulation_app.is_running():
    manager.step(physics_dt)        # our work
    world.step(render=False)        # PhysX integration
    if not args.headless:
        if _render_step >= _render_every_n:
            world.render()          # 50 Hz throttled
            _render_step = 0

Inside DroneSimManager.step():

  1. GPU readbackget_world_poses(usd=False) + get_velocities() are batched into a single torch.cat(...).cpu().numpy() so only one CUDA stream sync happens per step.

  2. Per-drone loop — for each drone, populate the VehicleState, run the stability detector (waits for the spawn drop to settle before switching sensors from “ideal” to “noisy”), update the IMU/baro/mag sensors, GPS at 50 Hz, send HIL_SENSOR + HIL_GPS + HIL_STATE_QUATERNION to PX4, recv_match the latest HIL_ACTUATOR_CONTROLS, compute body-frame force + torque from the rotor speeds, and rotate to world frame.

  3. GPU upload — copy the (N×3) world-frame force and torque arrays into pre-allocated CUDA tensors with a non-blocking copy_() and call apply_forces_and_torques_at_pos.

  4. PhysX world.step() — runs outside our step(), integrates the articulation forward by physics_dt.

The simulator-PX4 contract is strict lockstep: PX4 only advances when it receives HIL_SENSOR, and Isaac Sim only advances when it has a fresh IMU sample to send. The reported time_drift (sim-time growth ÷ PX4-time growth) stays at exactly 1.000 in healthy operation.

Coordinate frames

The codebase juggles three frames:

frame axes used by
ENU world x=East, y=North, z=Up Isaac Sim, USD assets
FLU body x=Forward, y=Left, z=Up dynamics, rotor positions
NED / FRD x=North, y=East, z=Down MAVLink, PX4, HIL_STATE_QUATERNION

VehicleState stores everything in ENU/FLU and exposes get_attitude_ned_frd() and get_linear_velocity_ned() for the MAVLink path. state.py is the single source of truth for the conversion math; test_state_rotations.py covers it.