AP_Compass: 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 573a5bf3d0
commit f326377a5c
2 changed files with 3 additions and 7 deletions

View File

@ -44,9 +44,7 @@ class Compass
{
friend class AP_Compass_Backend;
public:
static Compass create() { return Compass{}; }
constexpr Compass(Compass &&other) = default;
Compass();
/* Do not allow copies */
Compass(const Compass &other) = delete;
@ -293,8 +291,6 @@ public:
}
private:
Compass();
/// Register a new compas driver, allocating an instance number
///
/// @return number of compass instances

View File

@ -9,8 +9,8 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
static AP_BoardConfig board_config = AP_BoardConfig::create();
static Compass compass = Compass::create();
static AP_BoardConfig board_config;
static Compass compass;
uint32_t timer;