From 3a81e12866809cf92507ccf667671ca8dff84df8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 18 Sep 2011 19:05:12 +1000 Subject: [PATCH] get rid of the last active uses of the SendDebug macros please use gcs_send_text*() from now on, to ensure serial queueing --- ArduPlane/config.h | 26 -------------------------- ArduPlane/radio.pde | 6 ++---- 2 files changed, 2 insertions(+), 30 deletions(-) diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 69cc9df28f..ee2c149362 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -639,32 +639,6 @@ LOGBIT(CUR) -#ifndef DEBUG_PORT -# define DEBUG_PORT 0 -#endif - -#if DEBUG_PORT == 0 -# define SendDebug_P(a) Serial.print_P(PSTR(a)) -# define SendDebugln_P(a) Serial.println_P(PSTR(a)) -# define SendDebug Serial.print -# define SendDebugln Serial.println -#elif DEBUG_PORT == 1 -# define SendDebug_P(a) Serial1.print_P(PSTR(a)) -# define SendDebugln_P(a) Serial1.println_P(PSTR(a)) -# define SendDebug Serial1.print -# define SendDebugln Serial1.println -#elif DEBUG_PORT == 2 -# define SendDebug_P(a) Serial2.print_P(PSTR(a)) -# define SendDebugln_P(a) Serial2.println_P(PSTR(a)) -# define SendDebug Serial2.print -# define SendDebugln Serial2.println -#elif DEBUG_PORT == 3 -# define SendDebug_P(a) Serial3.print_P(PSTR(a)) -# define SendDebugln_P(a) Serial3.println_P(PSTR(a)) -# define SendDebug Serial3.print -# define SendDebugln Serial3.println -#endif - ////////////////////////////////////////////////////////////////////////////// // Navigation defaults // diff --git a/ArduPlane/radio.pde b/ArduPlane/radio.pde index 674c096e25..9994e74ef6 100644 --- a/ArduPlane/radio.pde +++ b/ArduPlane/radio.pde @@ -120,8 +120,7 @@ static void control_failsafe(uint16_t pwm) // throttle has dropped below the mark failsafeCounter++; if (failsafeCounter == 9){ - SendDebug_P("MSG FS ON "); - SendDebugln(pwm, DEC); + gcs_send_text_fmt(PSTR("MSG FS ON %u"), (unsigned)pwm); }else if(failsafeCounter == 10) { ch3_failsafe = true; }else if (failsafeCounter > 10){ @@ -136,8 +135,7 @@ static void control_failsafe(uint16_t pwm) failsafeCounter = 3; } if (failsafeCounter == 1){ - SendDebug_P("MSG FS OFF "); - SendDebugln(pwm, DEC); + gcs_send_text_fmt(PSTR("MSG FS OFF %u"), (unsigned)pwm); }else if(failsafeCounter == 0) { ch3_failsafe = false; }else if (failsafeCounter <0){