The race controller is a finite state machine with six discrete phases. Every frame, exactly one phase is active. Transitions are deterministic — no priority conflicts, no deferred transitions.
Establishes connection to the flight controller via MAVSDK. Verifies telemetry streams (position, attitude, battery), arms the drone, and confirms pre-arm checks pass.
| Action | Detail |
|---|---|
| Connect | MAVSDK system.connect() — waits for heartbeat |
| Verify telemetry | Position, attitude, and battery streams must report non-null within 2s |
| Arm | Send arm command; verify is_armed == true |
TAKEOFFExecutes a vertical climb to the race altitude of 5m AGL. Throttle is managed by the altitude controller. No lateral movement.
SEEK_GATEThe drone enters a rapid yaw scan to locate the next gate. Vision pipeline processes every frame looking for gate detections.
| Parameter | Value |
|---|---|
| Yaw rate | 180 deg/s continuous rotation |
| Approach distance | 15m — gate must be within this range to trigger approach |
| Seek timeout | 30s with no detection → EMERGENCY |
| Finish timeout | 30s after last gate pass with no new gate → FINISHED |
APPROACH_GATEEMERGENCYProportional pursuit toward the tracked gate. The controller outputs pitch, yaw, and roll commands to close distance while keeping the gate centered in the frame.
| Behavior | Detail |
|---|---|
| Forward pitch | Proportional to gate distance — aggressive far, gentle close |
| Yaw tracking | Bearing error drives yaw correction |
| Roll tracking | Lateral bearing error drives roll compensation |
| Distance tracking | Records prev_gate_distance each frame for derivative (closing detection) |
| No-detection limit | max_no_detection = 15 frames |
TRANSIT_GATESEEK_GATE (direct, no recovery phase)no_detection_count resets to 0 and approach continues seamlessly.
A single-frame event marking successful gate passage. Not a sustained phase — it fires and immediately transitions.
| Action | Detail |
|---|---|
| Increment | gates_passed++ |
| Record time | Log split time for this gate |
| Reset tracker | Clear tracked gate data — fresh start for next gate |
| Cooldown | 0.3s cooldown to prevent double-counting same gate |
SEEK_GATEFINISHEDHover in place with zero velocity. The drone holds position and altitude. Triggered when SEEK_GATE times out after 30s without finding any gate.
Race complete. Triggered by one of two conditions:
Transit through a gate is not triggered by a simple distance threshold. Raw distance measurements are noisy — a jittery reading could falsely trigger transit while the drone is still meters away. Instead, the system requires consistent closing behavior before accepting a transit.
dist_delta = prev_distance - current_distancedist_delta > 0 (closing): increment distance_closing_countdist_delta ≤ 0 (opening or jitter): reset distance_closing_count = 0distance < 1.5m (transit distance threshold)closing_count ≥ 3 (consistently getting closer)APPROACH_GATERaw gate detections are noisy. The tracker applies Exponential Moving Average (EMA) smoothing to produce stable bearing, distance, and position estimates that the controller can act on without oscillation.
| Field | Type | Description |
|---|---|---|
bearing_x | float | Horizontal bearing to gate center (normalized, -1 to +1) |
bearing_y | float | Vertical bearing to gate center (normalized, -1 to +1) |
distance | float | Estimated distance to gate plane (meters) |
confidence | float | Detection confidence score (0.0 to 1.0) |
position | vec3 | 3D world-frame position estimate of gate center |
age | int | Number of frames this gate has been tracked |
stale | int | Frames since last detection update (0 = fresh this frame) |
smoothed = alpha * new_measurement + (1 - alpha) * prev_smoothed
| Parameter | Value | Rationale |
|---|---|---|
alpha | 0.65 | Racing default — fast response to gate movement, minimal lag. Higher than typical (0.3-0.5) because racing demands quick reaction. |
| Staleness limit | 10 frames | Gate is dropped after 10 consecutive frames with no detection. At 120Hz, this is ~83ms. |
| Max tracking distance | 80m | Detections beyond 80m are discarded — too unreliable for tracking. |
Frame N: detection arrives → stale = 0, EMA update applied
Frame N+1: no detection → stale = 1, use last smoothed values
Frame N+2: no detection → stale = 2, use last smoothed values
...
Frame N+9: no detection → stale = 9, use last smoothed values
Frame N+10: no detection → stale = 10, GATE DROPPED — tracker cleared
Two control modes are available, selectable per-mission. Attitude mode is the default for aggressive racing; velocity body mode is available for smoother, more conservative approaches.
Sends SET_ATTITUDE_TARGET MAVLink messages. Direct control over roll, pitch, yaw rate, and thrust. No position or velocity controller in the loop — the race code is the outer controller.
| Gains | |
|---|---|
kp_yaw | 50 — deg/s per unit bearing error |
kp_pitch | 30 — degrees per unit distance error |
kp_roll | 25 — degrees per unit lateral error |
kp_throttle | 0.45 — thrust per unit altitude error |
| Key Setpoints | |
|---|---|
| Cruise pitch | -25 deg — aggressive forward tilt during approach |
| Approach pitch (close) | -15 deg at 2m distance — late braking |
| Seek yaw rate | 180 deg/s — full rotation every 2 seconds |
| Limits (Safety Clamps) | |
|---|---|
| Pitch | [-45, +15] deg |
| Roll | [-45, +45] deg |
| Thrust | [0.15, 0.85] (normalized 0-1) |
Sends SET_POSITION_TARGET_LOCAL_NED with velocity setpoints in the body frame. The flight controller's velocity PID handles the inner loop, giving smoother trajectories at the cost of peak speed.
| Velocity Gains | |
|---|---|
| Forward (body-X) | Proportional to gate distance, max 15 m/s |
| Lateral (body-Y) | 5.0 m/s per unit horizontal bearing error |
| Vertical (body-Z) | 3.0 m/s per unit vertical bearing error |
| Yaw rate | 80 deg/s per unit bearing error |
The race loop targets 120Hz (8.33ms per frame). Every millisecond matters — a frame overrun means stale commands and degraded tracking. Below is the per-frame budget breakdown.
| Stage | Time | Notes |
|---|---|---|
| Camera capture | ~1.0 ms | USB3 frame grab, pre-allocated buffer |
| U-Net inference | ~5.0 ms | Gate segmentation network, FP16 on GPU |
| RANSAC corner extraction | ~1-3 ms | Fit gate corners from segmentation mask; varies with mask complexity |
| PnP solve | ~0.5 ms | solvePnP with 4 corner correspondences → distance + bearing |
| State machine + controller | ~0.5 ms | Phase logic, EMA update, command computation |
| MAVLink send | ~0.1 ms | Serialize and transmit attitude/velocity target |
| Total | ~8-10 ms |
Fits 120Hz with margin; RANSAC is the variable component |
The main async loop runs at 120Hz. Each iteration follows a strict pipeline: sense, decide, act. No deferred work, no background threads for control — everything is synchronous within the frame.
async def race_loop():
# Initialize state machine
phase = Phase.INIT
gates_passed = 0
tracked_gate = None
prev_gate_distance = None
distance_closing_count = 0
no_detection_count = 0
last_transit_time = 0
transit_cooldown = 0.3 # seconds
while phase not in (Phase.FINISHED, Phase.EMERGENCY):
frame_start = time.monotonic()
# ── SENSE ──────────────────────────────────────
telemetry = await get_telemetry() # attitude, position, velocity
frame = await get_frame() # camera capture (~1ms)
detection = detect_gates(frame) # U-Net + RANSAC + PnP (~7ms)
# ── TRACK ──────────────────────────────────────
if detection:
tracked_gate = ema_update(tracked_gate, detection, alpha=0.65)
tracked_gate.stale = 0
no_detection_count = 0
else:
if tracked_gate:
tracked_gate.stale += 1
if tracked_gate.stale >= 10:
tracked_gate = None # drop stale gate
no_detection_count += 1
# ── DECIDE (state machine) ─────────────────────
if phase == Phase.INIT:
if telemetry.armed:
phase = Phase.TAKEOFF
elif phase == Phase.TAKEOFF:
if telemetry.altitude >= 5.0:
phase = Phase.SEEK_GATE
elif phase == Phase.SEEK_GATE:
if tracked_gate and tracked_gate.distance < 15.0:
phase = Phase.APPROACH_GATE
distance_closing_count = 0
elif seek_timeout_exceeded(30):
phase = Phase.EMERGENCY
elif gates_passed > 0 and since_last_transit() > 30:
phase = Phase.FINISHED
elif phase == Phase.APPROACH_GATE:
# Distance derivative for transit detection
if tracked_gate and prev_gate_distance:
dist_delta = prev_gate_distance - tracked_gate.distance
if dist_delta > 0:
distance_closing_count += 1
else:
distance_closing_count = 0
if tracked_gate:
prev_gate_distance = tracked_gate.distance
# Check transit conditions
if (tracked_gate
and tracked_gate.distance < 1.5
and distance_closing_count >= 3
and tracked_gate.stale == 0
and time.monotonic() - last_transit_time > transit_cooldown):
phase = Phase.TRANSIT_GATE
# Lost gate → back to SEEK (no recovery phase)
elif no_detection_count >= 15:
phase = Phase.SEEK_GATE
tracked_gate = None
prev_gate_distance = None
elif phase == Phase.TRANSIT_GATE:
gates_passed += 1
last_transit_time = time.monotonic()
log_split_time(gates_passed)
tracked_gate = None # reset tracker
prev_gate_distance = None
distance_closing_count = 0
if gates_passed >= expected_gates:
phase = Phase.FINISHED
else:
phase = Phase.SEEK_GATE
# ── ACT ────────────────────────────────────────
command = compute_command(phase, tracked_gate, telemetry)
await send_command(command) # MAVLink (~0.1ms)
# ── RATE LIMIT ─────────────────────────────────
elapsed = time.monotonic() - frame_start
await asyncio.sleep(max(0, 1/120 - elapsed)) # 120Hz target
gates_passed, resets the tracker, and immediately transitions to SEEK_GATE (or FINISHED). It never persists across multiple frames.
| Approach distance | 15m |
| Transit distance | 1.5m |
| Closing frames req. | 3 |
| Transit cooldown | 0.3s |
| Max no-detection | 15 frames |
| Stale gate drop | 10 frames |
| Seek timeout | 30s |
| Finish timeout | 30s |
| Max tracking dist. | 80m |
| EMA alpha | 0.65 |
| Pitch range | [-45, +15] deg |
| Roll range | [-45, +45] deg |
| Thrust range | [0.15, 0.85] |
| Cruise pitch | -25 deg |
| Close pitch | -15 deg @ 2m |
| Seek yaw rate | 180 deg/s |
| Max forward vel. | 15 m/s |
| Loop rate | 120 Hz |
| Race altitude | 5m AGL |