From 1baccdaf853e34505850b532eef3073423a75172 Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 29 Aug 2017 17:18:26 -0700 Subject: [PATCH] AC_InputManager: add static create method --- libraries/AC_InputManager/AC_InputManager.h | 15 ++++++++---- .../AC_InputManager/AC_InputManager_Heli.h | 24 ++++++++++++------- 2 files changed, 27 insertions(+), 12 deletions(-) diff --git a/libraries/AC_InputManager/AC_InputManager.h b/libraries/AC_InputManager/AC_InputManager.h index c68365c7bd..101f68493f 100644 --- a/libraries/AC_InputManager/AC_InputManager.h +++ b/libraries/AC_InputManager/AC_InputManager.h @@ -11,15 +11,22 @@ /// @brief Class managing the pilot's control inputs class AC_InputManager{ public: - AC_InputManager() { - // setup parameter defaults - AP_Param::setup_object_defaults(this, var_info); - } + static AC_InputManager create() { return AC_InputManager{}; } + + constexpr AC_InputManager(AC_InputManager &&other) = default; + + /* Do not allow copies */ + AC_InputManager(const AC_InputManager &other) = delete; + AC_InputManager &operator=(const AC_InputManager&) = delete; static const struct AP_Param::GroupInfo var_info[]; 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 3cedb6aee9..f6013501b3 100644 --- a/libraries/AC_InputManager/AC_InputManager_Heli.h +++ b/libraries/AC_InputManager/AC_InputManager_Heli.h @@ -16,13 +16,13 @@ /// @brief Class managing the pilot's control inputs for Conventional Helicopter class AC_InputManager_Heli : public AC_InputManager { public: - // Constructor - AC_InputManager_Heli(): - AC_InputManager() - { - // setup parameter defaults - AP_Param::setup_object_defaults(this, var_info); - } + static AC_InputManager_Heli create() { return AC_InputManager_Heli{}; } + + constexpr AC_InputManager_Heli(AC_InputManager_Heli &&other) = default; + + /* Do not allow copies */ + AC_InputManager_Heli(const AC_InputManager_Heli &other) = delete; + AC_InputManager_Heli &operator=(const AC_InputManager_Heli&) = delete; // get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes float get_pilot_desired_collective(int16_t control_in); @@ -35,8 +35,16 @@ public: static const struct AP_Param::GroupInfo var_info[]; -private: +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 } _im_flags_heli;