GCS_MAVLink: Fix build for builds with GPS_MAX_RECEIVERS = 1

This commit is contained in:
giacomo892 2021-05-16 18:36:24 +02:00 committed by Andrew Tridgell
parent fcba2a6e69
commit f486d7170c

View File

@ -4905,8 +4905,10 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
AP::gps().send_mavlink_gps_rtk(chan, 0); AP::gps().send_mavlink_gps_rtk(chan, 0);
break; break;
case MSG_GPS2_RAW: case MSG_GPS2_RAW:
#if GPS_MAX_RECEIVERS > 1
CHECK_PAYLOAD_SIZE(GPS2_RAW); CHECK_PAYLOAD_SIZE(GPS2_RAW);
AP::gps().send_mavlink_gps2_raw(chan); AP::gps().send_mavlink_gps2_raw(chan);
#endif
break; break;
case MSG_GPS2_RTK: case MSG_GPS2_RTK:
CHECK_PAYLOAD_SIZE(GPS2_RTK); CHECK_PAYLOAD_SIZE(GPS2_RTK);