Browse Source

AP_GPS_UBLOX: use get_rate_ms accessor

mission-4.1.18
Randy Mackay 8 years ago
parent
commit
81b20e971b
  1. 2
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

2
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -1269,7 +1269,7 @@ AP_GPS_UBLOX::_configure_rate(void)
{ {
struct ubx_cfg_nav_rate msg; struct ubx_cfg_nav_rate msg;
// require a minimum measurement rate of 5Hz // 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.nav_rate = 1;
msg.timeref = 0; // UTC time msg.timeref = 0; // UTC time
_send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg)); _send_message(CLASS_CFG, MSG_CFG_RATE, &msg, sizeof(msg));

Loading…
Cancel
Save