Browse Source

Plane: print flight mode as string in logs

mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
2e5834cc7f
  1. 1
      ArduPlane/ArduPlane.pde
  2. 4
      ArduPlane/Log.pde
  3. 3
      ArduPlane/setup.pde
  4. 22
      ArduPlane/system.pde
  5. 6
      ArduPlane/test.pde

1
ArduPlane/ArduPlane.pde

@ -107,6 +107,7 @@ static Parameters g;
// prototypes // prototypes
static void update_events(void); static void update_events(void);
void gcs_send_text_fmt(const prog_char_t *fmt, ...); void gcs_send_text_fmt(const prog_char_t *fmt, ...);
static void print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode);
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////

4
ArduPlane/Log.pde

@ -458,7 +458,9 @@ static void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page)
DataFlash.LogReadProcess(log_num, start_page, end_page, DataFlash.LogReadProcess(log_num, start_page, end_page,
sizeof(log_structure)/sizeof(log_structure[0]), sizeof(log_structure)/sizeof(log_structure[0]),
log_structure, cliSerial); log_structure,
print_flight_mode,
cliSerial);
} }
// start a new log // start a new log

3
ArduPlane/setup.pde

@ -561,7 +561,8 @@ static void
print_switch(uint8_t p, uint8_t m) print_switch(uint8_t p, uint8_t m)
{ {
cliSerial->printf_P(PSTR("Pos %d: "),p); cliSerial->printf_P(PSTR("Pos %d: "),p);
print_flight_mode(m); print_flight_mode(cliSerial, m);
cliSerial->println();
} }
static void static void

22
ArduPlane/system.pde

@ -594,38 +594,38 @@ static void reboot_apm(void)
static void static void
print_flight_mode(uint8_t mode) print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{ {
switch (mode) { switch (mode) {
case MANUAL: case MANUAL:
cliSerial->println_P(PSTR("Manual")); port->print_P(PSTR("Manual"));
break; break;
case CIRCLE: case CIRCLE:
cliSerial->println_P(PSTR("Circle")); port->print_P(PSTR("Circle"));
break; break;
case STABILIZE: case STABILIZE:
cliSerial->println_P(PSTR("Stabilize")); port->print_P(PSTR("Stabilize"));
break; break;
case TRAINING: case TRAINING:
cliSerial->println_P(PSTR("Training")); port->print_P(PSTR("Training"));
break; break;
case FLY_BY_WIRE_A: case FLY_BY_WIRE_A:
cliSerial->println_P(PSTR("FBW_A")); port->print_P(PSTR("FBW_A"));
break; break;
case FLY_BY_WIRE_B: case FLY_BY_WIRE_B:
cliSerial->println_P(PSTR("FBW_B")); port->print_P(PSTR("FBW_B"));
break; break;
case AUTO: case AUTO:
cliSerial->println_P(PSTR("AUTO")); port->print_P(PSTR("AUTO"));
break; break;
case RTL: case RTL:
cliSerial->println_P(PSTR("RTL")); port->print_P(PSTR("RTL"));
break; break;
case LOITER: case LOITER:
cliSerial->println_P(PSTR("Loiter")); port->print_P(PSTR("Loiter"));
break; break;
default: default:
cliSerial->println_P(PSTR("---")); port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
break; break;
} }
} }

6
ArduPlane/test.pde

@ -227,13 +227,15 @@ test_failsafe(uint8_t argc, const Menu::arg *argv)
if(oldSwitchPosition != readSwitch()) { if(oldSwitchPosition != readSwitch()) {
cliSerial->printf_P(PSTR("CONTROL MODE CHANGED: ")); cliSerial->printf_P(PSTR("CONTROL MODE CHANGED: "));
print_flight_mode(readSwitch()); print_flight_mode(cliSerial, readSwitch());
cliSerial->println();
fail_test++; fail_test++;
} }
if(g.throttle_fs_enabled && g.channel_throttle.get_failsafe()) { if(g.throttle_fs_enabled && g.channel_throttle.get_failsafe()) {
cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)g.channel_throttle.radio_in); cliSerial->printf_P(PSTR("THROTTLE FAILSAFE ACTIVATED: %d, "), (int)g.channel_throttle.radio_in);
print_flight_mode(readSwitch()); print_flight_mode(cliSerial, readSwitch());
cliSerial->println();
fail_test++; fail_test++;
} }

Loading…
Cancel
Save