mirror of https://github.com/ArduPilot/ardupilot
APM: save 100 bytes of memory
remove flight_mode_strings array
This commit is contained in:
parent
3b5b2eba6e
commit
f32fcb7495
|
@ -300,24 +300,6 @@ static bool usb_connected;
|
|||
|
||||
static const char *comma = ",";
|
||||
|
||||
static const char* flight_mode_strings[] = {
|
||||
"Manual",
|
||||
"Circle",
|
||||
"Stabilize",
|
||||
"",
|
||||
"",
|
||||
"FBW_A",
|
||||
"FBW_B",
|
||||
"",
|
||||
"",
|
||||
"",
|
||||
"Auto",
|
||||
"RTL",
|
||||
"Loiter",
|
||||
"Takeoff",
|
||||
"Land"
|
||||
};
|
||||
|
||||
|
||||
/* Radio values
|
||||
* Channel assignments
|
||||
|
|
|
@ -408,7 +408,6 @@ static void set_servos(void)
|
|||
|
||||
// Auto flap deployment
|
||||
if(control_mode < FLY_BY_WIRE_B) {
|
||||
// only use radio_in if the channel is not used as flight_mode_channel
|
||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_flap_auto);
|
||||
} else if (control_mode >= FLY_BY_WIRE_B) {
|
||||
// FIXME: use target_airspeed in both FBW_B and g.airspeed_enabled cases - Doug?
|
||||
|
|
|
@ -499,7 +499,7 @@ static void Log_Read_Attitude()
|
|||
static void Log_Read_Mode()
|
||||
{
|
||||
Serial.printf_P(PSTR("MOD:"));
|
||||
Serial.println(flight_mode_strings[DataFlash.ReadByte()]);
|
||||
print_flight_mode(DataFlash.ReadByte());
|
||||
}
|
||||
|
||||
// Read a GPS packet
|
||||
|
|
|
@ -520,7 +520,7 @@ static void
|
|||
print_switch(byte p, byte m)
|
||||
{
|
||||
Serial.printf_P(PSTR("Pos %d: "),p);
|
||||
Serial.println(flight_mode_strings[m]);
|
||||
print_flight_mode(m);
|
||||
}
|
||||
|
||||
static void
|
||||
|
|
|
@ -567,3 +567,38 @@ static void reboot_apm(void)
|
|||
while (1);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
static void
|
||||
print_flight_mode(uint8_t mode)
|
||||
{
|
||||
switch (mode) {
|
||||
case MANUAL:
|
||||
Serial.println_P(PSTR("Manual"));
|
||||
break;
|
||||
case CIRCLE:
|
||||
Serial.println_P(PSTR("Circle"));
|
||||
break;
|
||||
case STABILIZE:
|
||||
Serial.println_P(PSTR("Stabilize"));
|
||||
break;
|
||||
case FLY_BY_WIRE_A:
|
||||
Serial.println_P(PSTR("FBW_A"));
|
||||
break;
|
||||
case FLY_BY_WIRE_B:
|
||||
Serial.println_P(PSTR("FBW_B"));
|
||||
break;
|
||||
case AUTO:
|
||||
Serial.println_P(PSTR("AUTO"));
|
||||
break;
|
||||
case RTL:
|
||||
Serial.println_P(PSTR("RTL"));
|
||||
break;
|
||||
case LOITER:
|
||||
Serial.println_P(PSTR("Loiter"));
|
||||
break;
|
||||
default:
|
||||
Serial.println_P(PSTR("---"));
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -223,13 +223,13 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
|
|||
|
||||
if(oldSwitchPosition != readSwitch()) {
|
||||
Serial.printf_P(PSTR("CONTROL MODE CHANGED: "));
|
||||
Serial.println(flight_mode_strings[readSwitch()]);
|
||||
print_flight_mode(readSwitch());
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
if(g.throttle_fs_enabled && g.channel_throttle.get_failsafe()) {
|
||||
Serial.printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)g.channel_throttle.radio_in);
|
||||
Serial.println(flight_mode_strings[readSwitch()]);
|
||||
print_flight_mode(readSwitch());
|
||||
fail_test++;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue