From f2b21ecc414bda8de9209ecad8f15d4a432a8857 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Tue, 18 Sep 2012 11:08:38 -0700 Subject: [PATCH] AP_Param: Port to work with AP_HAL class instead of FastSerial --- libraries/AP_Param/AP_Param.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index f0d0d4e71b..5edc4824fe 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -13,17 +13,19 @@ /// @brief The AP variable store. -#include +#include #include #include #include #include +extern const AP_HAL::HAL &hal; + // #define ENABLE_FASTSERIAL_DEBUG #ifdef ENABLE_FASTSERIAL_DEBUG - # define serialDebug(fmt, args ...) if (FastSerial::getInitialized(0)) do {Serial.printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); delay(0); } while(0) + # define serialDebug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); delay(0); } while(0) #else # define serialDebug(fmt, args ...) #endif @@ -987,16 +989,16 @@ void AP_Param::show_all(void) switch (type) { case AP_PARAM_INT8: - Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int8 *)ap)->get()); + hal.console->printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int8 *)ap)->get()); break; case AP_PARAM_INT16: - Serial.printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int16 *)ap)->get()); + hal.console->printf_P(PSTR("%s: %d\n"), s, (int)((AP_Int16 *)ap)->get()); break; case AP_PARAM_INT32: - Serial.printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get()); + hal.console->printf_P(PSTR("%s: %ld\n"), s, (long)((AP_Int32 *)ap)->get()); break; case AP_PARAM_FLOAT: - Serial.printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get()); + hal.console->printf_P(PSTR("%s: %f\n"), s, ((AP_Float *)ap)->get()); break; default: break;