mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_Notify: fix wrong boolean check
Check by false instead of checking by -1. Fix the following compiler warning with gcc 5.1.0: ardupilot/libraries/AP_Notify/ToneAlarm_Linux.cpp:64:13: warning: comparison of constant '-1' with boolean expression is always false [-Wbool-compare] if (err == -1) { ^ Also change the initialization code not to use -1.
This commit is contained in:
parent
bb534c20b5
commit
3f8dab41c4
@ -61,7 +61,7 @@ bool ToneAlarm_Linux::play_tune(uint8_t tune_number)
|
||||
void ToneAlarm_Linux::update()
|
||||
{
|
||||
// exit immediately if we haven't initialised successfully
|
||||
if (err == -1) {
|
||||
if (err) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -23,9 +23,9 @@
|
||||
class ToneAlarm_Linux: public NotifyDevice
|
||||
{
|
||||
public:
|
||||
ToneAlarm_Linux():
|
||||
err(-1)
|
||||
{}
|
||||
ToneAlarm_Linux() : err(true)
|
||||
{ }
|
||||
|
||||
/// init - initialised the tone alarm
|
||||
bool init(void);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user