mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_InertialSensor: 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
d2c9e2719e
commit
99499dece2
@ -49,9 +49,7 @@ class AP_InertialSensor : AP_AccelCal_Client
|
||||
friend class AP_InertialSensor_Backend;
|
||||
|
||||
public:
|
||||
static AP_InertialSensor create() { return AP_InertialSensor{}; }
|
||||
|
||||
constexpr AP_InertialSensor(AP_InertialSensor &&other) = default;
|
||||
AP_InertialSensor();
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_InertialSensor(const AP_InertialSensor &other) = delete;
|
||||
@ -346,8 +344,6 @@ public:
|
||||
BatchSampler batchsampler{*this};
|
||||
|
||||
private:
|
||||
AP_InertialSensor();
|
||||
|
||||
// load backend drivers
|
||||
bool _add_backend(AP_InertialSensor_Backend *backend);
|
||||
void _start_backends();
|
||||
|
@ -8,13 +8,13 @@
|
||||
|
||||
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||
|
||||
static AP_InertialSensor ins = AP_InertialSensor::create();
|
||||
static AP_InertialSensor ins;
|
||||
|
||||
static void display_offsets_and_scaling();
|
||||
static void run_test();
|
||||
|
||||
// board specific config
|
||||
static AP_BoardConfig BoardConfig = AP_BoardConfig::create();
|
||||
static AP_BoardConfig BoardConfig;
|
||||
|
||||
void setup(void);
|
||||
void loop(void);
|
||||
|
Loading…
Reference in New Issue
Block a user