From 86c2b1d84a3e59736bceda1a7255f473354cd1ae Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Thu, 15 Sep 2016 04:03:39 -0700 Subject: [PATCH] AP_GPS: u-blox Remove 5Hz warning The warnings test case is better covered by the rest of the driver while it is performing the normal settings audit. --- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 32 +------------------------------ libraries/AP_GPS/AP_GPS_UBLOX.h | 3 --- 2 files changed, 1 insertion(+), 34 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 1aea7c1bec..0235f74ef1 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -65,15 +65,12 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART _new_speed(0), _disable_counter(0), next_fix(AP_GPS::NO_FIX), - _last_5hz_time(0), _cfg_needs_save(false), noReceivedHdop(true) { // stop any config strings that are pending gps.send_blob_start(state.instance, NULL, 0); - _last_5hz_time = AP_HAL::millis(); - // start the process of updating the GPS rates _request_next_config(); } @@ -127,7 +124,7 @@ AP_GPS_UBLOX::_request_next_config(void) _send_message(CLASS_CFG, MSG_CFG_GNSS, NULL, 0); break; case STEP_NAV_RATE: - _request_navigation_rate(); + _send_message(CLASS_CFG, MSG_CFG_RATE, NULL, 0); break; case STEP_POSLLH: if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) { @@ -900,13 +897,6 @@ AP_GPS_UBLOX::_parse_gps(void) state.num_sats = _buffer.solution.satellites; if (next_fix >= AP_GPS::GPS_OK_FIX_2D) { state.last_gps_time_ms = AP_HAL::millis(); - if (state.time_week == _buffer.solution.week && - state.time_week_ms + 200 == _buffer.solution.time) { - // we got a 5Hz update. This relies on the way - // that uBlox gives timestamps that are always - // multiples of 200 for 5Hz - _last_5hz_time = state.last_gps_time_ms; - } state.time_week_ms = _buffer.solution.time; state.time_week = _buffer.solution.week; } @@ -977,17 +967,6 @@ AP_GPS_UBLOX::_parse_gps(void) // this ensures we don't use stale data if (_new_position && _new_speed && _last_vel_time == _last_pos_time) { _new_speed = _new_position = false; - // allow the GPS configuration to run through the full loop at least once before throwing this - if (state.status != AP_GPS::NO_FIX && AP_HAL::millis() - _last_5hz_time > 20000U) { - // the gps seems to be slow, possibly due to a brown out - // invalidate the config so it can be reset - _last_5hz_time = AP_HAL::millis(); - _unconfigured_messages = CONFIG_ALL; - _request_next_config(); - GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, - "GPS: u-blox %d is not maintaining a 5Hz update", - state.instance); - } return true; } return false; @@ -1074,15 +1053,6 @@ AP_GPS_UBLOX::_configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t return true; } -/* - * request the current naviation solution rate - */ -void -AP_GPS_UBLOX::_request_navigation_rate(void) -{ - _send_message(CLASS_CFG, MSG_CFG_RATE, 0, 0); -} - /* * save gps configurations to non-volatile memory sent until the call of * this message diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 1ebc28c0a7..2e826dbd33 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -506,8 +506,6 @@ private: // used to update fix between status and position packets AP_GPS::GPS_Status next_fix; - uint32_t _last_5hz_time; - bool _cfg_needs_save; bool noReceivedHdop; @@ -519,7 +517,6 @@ private: void _send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint16_t size); void send_next_rate_update(void); bool _request_message_rate(uint8_t msg_class, uint8_t msg_id); - void _request_navigation_rate(void); void _request_next_config(void); void _request_port(void); void _request_version(void);