From 25c409d4a26fc02db6d483e06d193a460c32313b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 13 Dec 2017 12:06:10 +1100 Subject: [PATCH] AC_InputManager: 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 --- libraries/AC_InputManager/AC_InputManager.h | 12 ++++-------- .../AC_InputManager/AC_InputManager_Heli.h | 19 +++++++------------ 2 files changed, 11 insertions(+), 20 deletions(-) diff --git a/libraries/AC_InputManager/AC_InputManager.h b/libraries/AC_InputManager/AC_InputManager.h index 101f68493f..ac154b81c4 100644 --- a/libraries/AC_InputManager/AC_InputManager.h +++ b/libraries/AC_InputManager/AC_InputManager.h @@ -11,9 +11,10 @@ /// @brief Class managing the pilot's control inputs class AC_InputManager{ public: - static AC_InputManager create() { return AC_InputManager{}; } - - constexpr AC_InputManager(AC_InputManager &&other) = default; + AC_InputManager() { + // setup parameter defaults + AP_Param::setup_object_defaults(this, var_info); + } /* Do not allow copies */ AC_InputManager(const AC_InputManager &other) = delete; @@ -23,11 +24,6 @@ public: void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; } protected: - AC_InputManager() { - // setup parameter defaults - AP_Param::setup_object_defaults(this, var_info); - } - // internal variables uint16_t _loop_rate; // rate at which output() function is called (normally 400hz) diff --git a/libraries/AC_InputManager/AC_InputManager_Heli.h b/libraries/AC_InputManager/AC_InputManager_Heli.h index f6013501b3..a4a7f4a03a 100644 --- a/libraries/AC_InputManager/AC_InputManager_Heli.h +++ b/libraries/AC_InputManager/AC_InputManager_Heli.h @@ -16,9 +16,13 @@ /// @brief Class managing the pilot's control inputs for Conventional Helicopter class AC_InputManager_Heli : public AC_InputManager { public: - static AC_InputManager_Heli create() { return AC_InputManager_Heli{}; } - - constexpr AC_InputManager_Heli(AC_InputManager_Heli &&other) = default; + // Constructor + AC_InputManager_Heli() + : AC_InputManager() + { + // setup parameter defaults + AP_Param::setup_object_defaults(this, var_info); + } /* Do not allow copies */ AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete; @@ -35,15 +39,6 @@ public: static const struct AP_Param::GroupInfo var_info[]; -protected: - // Constructor - AC_InputManager_Heli() - : AC_InputManager() - { - // setup parameter defaults - AP_Param::setup_object_defaults(this, var_info); - } - private: struct InputManagerHeliFlags { uint8_t use_stab_col : 1; // 1 if we should use Stabilise mode collective range, 0 for Acro range