AP_Param: add get and set functions

This commit is contained in:
Peter Hall 2019-11-25 16:21:57 +00:00 committed by Andrew Tridgell
parent 623c1aa3cd
commit 5164eacc4a
2 changed files with 44 additions and 0 deletions

View File

@ -2399,6 +2399,39 @@ bool AP_Param::set_by_name(const char *name, float value)
return false; return false;
} }
/*
get a value by name
*/
bool AP_Param::get(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:
value = ((AP_Int8 *)vp)->get();
break;
case AP_PARAM_INT16:
value = ((AP_Int16 *)vp)->get();
break;
case AP_PARAM_INT32:
value = ((AP_Int32 *)vp)->get();
break;
case AP_PARAM_FLOAT:
value = ((AP_Float *)vp)->get();
break;
default:
// not a supported type
return false;
}
return true;
}
/* /*
set and save a value by name set and save a value by name
*/ */

View File

@ -286,6 +286,15 @@ public:
/// @param value The new value /// @param value The new value
/// @return true if the variable is found /// @return true if the variable is found
static bool set_by_name(const char *name, float value); static bool set_by_name(const char *name, float value);
// name helper for scripting
static bool set(const char *name, float value) { return set_by_name(name, value); };
/// gat a value by name, used by scripting
///
/// @param name The full name of the variable to be found.
/// @param value A refernce to the variable
/// @return true if the variable is found
static bool get(const char *name, float &value);
/// set and save a value by name /// set and save a value by name
/// ///
@ -293,6 +302,8 @@ public:
/// @param value The new value /// @param value The new value
/// @return true if the variable is found /// @return true if the variable is found
static bool set_and_save_by_name(const char *name, float value); static bool set_and_save_by_name(const char *name, float value);
// name helper for scripting
static bool set_and_save(const char *name, float value) { return set_and_save_by_name(name, value); };
/// Find a variable by index. /// Find a variable by index.
/// ///