diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c2af85c496..7710290368 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -20,6 +20,7 @@ #include #include #include +#include #include "AP_GPS_NOVA.h" #include "AP_GPS_ERB.h" @@ -258,6 +259,9 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // constructor AP_GPS::AP_GPS() { + static_assert((sizeof(_initialisation_blob) * (CHAR_BIT + 2)) < (4800 * GPS_BAUD_TIME_MS * 1e-3), + "GPS initilisation blob is to large to be completely sent before the baud rate changes"); + AP_Param::setup_object_defaults(this, var_info); }