AP_Notify:change tonealarm-type bitmask to bool type,
change parameter data type from const uint8_t to uint8_t, initialise tonealarm error flag to value -1 at tonealarm class initiallisation This is a part of a set of fixes for the bugs and typos tridge discovered and shared inside earlier commits for setting up tonealarm.
This commit is contained in:
parent
9f5f5871f2
commit
e48fcf2df7
@ -50,7 +50,7 @@ bool ToneAlarm_Linux::init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// play_tune - play one of the pre-defined tunes
|
// play_tune - play one of the pre-defined tunes
|
||||||
bool ToneAlarm_Linux::play_tune(const uint8_t tune_number)
|
bool ToneAlarm_Linux::play_tune(uint8_t tune_number)
|
||||||
{
|
{
|
||||||
hal.util->toneAlarm_set_tune(tune_number);
|
hal.util->toneAlarm_set_tune(tune_number);
|
||||||
return true;
|
return true;
|
||||||
|
@ -23,6 +23,9 @@
|
|||||||
class ToneAlarm_Linux
|
class ToneAlarm_Linux
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
ToneAlarm_Linux():
|
||||||
|
err(-1)
|
||||||
|
{}
|
||||||
/// init - initialised the tone alarm
|
/// init - initialised the tone alarm
|
||||||
bool init(void);
|
bool init(void);
|
||||||
|
|
||||||
@ -31,18 +34,18 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
/// play_tune - play one of the pre-defined tunes
|
/// play_tune - play one of the pre-defined tunes
|
||||||
bool play_tune(const uint8_t tune_number);
|
bool play_tune(uint8_t tune_number);
|
||||||
|
|
||||||
int err;
|
int err;
|
||||||
|
|
||||||
/// tonealarm_type - bitmask of states we track
|
/// tonealarm_type - bitmask of states we track
|
||||||
struct tonealarm_type {
|
struct tonealarm_type {
|
||||||
uint8_t armed : 1; // 0 = disarmed, 1 = armed
|
bool armed : true; // false = disarmed, true = armed
|
||||||
uint8_t failsafe_battery : 1; // 1 if battery failsafe
|
bool failsafe_battery : true; // true if battery failsafe
|
||||||
uint8_t gps_glitching : 1; // 1 if gps position is not good
|
bool gps_glitching : true; // true if gps position is not good
|
||||||
uint8_t failsafe_gps : 1; // 1 if gps failsafe
|
bool failsafe_gps : true; // true if gps failsafe
|
||||||
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
|
bool arming_failed : true; // false = failing checks, true = passed
|
||||||
uint8_t parachute_release : 1; // 1 if parachute is being released
|
bool parachute_release : true; // true if parachute is being released
|
||||||
} flags;
|
} flags;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user