GPS: tidy up the auto gps test

This commit is contained in:
Andrew Tridgell 2012-06-08 16:07:40 +10:00
parent f7be9a4b5d
commit 148e59a4de
1 changed files with 4 additions and 3 deletions

View File

@ -52,16 +52,17 @@ void loop()
gps->update(); gps->update();
if (gps->new_data) { if (gps->new_data) {
if (gps->fix) { if (gps->fix) {
Serial.print("\nLat: "); Serial.print("Lat: ");
print_latlon(&Serial,gps->latitude); print_latlon(&Serial,gps->latitude);
Serial.print(" Lon: "); Serial.print(" Lon: ");
print_latlon(&Serial,gps->longitude); print_latlon(&Serial,gps->longitude);
Serial.printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu", Serial.printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu STATUS: %u\n",
(float)gps->altitude / 100.0, (float)gps->altitude / 100.0,
(float)gps->ground_speed / 100.0, (float)gps->ground_speed / 100.0,
(int)gps->ground_course / 100, (int)gps->ground_course / 100,
gps->num_sats, gps->num_sats,
gps->time); gps->time,
gps->status());
} else { } else {
Serial.println("No fix"); Serial.println("No fix");
} }