mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
Hopefully this fixes the GPS init bug.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1830 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
cdcee09e0d
commit
294d6752fe
@ -525,7 +525,7 @@ void medium_loop()
|
||||
medium_loopCounter++;
|
||||
|
||||
|
||||
if(Serial1.available() > 0){
|
||||
if(GPS_disabled == false){
|
||||
update_GPS();
|
||||
}
|
||||
|
||||
@ -785,7 +785,6 @@ void update_GPS(void)
|
||||
update_GPS_light();
|
||||
|
||||
if (g_gps->new_data && g_gps->fix) {
|
||||
GPS_disabled = false;
|
||||
|
||||
// XXX We should be sending GPS data off one of the regular loops so that we send
|
||||
// no-GPS-fix data too
|
||||
|
@ -254,8 +254,20 @@ void startup_ground(void)
|
||||
// -------------------
|
||||
init_commands();
|
||||
|
||||
// clear out the GPS buffer
|
||||
Serial1.flush();
|
||||
byte counter = 4;
|
||||
GPS_disabled = true;
|
||||
|
||||
// Read in the GPS
|
||||
for (byte counter = 0; ; counter++) {
|
||||
g_gps->update();
|
||||
if (g_gps->status() != 0){
|
||||
break;
|
||||
}
|
||||
if (counter >= 4) {
|
||||
GPS_disabled = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
gcs.send_text_P(SEVERITY_LOW,PSTR("\n\n Ready to FLY."));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user