AP_GPS: removed create() method for objects

See discussion here:

  https://github.com/ArduPilot/ardupilot/issues/7331

we were getting some uninitialised variables. While it only showed up in
AP_SbusOut, it means we can't be sure it won't happen on other objects,
so safest to remove the approach

Thanks to assistance from Lucas, Peter and Francisco
This commit is contained in:
Andrew Tridgell 2017-12-13 12:06:12 +11:00
parent c618a27ee0
commit d2c9e2719e
2 changed files with 4 additions and 8 deletions

View File

@ -64,9 +64,7 @@ class AP_GPS
friend class AP_GPS_Backend;
public:
static AP_GPS create() { return AP_GPS{}; }
constexpr AP_GPS(AP_GPS &&other) = default;
AP_GPS();
/* Do not allow copies */
AP_GPS(const AP_GPS &other) = delete;
@ -445,8 +443,6 @@ protected:
uint32_t _log_gps_bit = -1;
private:
AP_GPS();
static AP_GPS *_singleton;
// returns the desired gps update rate in milliseconds

View File

@ -36,15 +36,15 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_BoardConfig board_config = AP_BoardConfig::create();
static AP_BoardConfig board_config;
// create board led object
AP_BoardLED board_led;
// This example uses GPS system. Create it.
static AP_GPS gps = AP_GPS::create();
static AP_GPS gps;
// Serial manager is needed for UART comunications
static AP_SerialManager serial_manager = AP_SerialManager::create();
static AP_SerialManager serial_manager;
void setup()