From 236e74c529879301b6a3524b109ee53ac40c38bf Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 24 Oct 2017 18:30:10 -0700 Subject: [PATCH] AP_GPS: Singleton --- libraries/AP_GPS/AP_GPS.cpp | 7 +++++++ libraries/AP_GPS/AP_GPS.h | 6 ++++++ 2 files changed, 13 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 46e819d1d8..cf95a70335 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -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. diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index eb97851432..2f20606593 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -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