From 82dabd18724dddcc3ce29b3a451bfa27f0b5a506 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 11 Jan 2023 13:32:00 +0000 Subject: [PATCH] AP_OSD: use new param defualting method --- libraries/AP_OSD/AP_OSD.h | 15 +++++++-- libraries/AP_OSD/AP_OSD_ParamSetting.cpp | 39 ++++++++++++------------ libraries/AP_OSD/AP_OSD_Setting.cpp | 22 +++++-------- 3 files changed, 41 insertions(+), 35 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index 58e014e031..c55d8eb4df 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -72,11 +72,15 @@ public: AP_Int8 xpos; AP_Int8 ypos; - AP_OSD_Setting(); - AP_OSD_Setting(bool enabled, uint8_t x, uint8_t y); + AP_OSD_Setting(bool enabled = 0, uint8_t x = 0, uint8_t y = 0); // User settable parameters static const struct AP_Param::GroupInfo var_info[]; + +private: + const float default_enabled; + const float default_xpos; + const float default_ypos; }; class AP_OSD; @@ -384,6 +388,13 @@ public: static const struct AP_Param::GroupInfo var_info[]; private: + float default_enabled; + float default_ypos; + float default_param_group; + float default_param_idx; + float default_param_key; + float default_type; + }; /* diff --git a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp index dc0f9865d2..a0294ffe5d 100644 --- a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp @@ -35,7 +35,7 @@ const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = { // @Description: Enable setting // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("_EN", 1, AP_OSD_ParamSetting, enabled, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_EN", 1, AP_OSD_ParamSetting, enabled, default_enabled), // @Param: _X // @DisplayName: X position @@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = { // @Description: Vertical position on screen // @Range: 0 15 // @User: Standard - AP_GROUPINFO("_Y", 3, AP_OSD_ParamSetting, ypos, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_Y", 3, AP_OSD_ParamSetting, ypos, default_ypos), // Parameter access keys. These default to -1 too allow user overrides // to work properly @@ -58,19 +58,19 @@ const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = { // @DisplayName: Parameter key // @Description: Key of the parameter to be displayed and modified // @User: Standard - AP_GROUPINFO("_KEY", 4, AP_OSD_ParamSetting, _param_key, -1), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_KEY", 4, AP_OSD_ParamSetting, _param_key, default_param_key), // @Param: _IDX // @DisplayName: Parameter index // @Description: Index of the parameter to be displayed and modified // @User: Standard - AP_GROUPINFO("_IDX", 5, AP_OSD_ParamSetting, _param_idx, -1), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_IDX", 5, AP_OSD_ParamSetting, _param_idx, default_param_idx), // @Param: _GRP // @DisplayName: Parameter group // @Description: Group of the parameter to be displayed and modified // @User: Standard - AP_GROUPINFO("_GRP", 6, AP_OSD_ParamSetting, _param_group, -1), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_GRP", 6, AP_OSD_ParamSetting, _param_group, default_param_group), // @Param: _MIN // @DisplayName: Parameter minimum @@ -94,7 +94,7 @@ const AP_Param::GroupInfo AP_OSD_ParamSetting::var_info[] = { // @DisplayName: Parameter type // @Description: Type of the parameter to be displayed and modified // @User: Standard - AP_GROUPINFO("_TYPE", 10, AP_OSD_ParamSetting, _type, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_TYPE", 10, AP_OSD_ParamSetting, _type, default_type), AP_GROUPEND }; @@ -237,26 +237,27 @@ const AP_OSD_ParamSetting::ParamMetadata AP_OSD_ParamSetting::_param_metadata[OS extern const AP_HAL::HAL& hal; // default constructor that just sets some sensible defaults that exist on all platforms -AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number) - : _param_number(param_number) +AP_OSD_ParamSetting::AP_OSD_ParamSetting(uint8_t param_number) : + _param_number(param_number), + default_ypos(param_number + 1), + default_param_group(-1), + default_param_idx(-1), + default_param_key(-1) { AP_Param::setup_object_defaults(this, var_info); - - ypos.set(param_number + 1); } // construct a setting from a compact static initializer structure -AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer) - : _param_number(initializer.index) +AP_OSD_ParamSetting::AP_OSD_ParamSetting(const Initializer& initializer) : + _param_number(initializer.index), + default_enabled(true), + default_ypos(initializer.index + 1), + default_param_group(initializer.token.group_element), + default_param_idx(initializer.token.idx), + default_param_key(initializer.token.key), + default_type(initializer.type) { AP_Param::setup_object_defaults(this, var_info); - - enabled.set(true); - ypos.set(initializer.index + 1); - _param_group.set(initializer.token.group_element); - _param_idx.set(initializer.token.idx); - _param_key.set(initializer.token.key); - _type.set(initializer.type); } // update the contained parameter diff --git a/libraries/AP_OSD/AP_OSD_Setting.cpp b/libraries/AP_OSD/AP_OSD_Setting.cpp index 94eda4bb7e..260035a83e 100644 --- a/libraries/AP_OSD/AP_OSD_Setting.cpp +++ b/libraries/AP_OSD/AP_OSD_Setting.cpp @@ -29,36 +29,30 @@ const AP_Param::GroupInfo AP_OSD_Setting::var_info[] = { // @Description: Enable setting // @Values: 0:Disabled,1:Enabled // @User: Standard - AP_GROUPINFO("_EN", 1, AP_OSD_Setting, enabled, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_EN", 1, AP_OSD_Setting, enabled, default_enabled), // @Param: _X // @DisplayName: X position // @Description: Horizontal position on screen // @Range: 0 29 // @User: Standard - AP_GROUPINFO("_X", 2, AP_OSD_Setting, xpos, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_X", 2, AP_OSD_Setting, xpos, default_xpos), // @Param: _Y // @DisplayName: Y position // @Description: Vertical position on screen // @Range: 0 15 // @User: Standard - AP_GROUPINFO("_Y", 3, AP_OSD_Setting, ypos, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("_Y", 3, AP_OSD_Setting, ypos, default_ypos), AP_GROUPEND }; -// constructors -AP_OSD_Setting::AP_OSD_Setting() +// constructor +AP_OSD_Setting::AP_OSD_Setting(bool _enabled, uint8_t x, uint8_t y) : + default_enabled(_enabled), + default_xpos(x), + default_ypos(y) { AP_Param::setup_object_defaults(this, var_info); } - - -AP_OSD_Setting::AP_OSD_Setting(bool _enabled, uint8_t x, uint8_t y) : - AP_OSD_Setting() -{ - enabled.set(_enabled); - xpos.set(x); - ypos.set(y); -}