AP_GPS: Use a static assert to check that the init blob is small enough

This commit is contained in:
Michael du Breuil 2017-05-29 15:02:25 -07:00 committed by Francisco Ferreira
parent 0b7ec0dc64
commit ffe701bda3

View File

@ -20,6 +20,7 @@
#include <AP_Notify/AP_Notify.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <climits>
#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);
}