GCS_Common: fix missing #if for CAMERA_FOV_STATUS

This commit is contained in:
Bob Long 2025-02-20 22:35:30 +11:00 committed by Peter Barker
parent 922f86a7ed
commit 8d427dd229

View File

@ -1075,7 +1075,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
{ MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
{ MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION},
{ MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS},
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
{ MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS},
#endif
{ MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS},
#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED
{ MAVLINK_MSG_ID_CAMERA_THERMAL_RANGE, MSG_CAMERA_THERMAL_RANGE},