mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Airspeed: add AP::airspeed() to get airspeed singleton
This commit is contained in:
parent
4ab13b37ac
commit
59ef486da0
@ -501,3 +501,12 @@ bool AP_Airspeed::all_healthy(void) const
|
||||
|
||||
// singleton instance
|
||||
AP_Airspeed *AP_Airspeed::_singleton;
|
||||
|
||||
namespace AP {
|
||||
|
||||
AP_Airspeed *airspeed()
|
||||
{
|
||||
return AP_Airspeed::get_singleton();
|
||||
}
|
||||
|
||||
};
|
||||
|
@ -248,3 +248,7 @@ private:
|
||||
AP_Airspeed_Backend *sensor[AIRSPEED_MAX_SENSORS];
|
||||
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
AP_Airspeed *airspeed();
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user