Skip to content
Snippets Groups Projects
Commit 0d6b8479 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

AP_Notify: grab initial flags state in init()

this prevents annoying tones on startup of APM:Plane
parent 95a696ea
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment