From 81b20e971bc561538868baaf6a144f177db4424f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 10 Mar 2017 15:46:58 +0900 Subject: [PATCH] AP_GPS_UBLOX: use get_rate_ms accessor --- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 1e08eeae26..5e7c518e49 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -1269,7 +1269,7 @@ AP_GPS_UBLOX::_configure_rate(void) { struct ubx_cfg_nav_rate msg; // require a minimum measurement rate of 5Hz - msg.measure_rate_ms = MIN(gps._rate_ms[state.instance], GPS_MAX_RATE_MS); + msg.measure_rate_ms = gps.get_rate_ms(state.instance); msg.nav_rate = 1; msg.timeref = 0; // UTC time _send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));