AP_HAL_Linux: delay signal handlers setup

Allow default signals before full initialization in Linux, this makes sure we don't get an unkillable process if it hangs on initialization

Exit flag marked volatile to counteract possible compiler optimization due to the handler code running in a different context
This commit is contained in:
Oleksiy Protas 2023-12-18 22:52:09 +02:00 committed by Peter Barker
parent f1d37fc051
commit 364e6f06f3
2 changed files with 10 additions and 2 deletions

View File

@ -467,7 +467,11 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
}
}
setup_signal_handlers();
// NOTE: signal handlers are only set before the main loop, so
// that if anything before the loops hangs, the default signals
// can still stop the process proprely, although without proper
// teardown.
// This isn't perfect, but still prevents an unkillable process.
scheduler->init();
gpio->init();
@ -497,6 +501,8 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const
AP_Module::call_hook_setup_complete();
#endif
setup_signal_handlers();
while (!_should_exit) {
callbacks->loop();
}

View File

@ -2,6 +2,8 @@
#include <AP_HAL/AP_HAL.h>
#include <signal.h>
class HAL_Linux : public AP_HAL::HAL {
public:
HAL_Linux();
@ -12,7 +14,7 @@ public:
static void exit_signal_handler(int);
protected:
bool _should_exit = false;
volatile sig_atomic_t _should_exit = false;
};
#if HAL_NUM_CAN_IFACES