mirror of https://github.com/ArduPilot/ardupilot
GPS: fixed the idle timer
we need to reset the idle timer only on good data, or a call to init(). Otherwise we never use it. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1849 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
eb6962568b
commit
81c5770b77
|
@ -16,6 +16,9 @@ GPS::update(void)
|
||||||
if ((millis() - _idleTimer) > _idleTimeout) {
|
if ((millis() - _idleTimer) > _idleTimeout) {
|
||||||
_status = NO_GPS;
|
_status = NO_GPS;
|
||||||
init();
|
init();
|
||||||
|
|
||||||
|
// reset the idle timer
|
||||||
|
_idleTimer = millis();
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// we got a message, update our status correspondingly
|
// we got a message, update our status correspondingly
|
||||||
|
@ -23,10 +26,10 @@ GPS::update(void)
|
||||||
|
|
||||||
valid_read = true;
|
valid_read = true;
|
||||||
new_data = true;
|
new_data = true;
|
||||||
}
|
|
||||||
|
|
||||||
// reset the idle timer
|
// reset the idle timer
|
||||||
_idleTimer = millis();
|
_idleTimer = millis();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
|
|
Loading…
Reference in New Issue