AP_GPS: add static create method
This commit is contained in:
parent
87b30b4552
commit
2cb2727a31
@ -47,8 +47,6 @@ class AP_GPS_Backend;
|
|||||||
/// GPS driver main class
|
/// GPS driver main class
|
||||||
class AP_GPS
|
class AP_GPS
|
||||||
{
|
{
|
||||||
public:
|
|
||||||
|
|
||||||
friend class AP_GPS_ERB;
|
friend class AP_GPS_ERB;
|
||||||
friend class AP_GPS_GSOF;
|
friend class AP_GPS_GSOF;
|
||||||
friend class AP_GPS_MAV;
|
friend class AP_GPS_MAV;
|
||||||
@ -65,8 +63,14 @@ public:
|
|||||||
friend class AP_GPS_UBLOX;
|
friend class AP_GPS_UBLOX;
|
||||||
friend class AP_GPS_Backend;
|
friend class AP_GPS_Backend;
|
||||||
|
|
||||||
// constructor
|
public:
|
||||||
AP_GPS();
|
static AP_GPS create() { return AP_GPS{}; }
|
||||||
|
|
||||||
|
constexpr AP_GPS(AP_GPS &&other) = default;
|
||||||
|
|
||||||
|
/* Do not allow copies */
|
||||||
|
AP_GPS(const AP_GPS &other) = delete;
|
||||||
|
AP_GPS &operator=(const AP_GPS&) = delete;
|
||||||
|
|
||||||
// GPS driver types
|
// GPS driver types
|
||||||
enum GPS_Type {
|
enum GPS_Type {
|
||||||
@ -426,6 +430,8 @@ protected:
|
|||||||
uint32_t _log_gps_bit = -1;
|
uint32_t _log_gps_bit = -1;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
AP_GPS();
|
||||||
|
|
||||||
// returns the desired gps update rate in milliseconds
|
// returns the desired gps update rate in milliseconds
|
||||||
// this does not provide any guarantee that the GPS is updating at the requested
|
// 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
|
// rate it is simply a helper for use in the backends for determining what rate
|
||||||
|
Loading…
Reference in New Issue
Block a user