mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: Singleton
This commit is contained in:
parent
c856cc6f33
commit
236e74c529
@ -61,6 +61,8 @@ const uint32_t AP_GPS::_baudrates[] = {4800U, 19200U, 38400U, 115200U, 57600U, 9
|
||||
// right mode
|
||||
const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY;
|
||||
|
||||
AP_GPS *AP_GPS::_singleton;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo AP_GPS::var_info[] = {
|
||||
// @Param: TYPE
|
||||
@ -267,6 +269,11 @@ AP_GPS::AP_GPS()
|
||||
"GPS initilisation blob is to large to be completely sent before the baud rate changes");
|
||||
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("AP_GPS must be singleton");
|
||||
}
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
/// Startup initialisation.
|
||||
|
@ -72,6 +72,10 @@ public:
|
||||
AP_GPS(const AP_GPS &other) = delete;
|
||||
AP_GPS &operator=(const AP_GPS&) = delete;
|
||||
|
||||
static AP_GPS &gps() {
|
||||
return *_singleton;
|
||||
}
|
||||
|
||||
// GPS driver types
|
||||
enum GPS_Type {
|
||||
GPS_TYPE_NONE = 0,
|
||||
@ -443,6 +447,8 @@ protected:
|
||||
private:
|
||||
AP_GPS();
|
||||
|
||||
static AP_GPS *_singleton;
|
||||
|
||||
// returns the desired gps update rate in milliseconds
|
||||
// this does not provide any guarantee that the GPS is updating at the requested
|
||||
// rate it is simply a helper for use in the backends for determining what rate
|
||||
|
Loading…
Reference in New Issue
Block a user