From bd6145af6d91f93b39df6fd7fa0d9cad66767360 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Wed, 30 Aug 2017 00:41:41 -0700 Subject: [PATCH] AP_NavEKF3: add static create method --- libraries/AP_NavEKF3/AP_NavEKF3.h | 24 ++++++++++++++++++------ 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 1ee63163ed..e221294670 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -31,13 +31,23 @@ class NavEKF3_core; class AP_AHRS; -class NavEKF3 -{ -public: +class NavEKF3 { friend class NavEKF3_core; - static const struct AP_Param::GroupInfo var_info[]; - NavEKF3(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng); +public: + static NavEKF3 create(const AP_AHRS *ahrs, + AP_Baro &baro, + const RangeFinder &rng) { + return NavEKF3{ahrs, baro, rng}; + } + + constexpr NavEKF3(NavEKF3 &&other) = default; + + /* Do not allow copies */ + NavEKF3(const NavEKF3 &other) = delete; + NavEKF3 &operator=(const NavEKF3&) = delete; + + static const struct AP_Param::GroupInfo var_info[]; // allow logging to determine the number of active cores uint8_t activeCores(void) const { @@ -349,8 +359,10 @@ public: // get timing statistics structure 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;