Browse Source

HAL_PX4: use write() in panic()

this allows panic from the UARTDriver
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
1e69b88261
  1. 5
      libraries/AP_HAL_PX4/Scheduler.cpp

5
libraries/AP_HAL_PX4/Scheduler.cpp

@ -183,9 +183,8 @@ void PX4Scheduler::_timer_event(void *arg)
} }
void PX4Scheduler::panic(const prog_char_t *errormsg) { void PX4Scheduler::panic(const prog_char_t *errormsg) {
hal.console->println_P(errormsg); write(1, errormsg, strlen(errormsg));
hal.scheduler->usleep(10000); hal.scheduler->delay_microseconds(10000);
fflush(stdout);
exit(1); exit(1);
} }

Loading…
Cancel
Save