mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
364e6f06f3
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
26 lines
463 B
C++
26 lines
463 B
C++
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <signal.h>
|
|
|
|
class HAL_Linux : public AP_HAL::HAL {
|
|
public:
|
|
HAL_Linux();
|
|
void run(int argc, char* const* argv, Callbacks* callbacks) const override;
|
|
|
|
void setup_signal_handlers() const;
|
|
|
|
static void exit_signal_handler(int);
|
|
|
|
protected:
|
|
volatile sig_atomic_t _should_exit = false;
|
|
};
|
|
|
|
#if HAL_NUM_CAN_IFACES
|
|
namespace Linux {
|
|
class CANIface;
|
|
}
|
|
typedef Linux::CANIface HAL_CANIface;
|
|
#endif
|