mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
AP_Param: Add set_by_name and set_and_save_by_name helpers
This commit is contained in:
parent
d4c34323f3
commit
ef51ac9b64
@ -2030,3 +2030,63 @@ bool AP_Param::set_default_by_name(const char *name, float value)
|
|||||||
// not a supported type
|
// not a supported type
|
||||||
return false;
|
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;
|
||||||
|
}
|
||||||
|
@ -237,6 +237,20 @@ public:
|
|||||||
/// @return true if the variable is found
|
/// @return true if the variable is found
|
||||||
static bool set_default_by_name(const char *name, float value);
|
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.
|
/// Find a variable by index.
|
||||||
///
|
///
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user