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 22b4510606..7800d6a843 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 @@ -37,21 +37,21 @@ void loop() if (gps.new_data) { hal.console->print("gps:"); hal.console->print(" Lat:"); - hal.console->print((float)gps.latitude / T7, DEC); + hal.console->print((float)gps.latitude / T7, BASE_DEC); hal.console->print(" Lon:"); - hal.console->print((float)gps.longitude / T7, DEC); + hal.console->print((float)gps.longitude / T7, BASE_DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude_cm / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC); hal.console->print(" GSP:"); hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course_cd / 100, DEC); + hal.console->print(gps.ground_course_cd / 100, BASE_DEC); hal.console->print(" SAT:"); - hal.console->print(gps.num_sats, DEC); + hal.console->print(gps.num_sats, BASE_DEC); hal.console->print(" FIX:"); - hal.console->print(gps.fix, DEC); + hal.console->print(gps.fix, BASE_DEC); hal.console->print(" TIM:"); - hal.console->print(gps.time, DEC); + hal.console->print(gps.time, BASE_DEC); hal.console->println(); gps.new_data = 0; // We have readed the data } 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 10ecf97ef5..b0b584f42c 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 @@ -40,21 +40,21 @@ void loop() if (gps.new_data) { hal.console->print("gps:"); hal.console->print(" Lat:"); - hal.console->print((float)gps.latitude / T7, DEC); + hal.console->print((float)gps.latitude / T7, BASE_DEC); hal.console->print(" Lon:"); - hal.console->print((float)gps.longitude / T7, DEC); + hal.console->print((float)gps.longitude / T7, BASE_DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude_cm / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC); hal.console->print(" GSP:"); hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course_cd / 100.0, DEC); + hal.console->print(gps.ground_course_cd / 100.0, BASE_DEC); hal.console->print(" SAT:"); - hal.console->print(gps.num_sats, DEC); + hal.console->print(gps.num_sats, BASE_DEC); hal.console->print(" FIX:"); - hal.console->print(gps.fix, DEC); + hal.console->print(gps.fix, BASE_DEC); hal.console->print(" TIM:"); - hal.console->print(gps.time, DEC); + hal.console->print(gps.time, BASE_DEC); hal.console->println(); gps.new_data = 0; // We have readed the data } 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 12bad7f9aa..6159a4a2bc 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 @@ -40,26 +40,26 @@ void loop() if (gps.new_data) { hal.console->print("gps:"); hal.console->print(" Lat:"); - hal.console->print((float)gps.latitude / T7, DEC); + hal.console->print((float)gps.latitude / T7, BASE_DEC); hal.console->print(" Lon:"); - hal.console->print((float)gps.longitude / T7, DEC); + hal.console->print((float)gps.longitude / T7, BASE_DEC); hal.console->print(" Alt:"); - hal.console->print((float)gps.altitude_cm / 100.0, DEC); + hal.console->print((float)gps.altitude_cm / 100.0, BASE_DEC); hal.console->print(" GSP:"); hal.console->print(gps.ground_speed_cm / 100.0); hal.console->print(" COG:"); - hal.console->print(gps.ground_course_cd / 100.0, DEC); + hal.console->print(gps.ground_course_cd / 100.0, BASE_DEC); Vector2f vel = Vector2f(gps.velocity_north(), gps.velocity_east()); hal.console->printf(" VEL: %.2f %.2f %.2f", vel.x, vel.y, vel.length()); hal.console->print(" SAT:"); - hal.console->print(gps.num_sats, DEC); + hal.console->print(gps.num_sats, BASE_DEC); hal.console->print(" FIX:"); - hal.console->print(gps.fix, DEC); + hal.console->print(gps.fix, BASE_DEC); hal.console->print(" TIM:"); - hal.console->print(gps.time, DEC); + hal.console->print(gps.time, BASE_DEC); hal.console->println(); gps.new_data = 0; // We have readed the data }