AP_Camera: correct compilation when AP_CAMERA_RELAY_ENABLED is 0

... like on skyviper-v2450
This commit is contained in:
Peter Barker 2024-01-03 11:59:44 +11:00 committed by Andrew Tridgell
parent ed1ae3b5f1
commit 8fb1f6f02c

View File

@ -781,11 +781,13 @@ bool AP_Camera::get_legacy_relay_index(int8_t &index) const
// Copter, Plane, Sub and Rover all have both relay and camera and all init relay first
// This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.4
for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {
#if AP_CAMERA_RELAY_ENABLED
if ((CameraType)_params[i].type.get() == CameraType::RELAY) {
// Camera was hard coded to relay 0
index = 0;
return true;
}
#endif
}
return false;
}