update "NO_GPS" issue as per Justin Beech

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3225 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
mich146@hotmail.com 2011-09-04 04:46:14 +00:00
parent 4e71884298
commit 5e3e96b236
2 changed files with 3 additions and 1 deletions

View File

@ -22,6 +22,7 @@ AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s)
// Public Methods //////////////////////////////////////////////////////////////
void AP_GPS_HIL::init(void)
{
idleTimeout = 1200;
}
bool AP_GPS_HIL::read(void)

View File

@ -41,7 +41,8 @@ AP_GPS_IMU::AP_GPS_IMU(Stream *s) : GPS(s)
void
AP_GPS_IMU::init(void)
{
// we expect the stream to already be open at the corret bitrate
// we expect the stream to already be open at the corret bitrate
idleTimeout = 1200;
}
// optimization : This code doesn't wait for data. It only proccess the data available.