mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: improved queue handling and added set_and_save_by_name_ifchanged
This commit is contained in:
parent
d8575f0607
commit
23785c00dc
@ -1207,8 +1207,8 @@ void AP_Param::save(bool force_save)
|
|||||||
}
|
}
|
||||||
while (!save_queue.push(p)) {
|
while (!save_queue.push(p)) {
|
||||||
// if we can't save to the queue
|
// if we can't save to the queue
|
||||||
if (hal.util->get_soft_armed() || !hal.scheduler->in_main_thread()) {
|
if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) {
|
||||||
// if we are armed then don't sleep, instead we lose the
|
// if we are armed in main thread then don't sleep, instead we lose the
|
||||||
// parameter save
|
// parameter save
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -2567,6 +2567,36 @@ bool AP_Param::set_and_save_by_name(const char *name, float value)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set and save a value by name
|
||||||
|
*/
|
||||||
|
bool AP_Param::set_and_save_by_name_ifchanged(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_ifchanged(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT16:
|
||||||
|
((AP_Int16 *)vp)->set_and_save_ifchanged(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_INT32:
|
||||||
|
((AP_Int32 *)vp)->set_and_save_ifchanged(value);
|
||||||
|
return true;
|
||||||
|
case AP_PARAM_FLOAT:
|
||||||
|
((AP_Float *)vp)->set_and_save_ifchanged(value);
|
||||||
|
return true;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
// not a supported type
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
#if AP_PARAM_KEY_DUMP
|
#if AP_PARAM_KEY_DUMP
|
||||||
/*
|
/*
|
||||||
do not remove this show_all() code, it is essential for debugging
|
do not remove this show_all() code, it is essential for debugging
|
||||||
|
@ -304,6 +304,7 @@ 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);
|
||||||
|
static bool set_and_save_by_name_ifchanged(const char *name, float value);
|
||||||
// name helper for scripting
|
// name helper for scripting
|
||||||
static bool set_and_save(const char *name, float value) { return set_and_save_by_name(name, value); };
|
static bool set_and_save(const char *name, float value) { return set_and_save_by_name(name, value); };
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user