From c7141c4851654f9503c367a87fb4bd0f69b7c8f8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 15 Jul 2013 14:09:07 +1000 Subject: [PATCH] AP_GPS: fixed examples build --- libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde | 6 +++--- libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde | 6 +++--- libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde | 6 +++--- libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde | 6 +++--- libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde | 6 +++--- 5 files changed, 15 insertions(+), 15 deletions(-) diff --git a/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde b/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde index b632952282..3fc1e07e53 100644 --- a/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde +++ b/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde @@ -40,11 +40,11 @@ void loop() hal.console->print(" Lon:"); hal.console->print((float)gps.longitude / T7, DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, DEC); hal.console->print(" GSP:"); - hal.console->print(gps.ground_speed / 100.0); + hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course / 100, DEC); + hal.console->print(gps.ground_course_cd / 100, DEC); hal.console->print(" SAT:"); hal.console->print(gps.num_sats, DEC); hal.console->print(" FIX:"); diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde index 04368b93d6..05fc7a7d31 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde @@ -43,9 +43,9 @@ void loop() hal.console->print(" Lon: "); print_latlon(hal.console,gps->longitude); hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu STATUS: %u\n", - (float)gps->altitude / 100.0, - (float)gps->ground_speed / 100.0, - (int)gps->ground_course / 100, + (float)gps->altitude_cm / 100.0, + (float)gps->ground_speed_cm / 100.0, + (int)gps->ground_course_cd / 100, gps->num_sats, gps->time, gps->status()); diff --git a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde index 97f6fb407f..bdeee0fe68 100644 --- a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde +++ b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde @@ -43,11 +43,11 @@ void loop() hal.console->print(" Lon:"); hal.console->print((float)gps.longitude / T7, DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, DEC); hal.console->print(" GSP:"); - hal.console->print(gps.ground_speed / 100.0); + hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course / 100.0, DEC); + hal.console->print(gps.ground_course_cd / 100.0, DEC); hal.console->print(" SAT:"); hal.console->print(gps.num_sats, DEC); hal.console->print(" FIX:"); diff --git a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde index f99135158f..1bbe54cb56 100644 --- a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde +++ b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde @@ -63,9 +63,9 @@ void loop() "CoG: %d SAT: %d TIM: %lu\r\n"), (float)gps->latitude / T7, (float)gps->longitude / T7, - (float)gps->altitude / 100.0, - (float)gps->ground_speed / 100.0, - (int)gps->ground_course / 100, + (float)gps->altitude_cm / 100.0, + (float)gps->ground_speed_cm / 100.0, + (int)gps->ground_course_cd / 100, gps->num_sats, gps->time); } else { diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde index bcf1533553..b5622ec751 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde +++ b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde @@ -43,11 +43,11 @@ void loop() hal.console->print(" Lon:"); hal.console->print((float)gps.longitude / T7, DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, DEC); hal.console->print(" GSP:"); - hal.console->print(gps.ground_speed / 100.0); + hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course / 100.0, DEC); + hal.console->print(gps.ground_course_cd / 100.0, DEC); Vector2f vel = Vector2f(gps.velocity_north(), gps.velocity_east()); hal.console->printf(" VEL: %.2f %.2f %.2f", vel.x,