ArduCopter: replace Serial.print with Serial.print_P to save memory.
Includes replacing flight_mode_strings with print_flight_mode function. SendDebug macro replaced with direct Serial.print_P calls.
This commit is contained in:
parent
09485ddc5f
commit
78316adf75
@ -356,22 +356,6 @@ AP_RangeFinder_MaxsonarXL sonar(&sonar_analog_source, &sonar_mode_filter);
|
|||||||
// Global variables
|
// Global variables
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
static const char* flight_mode_strings[] = {
|
|
||||||
"STABILIZE", // 0
|
|
||||||
"ACRO", // 1
|
|
||||||
"ALT_HOLD", // 2
|
|
||||||
"AUTO", // 3
|
|
||||||
"GUIDED", // 4
|
|
||||||
"LOITER", // 5
|
|
||||||
"RTL", // 6
|
|
||||||
"CIRCLE", // 7
|
|
||||||
"POSITION", // 8
|
|
||||||
"LAND", // 9
|
|
||||||
"OF_LOITER", // 10
|
|
||||||
"TOY_M", // 11
|
|
||||||
"TOY_A"
|
|
||||||
}; // 12 THOR Added for additional Fligt mode
|
|
||||||
|
|
||||||
/* Radio values
|
/* Radio values
|
||||||
* Channel assignments
|
* Channel assignments
|
||||||
* 1 Ailerons (rudder if no ailerons)
|
* 1 Ailerons (rudder if no ailerons)
|
||||||
|
@ -381,9 +381,9 @@ static void Log_Read_Raw()
|
|||||||
for (int16_t y = 0; y < 6; y++) {
|
for (int16_t y = 0; y < 6; y++) {
|
||||||
logvar = get_float(DataFlash.ReadLong());
|
logvar = get_float(DataFlash.ReadLong());
|
||||||
Serial.print(logvar);
|
Serial.print(logvar);
|
||||||
Serial.print(", ");
|
Serial.print_P(PSTR(", "));
|
||||||
}
|
}
|
||||||
Serial.println(" ");
|
Serial.println_P(PSTR(" "));
|
||||||
|
|
||||||
/*
|
/*
|
||||||
float temp1 = get_float(DataFlash.ReadLong());
|
float temp1 = get_float(DataFlash.ReadLong());
|
||||||
@ -714,7 +714,7 @@ static void Log_Read_Iterm()
|
|||||||
}
|
}
|
||||||
// read 12
|
// read 12
|
||||||
temp = DataFlash.ReadInt();
|
temp = DataFlash.ReadInt();
|
||||||
Serial.printf("%d\n", (int)temp);
|
Serial.println((int)temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -846,7 +846,7 @@ static void Log_Write_Mode(byte mode)
|
|||||||
static void Log_Read_Mode()
|
static void Log_Read_Mode()
|
||||||
{
|
{
|
||||||
Serial.printf_P(PSTR("MOD:"));
|
Serial.printf_P(PSTR("MOD:"));
|
||||||
Serial.print(flight_mode_strings[DataFlash.ReadByte()]);
|
print_flight_mode(DataFlash.ReadByte());
|
||||||
Serial.printf_P(PSTR(", %d\n"),(int)DataFlash.ReadInt());
|
Serial.printf_P(PSTR(", %d\n"),(int)DataFlash.ReadInt());
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1041,7 +1041,7 @@ static int16_t Log_Read_Process(int16_t start_page, int16_t end_page)
|
|||||||
log_step++;
|
log_step++;
|
||||||
else{
|
else{
|
||||||
log_step = 0;
|
log_step = 0;
|
||||||
Serial.println(".");
|
Serial.println_P(PSTR("."));
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -990,32 +990,6 @@
|
|||||||
// #define LOG_ATTITUDE_MED DISABLED
|
// #define LOG_ATTITUDE_MED DISABLED
|
||||||
//#endif
|
//#endif
|
||||||
|
|
||||||
#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
|
// Navigation defaults
|
||||||
//
|
//
|
||||||
|
@ -168,8 +168,8 @@ static void throttle_failsafe(uint16_t pwm)
|
|||||||
// home distance is in meters
|
// home distance is in meters
|
||||||
// This is to prevent accidental RTL
|
// This is to prevent accidental RTL
|
||||||
if(motors.armed() && takeoff_complete) {
|
if(motors.armed() && takeoff_complete) {
|
||||||
SendDebug("MSG FS ON ");
|
Serial.print_P(PSTR("MSG FS ON "));
|
||||||
SendDebugln(pwm, DEC);
|
Serial.println(pwm, DEC);
|
||||||
set_failsafe(true);
|
set_failsafe(true);
|
||||||
}
|
}
|
||||||
}else if (failsafeCounter > FS_COUNTER) {
|
}else if (failsafeCounter > FS_COUNTER) {
|
||||||
@ -184,8 +184,8 @@ static void throttle_failsafe(uint16_t pwm)
|
|||||||
failsafeCounter = 3;
|
failsafeCounter = 3;
|
||||||
}
|
}
|
||||||
if (failsafeCounter == 1) {
|
if (failsafeCounter == 1) {
|
||||||
SendDebug("MSG FS OFF ");
|
Serial.print_P(PSTR("MSG FS OFF "));
|
||||||
SendDebugln(pwm, DEC);
|
Serial.println(pwm, DEC);
|
||||||
}else if(failsafeCounter == 0) {
|
}else if(failsafeCounter == 0) {
|
||||||
set_failsafe(false);
|
set_failsafe(false);
|
||||||
}else if (failsafeCounter <0) {
|
}else if (failsafeCounter <0) {
|
||||||
|
@ -53,7 +53,7 @@ static void init_optflow()
|
|||||||
#ifdef OPTFLOW_ENABLED
|
#ifdef OPTFLOW_ENABLED
|
||||||
if( optflow.init(false, &timer_scheduler, &spi_semaphore, &spi3_semaphore) == false ) {
|
if( optflow.init(false, &timer_scheduler, &spi_semaphore, &spi3_semaphore) == false ) {
|
||||||
g.optflow_enabled = false;
|
g.optflow_enabled = false;
|
||||||
SendDebug("\nFailed to Init OptFlow ");
|
Serial.print_P(PSTR("\nFailed to Init OptFlow "));
|
||||||
}
|
}
|
||||||
// suspend timer while we set-up SPI communication
|
// suspend timer while we set-up SPI communication
|
||||||
timer_scheduler.suspend_timer();
|
timer_scheduler.suspend_timer();
|
||||||
|
@ -144,7 +144,7 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
|
|||||||
static int8_t
|
static int8_t
|
||||||
setup_radio(uint8_t argc, const Menu::arg *argv)
|
setup_radio(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
Serial.println("\n\nRadio Setup:");
|
Serial.println_P(PSTR("\n\nRadio Setup:"));
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
for(i = 0; i < 100; i++) {
|
for(i = 0; i < 100; i++) {
|
||||||
@ -1000,7 +1000,7 @@ static void
|
|||||||
print_switch(byte p, byte m, bool b)
|
print_switch(byte p, byte m, bool b)
|
||||||
{
|
{
|
||||||
Serial.printf_P(PSTR("Pos %d:\t"),p);
|
Serial.printf_P(PSTR("Pos %d:\t"),p);
|
||||||
Serial.print(flight_mode_strings[m]);
|
print_flight_mode(m);
|
||||||
Serial.printf_P(PSTR(",\t\tSimple: "));
|
Serial.printf_P(PSTR(",\t\tSimple: "));
|
||||||
if(b)
|
if(b)
|
||||||
Serial.printf_P(PSTR("ON\n"));
|
Serial.printf_P(PSTR("ON\n"));
|
||||||
@ -1115,18 +1115,18 @@ static void
|
|||||||
print_divider(void)
|
print_divider(void)
|
||||||
{
|
{
|
||||||
for (int i = 0; i < 40; i++) {
|
for (int i = 0; i < 40; i++) {
|
||||||
Serial.print("-");
|
Serial.print_P(PSTR("-"));
|
||||||
}
|
}
|
||||||
Serial.println("");
|
Serial.println();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void print_enabled(boolean b)
|
static void print_enabled(boolean b)
|
||||||
{
|
{
|
||||||
if(b)
|
if(b)
|
||||||
Serial.printf_P(PSTR("en"));
|
Serial.print_P(PSTR("en"));
|
||||||
else
|
else
|
||||||
Serial.printf_P(PSTR("dis"));
|
Serial.print_P(PSTR("dis"));
|
||||||
Serial.printf_P(PSTR("abled\n"));
|
Serial.print_P(PSTR("abled\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -353,7 +353,7 @@ static void init_ardupilot()
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
SendDebug("\nReady to FLY ");
|
Serial.print_P(PSTR("\nReady to FLY "));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -684,3 +684,55 @@ uint16_t board_voltage(void)
|
|||||||
return vcc.read_vcc();
|
return vcc.read_vcc();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// print_flight_mode - prints flight mode to serial port.
|
||||||
|
//
|
||||||
|
static void
|
||||||
|
print_flight_mode(uint8_t mode)
|
||||||
|
{
|
||||||
|
switch (mode) {
|
||||||
|
case STABILIZE:
|
||||||
|
Serial.print_P(PSTR("STABILIZE"));
|
||||||
|
break;
|
||||||
|
case ACRO:
|
||||||
|
Serial.print_P(PSTR("ACRO"));
|
||||||
|
break;
|
||||||
|
case ALT_HOLD:
|
||||||
|
Serial.print_P(PSTR("ALT_HOLD"));
|
||||||
|
break;
|
||||||
|
case AUTO:
|
||||||
|
Serial.print_P(PSTR("AUTO"));
|
||||||
|
break;
|
||||||
|
case GUIDED:
|
||||||
|
Serial.print_P(PSTR("GUIDED"));
|
||||||
|
break;
|
||||||
|
case LOITER:
|
||||||
|
Serial.print_P(PSTR("LOITER"));
|
||||||
|
break;
|
||||||
|
case RTL:
|
||||||
|
Serial.print_P(PSTR("RTL"));
|
||||||
|
break;
|
||||||
|
case CIRCLE:
|
||||||
|
Serial.print_P(PSTR("CIRCLE"));
|
||||||
|
break;
|
||||||
|
case POSITION:
|
||||||
|
Serial.print_P(PSTR("POSITION"));
|
||||||
|
break;
|
||||||
|
case LAND:
|
||||||
|
Serial.print_P(PSTR("LAND"));
|
||||||
|
break;
|
||||||
|
case OF_LOITER:
|
||||||
|
Serial.print_P(PSTR("OF_LOITER"));
|
||||||
|
break;
|
||||||
|
case TOY_M:
|
||||||
|
Serial.print_P(PSTR("TOY_M"));
|
||||||
|
break;
|
||||||
|
case TOY_A:
|
||||||
|
Serial.print_P(PSTR("TOY_A"));
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
Serial.print_P(PSTR("---"));
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -764,7 +764,7 @@ test_gps(uint8_t argc, const Menu::arg *argv)
|
|||||||
g_gps->num_sats);
|
g_gps->num_sats);
|
||||||
g_gps->new_data = false;
|
g_gps->new_data = false;
|
||||||
}else{
|
}else{
|
||||||
Serial.print(".");
|
Serial.print_P(PSTR("."));
|
||||||
}
|
}
|
||||||
if(Serial.available() > 0) {
|
if(Serial.available() > 0) {
|
||||||
return (0);
|
return (0);
|
||||||
@ -1264,7 +1264,7 @@ test_wp_nav(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
// got 23506;, should be 22800
|
// got 23506;, should be 22800
|
||||||
navigate();
|
navigate();
|
||||||
Serial.printf("bear: %ld\n", target_bearing);
|
Serial.printf_P(PSTR("bear: %ld\n"), target_bearing);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user