From 09c210e10f63df8b73345d3273905e4f59b955aa Mon Sep 17 00:00:00 2001 From: Francisco Ferreira Date: Thu, 7 Mar 2019 21:30:37 +0000 Subject: [PATCH] AP_GPS: use proper macro in array sizes --- libraries/AP_GPS/AP_GPS.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 55fccfa2f6..09bebc2c61 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -461,8 +461,8 @@ private: uint16_t delta_time_ms; }; // Note allowance for an additional instance to contain blended data - GPS_timing timing[GPS_MAX_RECEIVERS+1]; - GPS_State state[GPS_MAX_RECEIVERS+1]; + GPS_timing timing[GPS_MAX_INSTANCES]; + GPS_State state[GPS_MAX_INSTANCES]; AP_GPS_Backend *drivers[GPS_MAX_RECEIVERS]; AP_HAL::UARTDriver *_port[GPS_MAX_RECEIVERS];