mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: Create a singleton
This commit is contained in:
parent
338af9e142
commit
a46c60f4de
|
@ -201,6 +201,11 @@ AP_Airspeed::AP_Airspeed()
|
|||
state[i].EAS2TAS = 1;
|
||||
}
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("AP_Airspeed must be singleton");
|
||||
}
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
|
||||
|
@ -449,3 +454,7 @@ bool AP_Airspeed::all_healthy(void) const
|
|||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
AP_Airspeed *AP_Airspeed::_singleton;
|
||||
|
||||
|
|
|
@ -164,8 +164,11 @@ public:
|
|||
|
||||
// get current primary sensor
|
||||
uint8_t get_primary(void) const { return primary; }
|
||||
|
||||
static AP_Airspeed *get_singleton() { return _singleton; }
|
||||
|
||||
private:
|
||||
static AP_Airspeed *_singleton;
|
||||
|
||||
AP_Int8 primary_sensor;
|
||||
|
||||
|
|
Loading…
Reference in New Issue