mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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:
parent
573a5bf3d0
commit
f326377a5c
@ -44,9 +44,7 @@ class Compass
|
|||||||
{
|
{
|
||||||
friend class AP_Compass_Backend;
|
friend class AP_Compass_Backend;
|
||||||
public:
|
public:
|
||||||
static Compass create() { return Compass{}; }
|
Compass();
|
||||||
|
|
||||||
constexpr Compass(Compass &&other) = default;
|
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
Compass(const Compass &other) = delete;
|
Compass(const Compass &other) = delete;
|
||||||
@ -293,8 +291,6 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Compass();
|
|
||||||
|
|
||||||
/// Register a new compas driver, allocating an instance number
|
/// Register a new compas driver, allocating an instance number
|
||||||
///
|
///
|
||||||
/// @return number of compass instances
|
/// @return number of compass instances
|
||||||
|
@ -9,8 +9,8 @@
|
|||||||
|
|
||||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
static AP_BoardConfig board_config = AP_BoardConfig::create();
|
static AP_BoardConfig board_config;
|
||||||
static Compass compass = Compass::create();
|
static Compass compass;
|
||||||
|
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user