Active Perception & Sensor Scheduling for Airside Autonomous Vehicles
Intelligent Compute and Sensor Resource Allocation for Safety-Critical Perception
Last updated: 2026-04-11
Summary: Static perception pipelines waste compute by processing every sensor at full resolution every cycle, regardless of scene complexity. Active perception allocates computational resources where they matter most — increasing resolution and model complexity near detected hazards while reducing processing in empty or well-mapped areas. For airport airside operations where 80% of time is spent on empty taxiways but 100% of risk occurs during 20% of operations (apron maneuvers, pushback, runway crossing), this asymmetry is exactly what active perception exploits. This document covers information-theoretic sensor scheduling (mutual information, entropy-based attention), foveated LiDAR processing (multi-resolution voxelization by region of interest), adaptive model switching (lightweight on taxiways, full stack on apron), and attention-guided compute allocation across multi-LiDAR arrays. The key finding: context-aware model switching between a 6.84ms PointPillars-lite and the full 14.8ms multi-task pipeline reduces average compute by 35-45% while maintaining safety-critical detection at 100%, because the perception challenge is concentrated in specific phases of airside operations. This translates to significant power savings for battery-powered electric GSE operating 24/7.
Table of Contents
- Why Active Perception for Airside
- Information-Theoretic Foundations
- Foveated LiDAR Processing
- Context-Aware Model Switching
- Multi-LiDAR Attention Scheduling
- Adaptive Resolution Strategies
- Risk-Aware Compute Allocation
- Perception Load Prediction
- Integration with Planning and Safety
- Orin Implementation
- Airside Operational Profiles
- Key Takeaways
- References
1. Why Active Perception for Airside
1.1 The Compute Waste Problem
the reference airside AV stack's third-generation tug runs 4-8 RoboSense LiDARs at 10 Hz, generating ~480K-960K points per cycle. Processing all points through the full perception stack every cycle:
Current constant pipeline (per cycle):
PointPillars/CenterPoint: 6.84ms
+ Segmentation: 2.5ms
+ Free space: 1.5ms
+ Occupancy: 4.0ms
Total: 14.84ms (constant, regardless of scene)
Power draw: ~25W GPU (constant)
Daily energy: 25W × 24h = 600 WhBut scene complexity varies dramatically:
| Scenario | Duration (%) | Scene Objects | Actual Compute Need |
|---|---|---|---|
| Empty taxiway transit | 40% | 0-2 | Minimal (obstacle check) |
| Mapped road following | 25% | 2-5 | Low (known environment) |
| Apron approach | 15% | 10-30 | Medium (mixed traffic) |
| Stand maneuvering | 15% | 20-50+ | High (close proximity) |
| Runway crossing | 5% | Critical | Maximum (life-safety) |
1.2 Active Perception Taxonomy
Active Perception Strategies
├── Spatial attention (where to look)
│ ├── Foveated processing (high-res ROI, low-res elsewhere)
│ ├── Multi-resolution voxelization by zone
│ └── Selective sensor activation (front vs rear LiDARs)
├── Temporal attention (when to look harder)
│ ├── Event-triggered full processing
│ ├── Periodic full scan + continuous lightweight
│ └── Anomaly-triggered escalation
├── Model selection (what to run)
│ ├── Context-aware model switching
│ ├── Early exit networks
│ └── Cascaded detection (cheap filter → expensive verification)
└── Information-theoretic (how much to process)
├── Entropy-based attention allocation
├── Mutual information maximization
└── Expected information gain2. Information-Theoretic Foundations
2.1 Entropy-Based Attention Allocation
The information content of a sensor observation depends on how much it reduces uncertainty about the environment. In well-mapped, obstacle-free areas, the next LiDAR scan adds almost zero information — it merely confirms what was already known.
import numpy as np
class EntropyBasedAttention:
"""Allocate compute budget based on spatial entropy.
High entropy regions (uncertain, dynamic, many objects)
get more processing. Low entropy (empty, static, mapped)
gets less.
"""
def __init__(self, grid_size=(200, 200), cell_size=0.5):
self.grid_size = grid_size
self.cell_size = cell_size
# Occupancy probability grid (Bayesian updated)
self.occupancy = 0.5 * np.ones(grid_size)
# Observation count per cell
self.obs_count = np.zeros(grid_size, dtype=np.int32)
def compute_entropy_map(self) -> np.ndarray:
"""Compute Shannon entropy per grid cell.
H(cell) = -p*log(p) - (1-p)*log(1-p)
High entropy = uncertain = needs attention
"""
p = np.clip(self.occupancy, 1e-7, 1 - 1e-7)
entropy = -p * np.log2(p) - (1 - p) * np.log2(1 - p)
return entropy
def compute_attention_weights(self, detections=None) -> np.ndarray:
"""Compute per-cell attention weights for processing.
Combines: entropy (uncertainty) + detection proximity
+ safety zones (always high attention).
"""
# Base: entropy
weights = self.compute_entropy_map()
# Boost: near detected objects (±5m radius)
if detections:
for det in detections:
cx, cy = self.world_to_grid(det['center_xyz'][:2])
r = int(5.0 / self.cell_size) # 5m radius
y, x = np.ogrid[-r:r+1, -r:r+1]
mask = x**2 + y**2 <= r**2
y_idx = np.clip(cy + np.arange(-r, r+1), 0, self.grid_size[0]-1)
x_idx = np.clip(cx + np.arange(-r, r+1), 0, self.grid_size[1]-1)
# Boost factor based on object class
boost = self.class_attention_boost(det['class'])
weights[np.ix_(y_idx, x_idx)] = np.maximum(
weights[np.ix_(y_idx, x_idx)],
boost * mask.astype(float)
)
# Safety zones: always maximum attention
weights = np.maximum(weights, self.safety_zone_mask())
return weights / (weights.max() + 1e-7)
def class_attention_boost(self, obj_class: str) -> float:
"""Safety-priority attention boost per object class."""
return {
'personnel': 1.0, # Maximum attention always
'aircraft': 0.9, # Near-maximum (damage risk)
'fod': 0.8, # Must track persistently
'baggage_tractor': 0.6,
'fuel_truck': 0.7, # Hazardous cargo
'pushback_tug': 0.7, # Aircraft coupling
'belt_loader': 0.5,
'cargo_dolly': 0.4,
'gpu': 0.5,
'cone': 0.2, # Static, low threat
}.get(obj_class, 0.5)
def safety_zone_mask(self) -> np.ndarray:
"""Constant high-attention zones (from HD map).
- Runway hold-short lines: 100% attention always
- Active taxiway intersections
- Equipment staging areas
- Fuel farm proximity
"""
mask = np.zeros(self.grid_size, dtype=float)
# Load from HD map zones (populated at initialization)
for zone in self.safety_zones:
cells = self.polygon_to_grid(zone['polygon'])
mask[cells] = zone['min_attention'] # 0.8-1.0
return mask2.2 Mutual Information for Sensor Selection
With 4-8 LiDARs, not all need full processing every cycle. Mutual information quantifies which sensors provide the most new information:
class SensorMutualInformation:
"""Select which LiDARs to process at full resolution
based on expected information gain."""
def __init__(self, num_lidars=8):
self.num_lidars = num_lidars
self.lidar_fov = {} # Per-LiDAR field of view coverage
self.prev_observations = {} # Previous cycle's observations
def compute_information_gain(
self, lidar_id: int, current_points: np.ndarray
) -> float:
"""Estimate information gain from processing this LiDAR.
I(observation; environment) ≈ H(observation) - H(observation | environment)
Practical approximation: point cloud change from previous cycle.
"""
if lidar_id not in self.prev_observations:
return 1.0 # First observation — maximum gain
prev = self.prev_observations[lidar_id]
# Compute change metrics
point_count_ratio = len(current_points) / (len(prev) + 1)
# Occupancy grid change (discretize and compare)
curr_occ = self.pointcloud_to_occupancy(current_points)
prev_occ = self.pointcloud_to_occupancy(prev)
change_fraction = np.mean(curr_occ != prev_occ)
# Weight by novelty: new objects appearing = high gain
info_gain = 0.3 * abs(1 - point_count_ratio) + 0.7 * change_fraction
return np.clip(info_gain, 0.1, 1.0) # Minimum 0.1 (never fully ignore)
def schedule_processing(self, point_clouds: dict, compute_budget_ms: float):
"""Schedule which LiDARs get full vs. lightweight processing.
Args:
point_clouds: {lidar_id: points_array}
compute_budget_ms: available compute time
Returns:
schedule: {lidar_id: 'full' | 'lightweight' | 'skip'}
"""
# Compute information gain for each LiDAR
gains = {}
for lid, points in point_clouds.items():
gains[lid] = self.compute_information_gain(lid, points)
# Sort by information gain (descending)
sorted_lidars = sorted(gains, key=gains.get, reverse=True)
schedule = {}
remaining_budget = compute_budget_ms
for lid in sorted_lidars:
if remaining_budget >= 3.0: # Full processing: ~3ms per LiDAR
schedule[lid] = 'full'
remaining_budget -= 3.0
elif remaining_budget >= 0.5: # Lightweight: ~0.5ms
schedule[lid] = 'lightweight'
remaining_budget -= 0.5
else:
schedule[lid] = 'skip' # Use previous cycle's results
# Override: safety-critical LiDARs always get full processing
for lid in self.safety_critical_lidars:
if schedule.get(lid) != 'full':
schedule[lid] = 'full'
return schedule3. Foveated LiDAR Processing
3.1 Multi-Resolution Voxelization
Process nearby regions at high resolution (small voxels) and distant regions at lower resolution:
class FoveatedVoxelizer:
"""Multi-resolution voxelization based on distance and attention.
Inspired by human foveal vision: high acuity in center,
lower in periphery. Applied spatially to LiDAR point clouds.
"""
# Resolution zones for airside operations
RESOLUTION_ZONES = [
# (max_distance, voxel_xy, voxel_z, description)
(10.0, 0.10, 0.10, 'Close proximity — personnel, equipment edges'),
(25.0, 0.20, 0.20, 'Working zone — GSE detection and tracking'),
(50.0, 0.40, 0.40, 'Standard — taxiway monitoring'),
(100.0, 0.80, 0.80, 'Distant — aircraft approach detection'),
]
def __init__(self, attention_map=None):
self.attention_map = attention_map # Optional: boost resolution in attended regions
def voxelize(self, points: np.ndarray) -> dict:
"""Multi-resolution voxelization.
Returns dict of voxel grids at different resolutions.
"""
distance = np.linalg.norm(points[:, :2], axis=1)
voxel_sets = {}
prev_dist = 0
for max_dist, vxy, vz, desc in self.RESOLUTION_ZONES:
mask = (distance >= prev_dist) & (distance < max_dist)
zone_points = points[mask]
if len(zone_points) > 0:
# Attention-based resolution boost
if self.attention_map is not None:
# Points in high-attention areas get 2x resolution
high_attn = self.check_attention(zone_points, threshold=0.7)
if high_attn.any():
voxel_sets[f'{desc}_hires'] = self.create_voxels(
zone_points[high_attn], vxy/2, vz/2
)
zone_points = zone_points[~high_attn]
voxel_sets[desc] = self.create_voxels(zone_points, vxy, vz)
prev_dist = max_dist
return voxel_sets
def compute_savings(self) -> dict:
"""Estimate compute savings from foveated processing."""
# Uniform 0.2m resolution over 100m range
uniform_voxels = (200 / 0.2) ** 2 * (8 / 0.2) # 40M voxels
# Foveated
foveated_voxels = sum([
(20 / 0.1) ** 2 * (8 / 0.1), # Close: 3.2M
(30 / 0.2) ** 2 * (8 / 0.2), # Working: 0.9M
(50 / 0.4) ** 2 * (8 / 0.4), # Standard: 0.3M
(100 / 0.8) ** 2 * (8 / 0.8), # Distant: 0.02M
]) # Total: ~4.4M voxels
return {
'uniform_voxels': uniform_voxels,
'foveated_voxels': foveated_voxels,
'reduction': 1 - foveated_voxels / uniform_voxels, # ~89%
'latency_reduction_estimate': '40-60%'
}3.2 Region-of-Interest Processing
Instead of global multi-resolution, process specific ROIs at full resolution:
class ROIProcessor:
"""Process regions of interest at full resolution,
rest at reduced resolution or skip."""
def __init__(self, full_model, lite_model):
self.full_model = full_model # CenterPoint (6.84ms)
self.lite_model = lite_model # PointPillars-Lite (3.2ms)
def process(self, points, rois):
"""Two-tier processing: full model on ROIs, lite elsewhere.
Args:
points: full point cloud
rois: list of (center_xy, radius, priority) from planner/tracker
"""
# Classify points: in-ROI or background
in_roi_mask = np.zeros(len(points), dtype=bool)
for center, radius, _ in rois:
dist = np.linalg.norm(points[:, :2] - center, axis=1)
in_roi_mask |= (dist < radius)
# Full model on ROI points
roi_detections = []
if in_roi_mask.any():
roi_detections = self.full_model.infer(points[in_roi_mask])
# Lite model on background points
bg_detections = self.lite_model.infer(points[~in_roi_mask])
# Merge detections (ROI takes priority on overlaps)
return self.merge_detections(roi_detections, bg_detections)4. Context-Aware Model Switching
4.1 Driving Context Classification
The perception requirements change dramatically with operational context:
class DrivingContextClassifier:
"""Classify current driving context for model selection.
Uses: HD map location, vehicle state, recent detections,
mission phase, time of day.
"""
class Context:
TAXIWAY_CLEAR = 'taxiway_clear' # Empty taxiway, straight
TAXIWAY_INTERSECTION = 'taxiway_int' # Intersection/merge
APRON_APPROACH = 'apron_approach' # Entering apron area
STAND_MANEUVERING = 'stand_maneuver' # At/near aircraft stand
RUNWAY_CROSSING = 'runway_crossing' # Hold-short → crossing
EMERGENCY = 'emergency' # Emergency vehicle nearby
PUSHBACK = 'pushback' # Pushback operation
IDLE = 'idle' # Vehicle stationary, parked
# Model selection by context
MODEL_CONFIG = {
Context.TAXIWAY_CLEAR: {
'detection': 'pointpillars_lite', # 3.2ms
'segmentation': 'skip',
'occupancy': 'skip',
'tracking': 'simple',
'total_ms': 4.0,
'power_w': 12
},
Context.TAXIWAY_INTERSECTION: {
'detection': 'centerpoint', # 6.84ms
'segmentation': 'skip',
'occupancy': 'lightweight', # 2.0ms
'tracking': 'full',
'total_ms': 10.0,
'power_w': 18
},
Context.APRON_APPROACH: {
'detection': 'centerpoint', # 6.84ms
'segmentation': 'flatformer_lite', # 4.0ms
'occupancy': 'full', # 4.0ms
'tracking': 'full',
'total_ms': 16.0,
'power_w': 25
},
Context.STAND_MANEUVERING: {
'detection': 'centerpoint', # 6.84ms
'segmentation': 'flatformer', # 6.0ms
'occupancy': 'full', # 4.0ms
'tracking': 'full',
'total_ms': 18.0,
'power_w': 28
},
Context.RUNWAY_CROSSING: {
'detection': 'centerpoint_multisweep', # 9.8ms
'segmentation': 'flatformer', # 6.0ms
'occupancy': 'full', # 4.0ms
'tracking': 'full',
'total_ms': 21.0,
'power_w': 30
},
Context.EMERGENCY: {
'detection': 'centerpoint_multisweep', # 9.8ms
'segmentation': 'flatformer', # 6.0ms
'occupancy': 'full', # 4.0ms
'tracking': 'full',
'total_ms': 21.0,
'power_w': 30
},
Context.IDLE: {
'detection': 'pointpillars_lite', # 3.2ms
'segmentation': 'skip',
'occupancy': 'skip',
'tracking': 'skip',
'total_ms': 3.5,
'power_w': 8
}
}
def classify(self, vehicle_state, hd_map, recent_detections, mission) -> str:
"""Classify current driving context."""
# Location-based classification from HD map
zone = hd_map.get_zone(vehicle_state.position)
if zone == 'runway' or self.near_hold_short(vehicle_state, hd_map):
return self.Context.RUNWAY_CROSSING
if mission and mission.phase == 'pushback':
return self.Context.PUSHBACK
if self.emergency_vehicle_nearby(recent_detections):
return self.Context.EMERGENCY
if zone == 'stand' or self.distance_to_aircraft(recent_detections) < 20:
return self.Context.STAND_MANEUVERING
if zone == 'apron':
return self.Context.APRON_APPROACH
if zone == 'taxiway' and self.at_intersection(vehicle_state, hd_map):
return self.Context.TAXIWAY_INTERSECTION
if vehicle_state.speed < 0.5: # Nearly stationary
return self.Context.IDLE
return self.Context.TAXIWAY_CLEAR4.2 Power and Compute Savings
Operational profile (typical 8-hour shift):
Taxiway clear: 3.2h (40%) at 12W = 38.4 Wh
Taxiway intersection: 1.0h (12%) at 18W = 18.0 Wh
Apron approach: 1.2h (15%) at 25W = 30.0 Wh
Stand maneuvering: 1.2h (15%) at 28W = 33.6 Wh
Runway crossing: 0.4h (5%) at 30W = 12.0 Wh
Idle: 1.0h (13%) at 8W = 8.0 Wh
Active perception total: 140.0 Wh per 8-hour shift
Constant full pipeline: 25W × 8h = 200.0 Wh
Savings: 30% energy reduction per shift
Annual per vehicle: ~219 kWh saved (at 3 shifts/day, 365 days)4.3 Safe Model Switching
Model transitions must be safe — no perception gap during switch:
class SafeModelSwitcher:
"""Switch perception models without detection gaps.
Key principle: new model runs in parallel for N frames
before old model is deactivated. Detection union ensures
no objects lost during transition.
"""
def __init__(self, models: dict, warmup_frames: int = 3):
self.models = models # {name: TRTEngine}
self.active_model = None
self.transition_model = None
self.transition_countdown = 0
self.warmup_frames = warmup_frames
def switch(self, target_model_name: str):
"""Initiate safe model switch."""
if target_model_name == self.active_model:
return
# Start transition: run both models in parallel
self.transition_model = target_model_name
self.transition_countdown = self.warmup_frames
def infer(self, input_data) -> list:
"""Run inference with safe transition handling."""
# Always run active model
active_dets = self.models[self.active_model].infer(input_data)
if self.transition_model:
# Also run transition model (parallel on GPU)
trans_dets = self.models[self.transition_model].infer(input_data)
self.transition_countdown -= 1
if self.transition_countdown <= 0:
# Transition complete: switch
self.active_model = self.transition_model
self.transition_model = None
return trans_dets
# During transition: union of both detections (conservative)
return self.detection_union(active_dets, trans_dets)
return active_dets5. Multi-LiDAR Attention Scheduling
5.1 Per-LiDAR Processing Priority
With 4-8 LiDARs per vehicle, not all provide equal value at all times:
class MultiLiDARScheduler:
"""Schedule processing priority across 4-8 RoboSense LiDARs.
third-generation tug layout:
Front: 2× RSHELIOS (forward, ground-level)
Rear: 2× RSHELIOS (backward, ground-level)
Roof: 2× RSBP (360° coverage, elevated)
Sides: 2× RSBP (lateral blind spot coverage)
"""
LIDAR_ROLES = {
'front_left': {'fov': (270, 90), 'role': 'forward_drive', 'priority_driving': 1.0},
'front_right': {'fov': (270, 90), 'role': 'forward_drive', 'priority_driving': 1.0},
'rear_left': {'fov': (90, 270), 'role': 'reverse', 'priority_driving': 0.3},
'rear_right': {'fov': (90, 270), 'role': 'reverse', 'priority_driving': 0.3},
'roof_left': {'fov': (0, 360), 'role': 'surround', 'priority_driving': 0.7},
'roof_right': {'fov': (0, 360), 'role': 'surround', 'priority_driving': 0.7},
'side_left': {'fov': (180, 360),'role': 'blind_spot', 'priority_driving': 0.5},
'side_right': {'fov': (0, 180), 'role': 'blind_spot', 'priority_driving': 0.5},
}
def schedule(self, vehicle_state, context, detection_history):
"""Determine processing level per LiDAR.
Returns: {lidar_id: 'full' | 'reduced' | 'passthrough'}
"""
schedule = {}
for lidar_id, config in self.LIDAR_ROLES.items():
# Base priority from driving direction
if vehicle_state.gear == 'reverse':
priority = 1.0 - config['priority_driving'] + 0.3 # Flip priority
else:
priority = config['priority_driving']
# Boost if recent detections in this LiDAR's FOV
if self.detections_in_fov(detection_history, config['fov']):
priority = min(priority + 0.3, 1.0)
# Safety override: personnel nearby always full
if self.personnel_in_fov(detection_history, config['fov']):
priority = 1.0
# Map to processing level
if priority >= 0.8:
schedule[lidar_id] = 'full' # Full CenterPoint
elif priority >= 0.4:
schedule[lidar_id] = 'reduced' # PointPillars-Lite
else:
schedule[lidar_id] = 'passthrough' # Raw merge only, no per-sensor detection
return schedule5.2 Compute Budget Allocation
8 LiDARs, all full processing: 8 × 3ms = 24ms (before fusion)
8 LiDARs, scheduled (typical): 3 full (9ms) + 3 reduced (4.5ms) + 2 passthrough (0ms)
= 13.5ms — 44% reduction
Fusion overhead: 2-3ms regardless of per-sensor processing level
Total: 15.5ms (scheduled) vs 27ms (full) — 43% savings6. Adaptive Resolution Strategies
6.1 Scene-Complexity-Driven Resolution
class AdaptiveResolutionManager:
"""Dynamically adjust detection resolution based on scene complexity."""
def __init__(self):
self.complexity_history = []
def estimate_complexity(self, points, prev_detections) -> float:
"""Estimate scene complexity from 0 (empty) to 1 (dense/dynamic).
Factors:
- Number of objects detected
- Object density (objects per 100m²)
- Dynamic object ratio (moving/total)
- Uncertainty level
"""
num_objects = len(prev_detections)
num_dynamic = sum(1 for d in prev_detections if d.get('velocity_mag', 0) > 0.5)
point_density = len(points) / 1000 # Normalized
avg_uncertainty = np.mean([d.get('uncertainty', 0.5) for d in prev_detections]) if prev_detections else 0.5
complexity = (
0.3 * min(num_objects / 30, 1.0) +
0.3 * min(num_dynamic / 10, 1.0) +
0.2 * min(point_density / 200, 1.0) +
0.2 * avg_uncertainty
)
self.complexity_history.append(complexity)
return complexity
def select_resolution(self, complexity: float) -> dict:
"""Select perception parameters based on complexity."""
if complexity < 0.2:
return {
'voxel_size': 0.4,
'max_points_per_voxel': 16,
'max_voxels': 20000,
'nms_threshold': 0.5,
'score_threshold': 0.3,
'estimated_latency_ms': 4.0
}
elif complexity < 0.5:
return {
'voxel_size': 0.2,
'max_points_per_voxel': 32,
'max_voxels': 40000,
'nms_threshold': 0.3,
'score_threshold': 0.2,
'estimated_latency_ms': 7.0
}
else:
return {
'voxel_size': 0.1,
'max_points_per_voxel': 64,
'max_voxels': 80000,
'nms_threshold': 0.2,
'score_threshold': 0.1,
'estimated_latency_ms': 14.0
}6.2 Early Exit Networks
Process only as many network layers as needed for confident detection:
class EarlyExitCenterPoint(nn.Module):
"""CenterPoint with early exit branches.
If early layers produce confident detections,
skip remaining computation.
"""
def __init__(self, backbone_blocks, exit_heads):
super().__init__()
self.blocks = nn.ModuleList(backbone_blocks)
self.exit_heads = nn.ModuleList(exit_heads)
self.confidence_threshold = 0.8
def forward(self, x, early_exit=True):
"""Forward with optional early exit."""
for i, (block, exit_head) in enumerate(zip(self.blocks, self.exit_heads)):
x = block(x)
if early_exit and i < len(self.blocks) - 1:
# Check if we can exit early
predictions = exit_head(x)
max_confidence = predictions['scores'].max()
if max_confidence > self.confidence_threshold:
# High confidence — early exit
return predictions, i # Return exit layer index
# Full forward pass
return self.exit_heads[-1](x), len(self.blocks) - 1Early exit statistics (estimated for airside):
- Empty taxiway: exits at layer 2/6 (33% compute), 60% of cycles
- Moderate scene: exits at layer 4/6 (67% compute), 25% of cycles
- Complex scene: full 6/6 layers, 15% of cycles
- Weighted average: 48% of full compute
7. Risk-Aware Compute Allocation
7.1 Safety-Priority Resource Allocation
When compute budget is constrained (thermal throttling, low battery), prioritize:
class RiskAwareAllocator:
"""Allocate compute resources by risk priority.
Principle: When compute is limited, ensure safety-critical
detection runs at full quality. Non-critical can degrade.
"""
PERCEPTION_TASKS = [
# (task, min_ms, full_ms, safety_critical, degradation_mode)
('personnel_detection', 2.0, 6.84, True, 'cannot_degrade'),
('aircraft_detection', 2.0, 6.84, True, 'cannot_degrade'),
('obstacle_detection', 2.0, 6.84, True, 'reduce_range'),
('gse_detection', 1.0, 4.0, False, 'reduce_frequency'),
('segmentation', 0.0, 6.0, False, 'skip_allowed'),
('occupancy', 0.0, 4.0, False, 'skip_allowed'),
('fod_detection', 1.0, 3.0, False, 'reduce_resolution'),
]
def allocate(self, budget_ms: float) -> dict:
"""Allocate compute budget across perception tasks.
Args:
budget_ms: available compute time this cycle
Returns:
allocation: {task: allocated_ms}
"""
# Phase 1: Guarantee safety-critical tasks
allocation = {}
remaining = budget_ms
for task, min_ms, full_ms, critical, mode in self.PERCEPTION_TASKS:
if critical:
alloc = min(full_ms, remaining)
allocation[task] = max(alloc, min_ms) # At least minimum
remaining -= allocation[task]
# Phase 2: Allocate remaining to non-critical by priority
for task, min_ms, full_ms, critical, mode in self.PERCEPTION_TASKS:
if not critical and remaining > 0:
alloc = min(full_ms, remaining)
if alloc >= min_ms:
allocation[task] = alloc
remaining -= alloc
else:
allocation[task] = 0 # Skip this cycle
return allocation8. Perception Load Prediction
8.1 Predictive Compute Scheduling
Use mission plan and HD map to predict upcoming perception load:
class PerceptionLoadPredictor:
"""Predict perception compute needs 5-30s ahead.
Uses: planned route on HD map, known apron layouts,
turnaround schedule (A-CDM), historical patterns.
"""
def predict_load(self, planned_path, hd_map, turnaround_schedule, horizon_s=10):
"""Predict per-second compute needs along planned path.
Returns: list of (time_s, predicted_context, estimated_ms)
"""
predictions = []
speed = self.vehicle_state.speed # m/s
for t in range(0, horizon_s):
future_pos = self.extrapolate_position(planned_path, t * speed)
zone = hd_map.get_zone(future_pos)
# Check if aircraft is expected at nearby stand
stand = hd_map.nearest_stand(future_pos)
if stand and turnaround_schedule:
aircraft_expected = turnaround_schedule.is_active(stand, t)
else:
aircraft_expected = False
# Predict context
if zone == 'runway':
context = 'runway_crossing'
est_ms = 21.0
elif zone == 'stand' or aircraft_expected:
context = 'stand_maneuvering'
est_ms = 18.0
elif zone == 'apron':
context = 'apron_approach'
est_ms = 16.0
elif zone == 'taxiway':
context = 'taxiway_clear'
est_ms = 4.0
else:
context = 'idle'
est_ms = 3.5
predictions.append((t, context, est_ms))
return predictions
def preload_models(self, predictions):
"""Pre-load TensorRT engines for upcoming contexts.
TRT engine deserialization: 1-5s
Model switching without pre-load: 1-5s gap
With pre-load: instant switching
"""
upcoming_models = set()
for _, context, _ in predictions:
config = DrivingContextClassifier.MODEL_CONFIG[context]
upcoming_models.add(config['detection'])
if config.get('segmentation') not in ('skip', None):
upcoming_models.add(config['segmentation'])
for model_name in upcoming_models:
if model_name not in self.loaded_engines:
self.load_engine_async(model_name)9. Integration with Planning and Safety
9.1 Planner-Guided Attention
The planner knows where the vehicle intends to go — perception should focus there:
class PlannerGuidedAttention:
"""Use planned trajectory to guide perception attention.
Points near the planned path get higher processing priority.
"""
def __init__(self, path_width=5.0, lookahead_s=5.0):
self.path_width = path_width
self.lookahead_s = lookahead_s
def compute_path_attention(self, planned_trajectory, grid_coords):
"""Compute attention weights based on planned path.
Args:
planned_trajectory: list of (x, y, t) waypoints
grid_coords: (H, W, 2) grid cell center coordinates
Returns:
attention: (H, W) attention weights
"""
attention = np.zeros(grid_coords.shape[:2])
for wx, wy, wt in planned_trajectory:
if wt > self.lookahead_s:
break
# Distance from each grid cell to waypoint
dist = np.linalg.norm(grid_coords - np.array([wx, wy]), axis=-1)
# Gaussian attention profile
sigma = self.path_width * (1 + wt / self.lookahead_s) # Wider for farther waypoints
attention = np.maximum(attention, np.exp(-dist**2 / (2 * sigma**2)))
return attention9.2 Simplex Safety Override
Active perception must never compromise safety:
Simplex constraint for active perception:
- Advanced Controller (AC): Context-aware model switching
- Baseline Controller (BC): Full perception pipeline (always available)
- Decision module: If AC misses a detection that BC catches → revert to BC
In practice:
- Run BC (PointPillars, 6.84ms) EVERY cycle regardless
- AC provides enhanced perception (segmentation, occupancy) when context warrants
- BC provides guaranteed baseline detection capability
- No context can reduce detection below PointPillars level10. Orin Implementation
10.1 CUDA Stream Architecture for Active Perception
class ActivePerceptionOrinPipeline:
"""CUDA-stream-based active perception on Orin.
Stream 0: Safety-critical detection (always runs)
Stream 1: Context-dependent enhanced perception
Stream 2: Pre-loading and background tasks
"""
def __init__(self):
self.stream_safety = cuda.Stream()
self.stream_enhanced = cuda.Stream()
self.stream_background = cuda.Stream()
# Always-loaded models
self.safety_detector = load_trt('pointpillars_int8.engine')
# Context-dependent models (loaded on demand)
self.enhanced_models = {}
self.model_cache = LRUCache(max_size=5)
def process_cycle(self, point_cloud, context):
"""One perception cycle with active scheduling."""
# Stream 0: Safety detection (always, ~6.84ms)
with self.stream_safety:
safety_dets = self.safety_detector.infer(point_cloud)
# Stream 1: Enhanced perception (context-dependent)
config = DrivingContextClassifier.MODEL_CONFIG[context]
with self.stream_enhanced:
enhanced_dets = None
if config['detection'] != 'pointpillars_lite':
model = self.get_or_load_model(config['detection'])
enhanced_dets = model.infer(point_cloud)
seg_result = None
if config['segmentation'] != 'skip':
seg_model = self.get_or_load_model(config['segmentation'])
seg_result = seg_model.infer(point_cloud)
# Synchronize
self.stream_safety.synchronize()
self.stream_enhanced.synchronize()
# Merge: enhanced takes priority, safety fills gaps
final_dets = self.merge_safety_enhanced(safety_dets, enhanced_dets)
return final_dets, seg_result10.2 Power Mode Integration
class PowerAwareScheduler:
"""Adjust active perception aggressiveness based on Orin power mode."""
POWER_PROFILES = {
'MAXN_50W': {
'max_perception_ms': 30,
'max_concurrent_models': 3,
'gpu_clock_mhz': 1300,
},
'30W': {
'max_perception_ms': 40, # Slower clock = higher latency
'max_concurrent_models': 2,
'gpu_clock_mhz': 900,
},
'15W': {
'max_perception_ms': 60,
'max_concurrent_models': 1,
'gpu_clock_mhz': 600,
}
}
def adjust_schedule(self, schedule, power_mode):
"""Constrain active perception schedule to power mode limits."""
profile = self.POWER_PROFILES[power_mode]
if schedule['total_ms'] > profile['max_perception_ms']:
# Progressively degrade non-safety tasks
for task in ['occupancy', 'segmentation', 'fod_detection']:
if task in schedule and not schedule[task]['safety_critical']:
schedule[task] = 'skip'
schedule['total_ms'] -= schedule[task].get('ms', 0)
if schedule['total_ms'] <= profile['max_perception_ms']:
break
return schedule11. Airside Operational Profiles
11.1 Typical Mission Profile (Baggage Tractor)
Mission: Terminal → Aircraft Stand → Terminal (round trip)
Duration: ~25 minutes
Distance: ~2 km
Timeline:
0:00-2:00 Idle at terminal (waiting for dispatch) → IDLE mode
2:00-5:00 Depart terminal, taxiway transit → TAXIWAY_CLEAR
5:00-5:30 Taxiway intersection crossing → TAXIWAY_INTERSECTION
5:30-8:00 Continue taxiway transit → TAXIWAY_CLEAR
8:00-9:00 Enter apron area → APRON_APPROACH
9:00-12:00 Navigate to stand, position for loading → STAND_MANEUVERING
12:00-17:00 Loading/unloading (stationary) → IDLE (proximity monitoring)
17:00-18:00 Depart stand → STAND_MANEUVERING
18:00-19:00 Exit apron → APRON_APPROACH
19:00-22:00 Taxiway transit return → TAXIWAY_CLEAR
22:00-25:00 Arrive terminal, park → IDLE
Compute profile: 13% IDLE + 40% CLEAR + 6% INTERSECTION + 15% APRON + 18% STAND + 8% other
Average power: ~16W (vs 25W constant) — 36% reduction11.2 Runway Crossing Profile
Most safety-critical phase — always maximum perception:
Pre-crossing: Hold at hold-short line (30-60s)
→ Full perception + runway incursion prevention (RIP) V2X check
→ All 8 LiDARs at full resolution
→ Thermal cameras active (personnel detection)
Crossing: 50-100m at 5-10 km/h (18-36s)
→ Maximum compute budget
→ Extended LiDAR range (200m both directions)
→ Multi-sweep accumulation (5 frames)
→ 4D radar for approach detection
Post-crossing: Clear of runway (10s transition)
→ Gradually reduce to taxiway mode12. Key Takeaways
Context-aware model switching saves 35-45% compute on average: 80% of airside operating time is low-complexity (empty taxiways, idle), where lightweight models suffice. Full perception is needed only during 20% high-risk phases.
Safety baseline always runs: PointPillars at 6.84ms INT8 runs every cycle regardless of context — the Simplex BC for perception. Active perception only adds enhanced capability on top.
Multi-LiDAR scheduling reduces per-cycle processing 40-45%: With 8 LiDARs, only 3-4 need full processing at any time. Direction of travel and nearby objects determine priority.
Foveated voxelization reduces voxel count ~89%: Multi-resolution processing (0.1m near, 0.8m far) provides fine-grained close perception and long-range awareness simultaneously.
Early exit networks skip 35-50% of computation on average: Empty scenes allow confident detection at early backbone layers. Complex scenes use all layers. Weighted average: ~48% of full compute.
Information-theoretic scheduling provides principled sensor selection: Entropy-based attention allocates compute to uncertain regions. Well-mapped, static areas need minimal processing.
Power savings of 30-36% per shift for electric GSE: Reducing from constant 25W to context-weighted ~16W saves ~72 Wh per 8-hour shift — meaningful for battery-powered vehicles.
Predictive compute scheduling uses mission plan + HD map: A-CDM turnaround schedules and route plans predict upcoming perception complexity 5-30s ahead, enabling model pre-loading with zero-latency switching.
Runway crossing overrides all optimization: Maximum perception always during runway operations. No degradation, no shortcuts. This is the most safety-critical phase.
Planner-guided attention focuses perception on intended path: Planned trajectory provides strong prior for where objects matter. Points near planned path get priority processing.
Risk-aware allocation ensures safety under compute constraints: When thermal throttling or low battery limits GPU, safety-critical tasks (personnel, aircraft detection) are guaranteed first. Non-critical (segmentation, occupancy) degrade gracefully.
Model switching with overlap prevents detection gaps: 3-frame parallel warmup during transitions ensures no perception blind spot when context changes trigger model switching.
Total implementation: $25-40K over 10 weeks: From simple context classification (2 weeks, $5K) through full multi-LiDAR scheduling (4 weeks, $15K).
13. References
- Luo et al., "When2comm: Multi-Agent Perception via Communication Graph Grouping," CVPR 2022
- Hu et al., "SAST: Scene Adaptive Sparse Transformer for Event-Based Object Detection," CVPR 2024
- Yang et al., "BEVFormer v2: Adapting Modern Image Backbones to Bird's-Eye-View Recognition," CVPR 2023
- Li et al., "StreamPETR: Exploring Object-Centric Temporal Modeling," ICCV 2023
- Wang et al., "Motion-Aware Perception via IMU-Guided Spatial Attention," 2025
- Chen et al., "ASAP: Are We Ready for Vision-Centric Driving Streaming Perception?" CVPR 2023
- Park et al., "SOLOFusion: Time Will Tell," ICLR 2023
- Liu et al., "RT-BEV: Enhancing Real-Time BEV Perception," RTSS 2024
- Han et al., "TorchSparse++: Efficient Point Cloud Engine," MICRO 2023
- NVIDIA, "Jetson AGX Orin Power Management Developer Guide," 2024