mirror of https://github.com/ArduPilot/ardupilot
Fix initialization of idleTimeout
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2602 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6be97515ac
commit
b53b749fc7
|
@ -27,6 +27,8 @@ void AP_GPS_406::init(void)
|
||||||
_configure_gps(); // Function to configure GPS, to output only the desired msg's
|
_configure_gps(); // Function to configure GPS, to output only the desired msg's
|
||||||
|
|
||||||
AP_GPS_SIRF::init(); // let the superclass do anything it might need here
|
AP_GPS_SIRF::init(); // let the superclass do anything it might need here
|
||||||
|
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Private Methods //////////////////////////////////////////////////////////////
|
// Private Methods //////////////////////////////////////////////////////////////
|
||||||
|
|
|
@ -33,6 +33,8 @@ AP_GPS_MTK::init(void)
|
||||||
|
|
||||||
// set initial epoch code
|
// set initial epoch code
|
||||||
_epoch = TIME_OF_DAY;
|
_epoch = TIME_OF_DAY;
|
||||||
|
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Process bytes available from the stream
|
// Process bytes available from the stream
|
||||||
|
|
|
@ -36,6 +36,7 @@ AP_GPS_MTK16::init(void)
|
||||||
_epoch = TIME_OF_DAY;
|
_epoch = TIME_OF_DAY;
|
||||||
_time_offset = 0;
|
_time_offset = 0;
|
||||||
_offset_calculated = false;
|
_offset_calculated = false;
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Process bytes available from the stream
|
// Process bytes available from the stream
|
||||||
|
|
|
@ -116,6 +116,8 @@ void AP_GPS_NMEA::init(void)
|
||||||
|
|
||||||
// send the ublox init strings
|
// send the ublox init strings
|
||||||
bs->print_P((const prog_char_t *)_ublox_init_string);
|
bs->print_P((const prog_char_t *)_ublox_init_string);
|
||||||
|
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_GPS_NMEA::read(void)
|
bool AP_GPS_NMEA::read(void)
|
||||||
|
|
|
@ -40,6 +40,7 @@ AP_GPS_SIRF::init(void)
|
||||||
|
|
||||||
// send SiRF binary setup messages
|
// send SiRF binary setup messages
|
||||||
_port->write(init_messages, sizeof(init_messages));
|
_port->write(init_messages, sizeof(init_messages));
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Process bytes available from the stream
|
// Process bytes available from the stream
|
||||||
|
|
|
@ -29,6 +29,7 @@ AP_GPS_UBLOX::init(void)
|
||||||
_port->flush();
|
_port->flush();
|
||||||
|
|
||||||
_epoch = TIME_OF_WEEK;
|
_epoch = TIME_OF_WEEK;
|
||||||
|
idleTimeout = 1200;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Process bytes available from the stream
|
// Process bytes available from the stream
|
||||||
|
|
|
@ -15,8 +15,8 @@ GPS::update(void)
|
||||||
if (!result) {
|
if (!result) {
|
||||||
if ((millis() - _idleTimer) > idleTimeout) {
|
if ((millis() - _idleTimer) > idleTimeout) {
|
||||||
_status = NO_GPS;
|
_status = NO_GPS;
|
||||||
init();
|
|
||||||
|
|
||||||
|
init();
|
||||||
// reset the idle timer
|
// reset the idle timer
|
||||||
_idleTimer = millis();
|
_idleTimer = millis();
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue