Every parameter, what it does, safe ranges, and how to tune
All tuning lives in race_config.py — 7 dataclass sections, YAML serializable. Every value flows into race_pipeline.py, vision_pipeline.py, and the rest of the stack.
from race_config import RaceConfig
cfg = RaceConfig() # all defaults
cfg = RaceConfig.from_yaml("config.yaml") # from file (missing keys fall back to defaults)
cfg.save_yaml("my_config.yaml") # save current state
| Dataclass | Attribute | Purpose |
|---|---|---|
CameraSettings | cfg.camera | Resolution and FOV |
GateSettings | cfg.gate | Physical gate dimensions |
VisionSettings | cfg.vision | Detection mode, HSV, YOLO thresholds |
ControlSettings | cfg.control | PID gains, speed profile, thrust |
RaceSettings | cfg.race | Timing, distances, command rate |
SafetySettings | cfg.safety | Altitude, speed, tilt limits |
ConnectionSettings | cfg.connection | MAVSDK URL, camera source |
| Parameter | Default | Range | Description |
|---|---|---|---|
width | 640 | 320 – 1920 | Frame width in pixels |
height | 480 | 240 – 1080 | Frame height in pixels |
fov_h | 90.0 | 60 – 120 | Horizontal FOV in degrees |
fov_v | 60.0 | 40 – 90 | Vertical FOV in degrees |
| Parameter | Default | Range | Description |
|---|---|---|---|
width | 2.0 | 1.0 – 5.0 | Gate width in meters |
height | 2.0 | 1.0 – 5.0 | Gate height in meters |
| Parameter | Default | Range | Description |
|---|---|---|---|
mode | "unet" | "color" / "yolo" / "unet" | Detection pipeline mode |
hsv_lower | (40, 100, 100) | (0,0,0) – (179,255,255) | HSV lower bound (color mode only) |
hsv_upper | (90, 255, 255) | (0,0,0) – (179,255,255) | HSV upper bound (color mode only) |
color_preset | "green" | green / cyan / magenta / red / yellow / white | Quick HSV preset selector |
min_area | 500 | 100 – 5000 | Minimum contour area in pixels |
min_aspect | 0.3 | 0.1 – 0.5 | Minimum width/height ratio |
max_aspect | 3.0 | 2.0 – 10.0 | Maximum width/height ratio |
yolo_model_path | "gate_detector.pt" | path | YOLO weights file path |
yolo_conf_threshold | 0.5 | 0.1 – 0.9 | YOLO confidence cutoff |
color_preset instead of hand-tuning HSV bounds. The presets are tested across multiple lighting conditions.
| Parameter | Default | Previous | Safe Range | Too Low | Too High | Description |
|---|---|---|---|---|---|---|
kp_yaw | 50.0 | was 35 | 20 – 80 | Sluggish heading | Oscillation | Yaw gain (deg / bearing error) |
kp_pitch | 30.0 | was 20 | 10 – 50 | Won't pitch forward | Nosedive risk | Pitch gain |
kp_roll | 25.0 | was 15 | 5 – 40 | Slow turns | Roll oscillation | Bank angle gain |
kp_throttle | 0.45 | was 0.3 | 0.1 – 0.7 | Altitude drop in turns | Altitude oscillation | Thrust per vertical error |
cruise_pitch | −25.0 | was −12 | −35 to −5 | Slow | Crash into ground | Forward tilt when gate is far (deg) |
approach_pitch | −15.0 | was −5 | −25 to −2 | Slow approach | Overshoot gate | Forward tilt when close (deg) |
approach_dist | 2.0 | was 5 | 1.0 – 10.0 | Late braking | Slow from far out | Start braking distance (m) |
hover_thrust | 0.50 | — | 0.3 – 0.7 | Descends | Ascends | CALIBRATE PER VEHICLE |
seek_yaw_rate | 180.0 | was 25 | 20 – 360 | Slow search | Blur kills detection | Yaw speed when seeking (deg/s) |
lookahead_gates | 3 | — | 1 – 5 | Reactive only | Wasted compute | Gates to plan ahead |
| Parameter | Default | Previous | Safe Range | Too Low | Too High | Description |
|---|---|---|---|---|---|---|
command_hz | 120.0 | was 100 | 50 – 200 | Control lag | CPU-bound | Command rate (Hz) |
max_time_s | 480.0 | — | 120 – 600 | Short race | Wasted time | 8 min per spec |
max_no_detection | 15 | was 30 | 5 – 60 | False seek on blink | Fly blind too long | Frames before SEEK state |
approach_distance | 15.0 | was 30 | 5 – 50 | Late approach | Speed lost early | Enter approach mode (m) |
transit_distance | 1.5 | was 2.0 | 0.5 – 5.0 | Miss detection | False transit | Gate pass threshold (m) |
expected_gates | 0 | — | 0 – 50 | Finish by timeout | — | 0 = unknown |
seek_timeout | 30.0 | was 60 | 10 – 120 | False emergency | Stuck searching | Seconds before emergency |
approach_lost_timeout | 2.0 | was 5 | 0.5 – 10 | Over-reactive | Fly blind | Unused currently |
recovery_timeout | 0.0 | was 30 | 0 | — | Wastes time | ZERO = no recovery phase |
no_gate_finish_timeout | 30.0 | was 60 | 15 – 120 | Premature finish | Wastes time | Seconds after last gate |
| Parameter | Default | Previous | Safe Range | Description |
|---|---|---|---|---|
min_altitude | 0.5 | — | 0.5 – 2.0 | Floor check (meters AGL) |
max_altitude | 80.0 | — | 10 – 100 | Ceiling check (meters AGL) |
max_speed | 30.0 | was 20 | 10 – 50 | Speed limit (m/s) |
max_tilt | 70.0 | was 60 | 30 – 80 | Bank angle limit (degrees) |
geofence_radius | 500.0 | was 200 | 50 – 1000 | Arena boundary (meters) |
kp_throttle before reducing tilt. Tilt is speed.
Follow this order. Skipping steps leads to compound errors that are impossible to diagnose.
Load race_config.py with RaceConfig(). The defaults are a known-good aggressive baseline.
Hover test in the simulator. The drone should hold altitude with zero input. Adjust in increments of 0.02.
Does the drone spin and find gates? If it takes more than 3 seconds, increase seek_yaw_rate. If the camera is blurry during spin, decrease it.
Does it fly to the gate smoothly? Adjust kp_yaw and kp_pitch. Watch for overshoot (gain too high) or sluggish correction (gain too low).
Does it register gate passage? If it flies through without triggering transit, lower transit_distance. Check if distance_closing_count logic fires correctly.
Increase cruise_pitch by 5 degrees (more negative = faster). Run a full course. Check for crashes, missed gates, and altitude stability.
One parameter at a time, 10-20% changes. Log telemetry. Compare lap times.
| Symptom | Fix |
|---|---|
| Drone oscillates left-right | Lower kp_yaw and kp_roll by 20% |
| Drone flies past gates | Lower cruise_pitch (less negative), increase approach_dist |
| Drone doesn't detect transit | Lower transit_distance, check if distance_closing_count triggers |
| Drone spirals during seek | Lower seek_yaw_rate — camera motion blur kills detection |
| Drone slowly descends during approach | Increase hover_thrust by 0.05 |
| Gates detected but PnP distance is wrong | Check that gate.width and gate.height match the actual physical gates |
A complete config file with all sections. Save as config.yaml and load with RaceConfig.from_yaml("config.yaml").
camera:
width: 640
height: 480
fov_h: 90.0
fov_v: 60.0
gate:
width: 2.0
height: 2.0
vision:
mode: "unet"
hsv_lower: [40, 100, 100]
hsv_upper: [90, 255, 255]
color_preset: "green"
min_area: 500
min_aspect: 0.3
max_aspect: 3.0
yolo_model_path: "gate_detector.pt"
yolo_conf_threshold: 0.5
control:
kp_yaw: 50.0
kp_pitch: 30.0
kp_roll: 25.0
kp_throttle: 0.45
cruise_pitch: -25.0
approach_pitch: -15.0
approach_dist: 2.0
hover_thrust: 0.50
seek_yaw_rate: 180.0
lookahead_gates: 3
race:
command_hz: 120.0
max_time_s: 480.0
max_no_detection: 15
approach_distance: 15.0
transit_distance: 1.5
expected_gates: 0
seek_timeout: 30.0
approach_lost_timeout: 2.0
recovery_timeout: 0.0
no_gate_finish_timeout: 30.0
safety:
min_altitude: 0.5
max_altitude: 80.0
max_speed: 30.0
max_tilt: 70.0
geofence_radius: 500.0
connection:
sim_url: "udpin://0.0.0.0:14540"
camera_source: "synthetic"
camera_topic: "/camera"
camera_exe: "~/grandprix/gz_camera_sub"