AP_RPM: 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
16cd31b63a
commit
9b4fef4d50
@ -29,9 +29,7 @@ class AP_RPM
|
||||
friend class AP_RPM_Backend;
|
||||
|
||||
public:
|
||||
static AP_RPM create() { return AP_RPM{}; }
|
||||
|
||||
constexpr AP_RPM(AP_RPM &&other) = default;
|
||||
AP_RPM();
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_RPM(const AP_RPM &other) = delete;
|
||||
@ -95,8 +93,6 @@ public:
|
||||
bool enabled(uint8_t instance) const;
|
||||
|
||||
private:
|
||||
AP_RPM();
|
||||
|
||||
RPM_State state[RPM_MAX_INSTANCES];
|
||||
AP_RPM_Backend *drivers[RPM_MAX_INSTANCES];
|
||||
uint8_t num_instances:2;
|
||||
|
@ -26,7 +26,7 @@ void loop();
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
static AP_RPM RPM = AP_RPM::create();
|
||||
static AP_RPM RPM;
|
||||
|
||||
char sensor_state;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user