mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: 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
3d2c81ff05
commit
4d4e66d825
|
@ -38,13 +38,7 @@ class NavEKF2 {
|
||||||
friend class NavEKF2_core;
|
friend class NavEKF2_core;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static NavEKF2 create(const AP_AHRS *ahrs,
|
NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
|
||||||
AP_Baro &baro,
|
|
||||||
const RangeFinder &rng) {
|
|
||||||
return NavEKF2{ahrs, baro, rng};
|
|
||||||
}
|
|
||||||
|
|
||||||
constexpr NavEKF2(NavEKF2 &&other) = default;
|
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
NavEKF2(const NavEKF2 &other) = delete;
|
NavEKF2(const NavEKF2 &other) = delete;
|
||||||
|
@ -330,8 +324,6 @@ public:
|
||||||
void getTimingStatistics(int8_t instance, struct ekf_timing &timing);
|
void getTimingStatistics(int8_t instance, struct ekf_timing &timing);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
|
|
||||||
|
|
||||||
uint8_t num_cores; // number of allocated cores
|
uint8_t num_cores; // number of allocated cores
|
||||||
uint8_t primary; // current primary core
|
uint8_t primary; // current primary core
|
||||||
NavEKF2_core *core = nullptr;
|
NavEKF2_core *core = nullptr;
|
||||||
|
|
Loading…
Reference in New Issue