mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_GPS_UBLOX: send cfg save msg only once every 1 second
This commit is contained in:
parent
bc708f9808
commit
360c09f9bd
@ -57,7 +57,8 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART
|
||||
rate_update_step(0),
|
||||
_last_5hz_time(0),
|
||||
noReceivedHdop(true),
|
||||
_cfg_saved(false)
|
||||
_cfg_saved(false),
|
||||
_last_cfg_sent_time(0)
|
||||
{
|
||||
// stop any config strings that are pending
|
||||
gps.send_blob_start(state.instance, NULL, 0);
|
||||
@ -154,10 +155,12 @@ AP_GPS_UBLOX::read(void)
|
||||
uint8_t data;
|
||||
int16_t numc;
|
||||
bool parsed = false;
|
||||
uint32_t millis_now = hal.scheduler->millis();
|
||||
|
||||
if (need_rate_update) {
|
||||
send_next_rate_update();
|
||||
}else if(!_cfg_saved && gps._save_config) { //save the configuration sent until now
|
||||
}else if(!_cfg_saved && gps._save_config && (millis_now - _last_cfg_sent_time) > 1000) { //save the configuration sent until now
|
||||
_last_cfg_sent_time = millis_now;
|
||||
_save_cfg();
|
||||
}
|
||||
|
||||
@ -796,7 +799,8 @@ AP_GPS_UBLOX::_configure_gps(void)
|
||||
}
|
||||
|
||||
/*
|
||||
*
|
||||
* save gps configurations to non-volatile memory sent until the call of
|
||||
* this message
|
||||
*/
|
||||
void
|
||||
AP_GPS_UBLOX::_save_cfg()
|
||||
|
@ -405,6 +405,7 @@ private:
|
||||
|
||||
uint32_t _last_vel_time;
|
||||
uint32_t _last_pos_time;
|
||||
uint32_t _last_cfg_sent_time;
|
||||
|
||||
// do we have new position information?
|
||||
bool _new_position:1;
|
||||
|
Loading…
Reference in New Issue
Block a user