AP_HAL_Linux_Class: Correct deadlock, and infinite loop in setup()

(credit to Mitch Miers <mmiers@mmiers.com>):

setup() is attempting to initialize the hardware, and while doing so
is attempting to output some text via the console (and maybe mavlink
data).  The problem is, the output isn't going to complete once a
write buffer is full, because LinuxUARTDriver::_timer_tick() doesn't
perform work until _initialized is true.  So, what happens is,
setup() (and subroutines) call LinuxUARTDriver::_write(uint8_t c),
which loops waiting for buffer space to become available (once the
write buffer is full).  The buffer never gets space, because the
UART thread is waiting for initialization to complete before it
will write out data and drain the buffer, but that doesn't happen
until setup() returns (see AP_HAL_Linux_main.h).

Refer to https://groups.google.com/forum/#!topic/beaglepilot/dQlxse11JNI
This commit is contained in:
Víctor Mayoral Vilches 2014-05-02 11:57:19 +02:00 committed by Andrew Tridgell
parent fac3d1c271
commit 9f5b4ffca4

View File

@ -7,10 +7,9 @@
#define AP_HAL_MAIN() extern "C" {\
int main (int argc, char * const argv[]) { \
hal.init(argc, argv); \
setup();\
hal.scheduler->system_initialized(); \
for(;;) { loop(); \
hal.scheduler->delay_microseconds(500); } \
setup();\
for(;;) loop();\
return 0;\
}\
}