AP_NavEKF3: 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:13 +11:00
parent 4d4e66d825
commit c13eaf0c7f

View File

@ -35,13 +35,7 @@ class NavEKF3 {
friend class NavEKF3_core;
public:
static NavEKF3 create(const AP_AHRS *ahrs,
AP_Baro &baro,
const RangeFinder &rng) {
return NavEKF3{ahrs, baro, rng};
}
constexpr NavEKF3(NavEKF3 &&other) = default;
NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
/* Do not allow copies */
NavEKF3(const NavEKF3 &other) = delete;
@ -361,8 +355,6 @@ public:
void getTimingStatistics(int8_t instance, struct ekf_timing &timing);
private:
NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng);
uint8_t num_cores; // number of allocated cores
uint8_t primary; // current primary core
NavEKF3_core *core = nullptr;