From d5896287b791901de9f02f6402ab6d998eceb5eb Mon Sep 17 00:00:00 2001 From: Jacob Walser Date: Fri, 20 Oct 2017 14:10:09 -0400 Subject: [PATCH] AP_Param: Add set_by_name and set_and_save_by_name helpers --- libraries/AP_Param/AP_Param.cpp | 60 +++++++++++++++++++++++++++++++++ libraries/AP_Param/AP_Param.h | 14 ++++++++ 2 files changed, 74 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 9eabef8c59..a2c471669c 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1984,3 +1984,63 @@ bool AP_Param::set_default_by_name(const char *name, float value) // not a supported type return false; } + +/* + set a value by name + */ +bool AP_Param::set_by_name(const char *name, float value) +{ + enum ap_var_type vtype; + AP_Param *vp = find(name, &vtype); + if (vp == nullptr) { + return false; + } + switch (vtype) { + case AP_PARAM_INT8: + ((AP_Int8 *)vp)->set(value); + return true; + case AP_PARAM_INT16: + ((AP_Int16 *)vp)->set(value); + return true; + case AP_PARAM_INT32: + ((AP_Int32 *)vp)->set(value); + return true; + case AP_PARAM_FLOAT: + ((AP_Float *)vp)->set(value); + return true; + default: + break; + } + // not a supported type + return false; +} + +/* + set and save a value by name + */ +bool AP_Param::set_and_save_by_name(const char *name, float value) +{ + enum ap_var_type vtype; + AP_Param *vp = find(name, &vtype); + if (vp == nullptr) { + return false; + } + switch (vtype) { + case AP_PARAM_INT8: + ((AP_Int8 *)vp)->set_and_save(value); + return true; + case AP_PARAM_INT16: + ((AP_Int16 *)vp)->set_and_save(value); + return true; + case AP_PARAM_INT32: + ((AP_Int32 *)vp)->set_and_save(value); + return true; + case AP_PARAM_FLOAT: + ((AP_Float *)vp)->set_and_save(value); + return true; + default: + break; + } + // not a supported type + return false; +} diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 54f6457835..d6cc45099a 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -240,6 +240,20 @@ public: /// @return true if the variable is found static bool set_default_by_name(const char *name, float value); + /// set a value by name + /// + /// @param name The full name of the variable to be found. + /// @param value The new value + /// @return true if the variable is found + static bool set_by_name(const char *name, float value); + + /// set and save a value by name + /// + /// @param name The full name of the variable to be found. + /// @param value The new value + /// @return true if the variable is found + static bool set_and_save_by_name(const char *name, float value); + /// Find a variable by index. /// ///