mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_Notify: grab initial flags state in init()
this prevents annoying tones on startup of APM:Plane
This commit is contained in:
parent
95a696ea36
commit
0d6b847966
@ -41,6 +41,11 @@ bool ToneAlarm_PX4::init()
|
||||
hal.console->printf("Unable to open " TONEALARM_DEVICE_PATH);
|
||||
return false;
|
||||
}
|
||||
|
||||
// set initial boot states. This prevents us issueing a arming
|
||||
// warning in plane and rover on every boot
|
||||
flags.armed = AP_Notify::flags.armed;
|
||||
flags.failsafe_battery = AP_Notify::flags.failsafe_battery;
|
||||
return true;
|
||||
}
|
||||
|
||||
@ -56,7 +61,7 @@ bool ToneAlarm_PX4::play_tune(const uint8_t tune_number)
|
||||
void ToneAlarm_PX4::update()
|
||||
{
|
||||
// exit immediately if we haven't initialised successfully
|
||||
if (_tonealarm_fd <= 0 ) {
|
||||
if (_tonealarm_fd == -1) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -26,13 +26,13 @@ public:
|
||||
/// init - initialised the tone alarm
|
||||
bool init(void);
|
||||
|
||||
/// play_tune - play one of the pre-defined tunes
|
||||
bool play_tune(const uint8_t tune_number);
|
||||
|
||||
/// update - updates led according to timed_updated. Should be called at 50Hz
|
||||
void update();
|
||||
|
||||
private:
|
||||
/// play_tune - play one of the pre-defined tunes
|
||||
bool play_tune(const uint8_t tune_number);
|
||||
|
||||
int _tonealarm_fd; // file descriptor for the tone alarm
|
||||
|
||||
/// tonealarm_type - bitmask of states we track
|
||||
|
Loading…
Reference in New Issue
Block a user