VADR-TS-002 Issue 00.02 (NT, 2026-05-08) added the camera intrinsics, the vision stream protocol, and the gate / drone dimensions — all of which were "TBD" in TS-001. It also removed ODOMETRY from the supported MAVLink message set. This page is the single source of truth for what the new spec says, what was in our code that's now wrong, and what was changed on 2026-05-12 to fix it.
Reference: 260508_Technical_Spec_0002.pdf at repo root. Diff against TS-001 below.
TS-001 §4.6 said "Vision stream parameters will be provided in a separate specification." TS-002 §4.6 fills that in. Client must implement a UDP listener that reassembles JPEG from chunked datagrams.
Per-packet header layout (Python struct format: <I H H I I Q):
| Field | Type | Size | Purpose |
|---|---|---|---|
| frame_id | uint32 | 4 B | Sequence ID for the image frame |
| chunk_id | uint16 | 2 B | Packet index within the frame (0 … total_chunks − 1) |
| total_chunks | uint16 | 2 B | Packets needed to reconstruct |
| jpeg_size | uint32 | 4 B | Total reassembled JPEG byte length |
| payload_size | uint32 | 4 B | JPEG bytes in this packet |
| sim_time_ns | uint64 | 8 B | Simulator epoch timestamp (ns) |
Implementation drops stale partial frames when a newer frame's first chunk arrives, and caps in-flight frame buffers. Loopback smoke test (2-chunk JPEG): decoded back to identical 360×640×3 BGR.
TS-001 left the camera parameters undefined. TS-002 §3.8 pins them. The 20° upward pitch is new public info.
| Resolution | 640 × 360 px |
| fx, fy | 320, 320 |
| cx, cy | 320, 180 |
| Distortion | none (pure pinhole) |
| Camera → body | pitched 20° UPWARD about body Y (NED) |
| Body → IMU | identity |
The 20° tilt is consequential — gates appear above the optical axis, which the PnP-to-NED transform must account for. The _cam_to_body_rotation() helper in course_mapper.py applies an R_tilt rotation about body Y; cam_tilt_rad default is now math.radians(20.0).
vision_pipeline.py (CameraConfig), race_config.py (CameraSettings), drone_mpc_foundation.py (DroneParams), course_mapper.py (CourseMapperConfig.cam_tilt_rad), vq1_completion_pilot.py (CameraIntrinsics defaults), train_apex.py (CAMERA_* constants), synth_aigp_gates.py (renderer FoV constants).
TS-002 §3.7 specifies both the outer frame (the visible blue border) and the inner aperture (what the drone flies through). PnP targets the inner aperture — sharper, well-defined edges.
| Element | Width | Height | Depth |
|---|---|---|---|
| Outer frame | 2700 mm | 2700 mm | 260 mm |
| Inner aperture | 1500 mm | 1500 mm | 260 mm |
| Border on each side | 600 mm (with 140 mm corner bevel) | ||
Drone chassis is 280 × 280 × 160 mm — clearance per axis at the inner aperture is ~1.22 m wall-to-wall. That's the corridor the controller has to thread.
TS-001 listed ODOMETRY in §4.3. TS-002 removed it. The supported sim→client message set is now:
| HEARTBEAT | connection status |
| ATTITUDE | vehicle attitude (Euler / quat) |
| HIGHRES_IMU | body-frame accel + gyro (FRD) |
| TIMESYNC | clock alignment |
Client→sim control: SET_POSITION_TARGET_LOCAL_NED, SET_ATTITUDE_TARGET. Command rate < 100 Hz, heartbeat ≥ 2 Hz, physics 120 Hz.
Our response in mavsdk_bridge.py:
_subscribe_odometry() and its call site in connect()InertialIntegrator — dead-reckons NED position and velocity from HIGHRES_IMU + ATTITUDE using gravity-corrected Euler integration: a_world = R(q) · a_body + g_nedarm() calls estimator.start() so LOCAL_NED origin = drone position at arming time (per §3.8)SimBridge.apply_position_correction(pos_ned, alpha) — public hook for gate-PnP fixes to bound driftFullState.position_ned and velocity_ned properties still work; consumers don't need to changeSmoke tests passed: stationary level drone → zero NED drift over 8.3 s. 1 m/s² body-forward for 1 s → 0.99 m/s NED north, 0.49 m position (correct gravity cancellation + Euler integration).
TS-002 §3.8 states VFoV = 90°, but fy = 320 with image height = 360 implies VFoV = 2·atan(180/320) ≈ 58.72° and HFoV = 2·atan(320/320) = 90°. The two can't both be true.
Clarification email drafted in documents/vadr-ts-002-clarification-draft.md, sent to NT (author of the camera revision). If they confirm interpretation (b) — true VFoV = 90° with revised intrinsics — we'll need a second pass on synth FoV constants, the renderer, PnP K matrix, and retraining. All the existing tasks already split this dependency cleanly.
| File | Change |
|---|---|
camera_adapter.py | + UDPVisionCamera class (UDP:5600, JPEG-chunk reassembly), wired into create_camera |
mavsdk_bridge.py | − ODOMETRY subscription. + InertialIntegrator + apply_position_correction hook. Module docstring rewritten for TS-002. |
vision_pipeline.py | CameraConfig rewritten: 640×360, fx=fy=320, cx=320 cy=180, tilt_deg=20.0. GATE_OUTER_* + GATE_FRAME_DEPTH added. GATE_WIDTH/HEIGHT → 1.5. |
race_config.py | CameraSettings updated to spec. GateSettings + outer_width, outer_height, depth. |
imu_gate_predictor.py | GATE_WIDTH/HEIGHT 2.0 → 1.5 |
drone_mpc_foundation.py | Camera fields converted from FoV-derived to direct intrinsics. cam_tilt 0° → 20°. |
course_mapper.py | cam_tilt_rad default → math.radians(20.0) |
vq1_completion_pilot.py | Placeholder intrinsics fixed (height 480→360, cy 240→180). CameraIntrinsics gains tilt_deg field. |
synthetic_aperture_depth.py | GATE_WIDTH/HEIGHT 2.0 → 1.5 |
synth_aigp_gates.py | HFoV 120°→90°, VFoV 90°→58.72°. --imgsz default 480→360. GATE_OUTER_M constant added. Module docstring rewritten for TS-002. |
train_apex.py | CAMERA_TILT_DEG 45°→20°. FoV constants matched to spec. Image size constants added. |
documents/vadr-ts-002-clarification-draft.md. Asks: is "VFoV = 90°" a label typo or intent?dataset_gates_synthetic* was rendered at the old 640×480 / 120°×90° FoV / 45° tilt. New geometry → new render → new training run. Multi-hour GPU job; intentionally not auto-kicked.
course_mapper.py → SimBridge.apply_position_correction. The integrator is open-loop; without gate-PnP fixes it'll drift over the 8-minute window.