HAL_PX4: prevent excessive writes on startup from blocking

this could cause copter on PX4 to hang on startup
This commit is contained in:
Andrew Tridgell 2013-10-28 16:10:51 +11:00 committed by Randy Mackay
parent eee7a1de22
commit 7c4067e154
3 changed files with 8 additions and 4 deletions

View File

@ -120,6 +120,8 @@ static int main_loop(int argc, char **argv)
*/
set_priority(APM_STARTUP_PRIORITY);
schedulerInstance.hal_initialized();
setup();
hal.scheduler->system_initialized();

View File

@ -231,7 +231,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread)
void *PX4Scheduler::_timer_thread(void)
{
while (system_initializing()) {
while (!_hal_initialized) {
poll(NULL, 0, 1);
}
while (!_px4_thread_should_exit) {
@ -272,7 +272,7 @@ void PX4Scheduler::_run_io(void)
void *PX4Scheduler::_uart_thread(void)
{
while (system_initializing()) {
while (!_hal_initialized) {
poll(NULL, 0, 1);
}
while (!_px4_thread_should_exit) {
@ -288,7 +288,7 @@ void *PX4Scheduler::_uart_thread(void)
void *PX4Scheduler::_io_thread(void)
{
while (system_initializing()) {
while (!_hal_initialized) {
poll(NULL, 0, 1);
}
while (!_px4_thread_should_exit) {

View File

@ -42,9 +42,11 @@ public:
bool in_timerprocess();
bool system_initializing();
void system_initialized();
void hal_initialized() { _hal_initialized = true; }
private:
bool _initialized;
volatile bool _hal_initialized;
AP_HAL::Proc _delay_cb;
uint16_t _min_delay_cb_ms;
AP_HAL::Proc _failsafe;