mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_Param: added set_enable() API
used to set value of an enable parameter, clearing count cache
This commit is contained in:
parent
7e010ef50a
commit
766fb32292
@ -1074,7 +1074,7 @@ void AP_Param::save_sync(bool force_save)
|
|||||||
|
|
||||||
if (phdr.type == AP_PARAM_INT8 && ginfo != nullptr && (ginfo->flags & AP_PARAM_FLAG_ENABLE)) {
|
if (phdr.type == AP_PARAM_INT8 && ginfo != nullptr && (ginfo->flags & AP_PARAM_FLAG_ENABLE)) {
|
||||||
// clear cached parameter count
|
// clear cached parameter count
|
||||||
_parameter_count = 0;
|
invalidate_count();
|
||||||
}
|
}
|
||||||
|
|
||||||
char name[AP_MAX_NAME_SIZE+1];
|
char name[AP_MAX_NAME_SIZE+1];
|
||||||
@ -1476,7 +1476,7 @@ void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct
|
|||||||
uint16_t key;
|
uint16_t key;
|
||||||
|
|
||||||
// reset cached param counter as we may be loading a dynamic var_info
|
// reset cached param counter as we may be loading a dynamic var_info
|
||||||
_parameter_count = 0;
|
invalidate_count();
|
||||||
|
|
||||||
if (!find_key_by_pointer(object_pointer, key)) {
|
if (!find_key_by_pointer(object_pointer, key)) {
|
||||||
hal.console->printf("ERROR: Unable to find param pointer\n");
|
hal.console->printf("ERROR: Unable to find param pointer\n");
|
||||||
@ -2340,6 +2340,14 @@ uint16_t AP_Param::count_parameters(void)
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
invalidate parameter count cache
|
||||||
|
*/
|
||||||
|
void AP_Param::invalidate_count(void)
|
||||||
|
{
|
||||||
|
_parameter_count = 0;
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
set a default value by name
|
set a default value by name
|
||||||
*/
|
*/
|
||||||
|
@ -478,6 +478,9 @@ public:
|
|||||||
// count of parameters in tree
|
// count of parameters in tree
|
||||||
static uint16_t count_parameters(void);
|
static uint16_t count_parameters(void);
|
||||||
|
|
||||||
|
// invalidate parameter count
|
||||||
|
static void invalidate_count(void);
|
||||||
|
|
||||||
static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }
|
static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }
|
||||||
|
|
||||||
// set frame type flags. Used to unhide frame specific parameters
|
// set frame type flags. Used to unhide frame specific parameters
|
||||||
@ -735,6 +738,14 @@ public:
|
|||||||
_value = v;
|
_value = v;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// set a parameter that is an ENABLE param
|
||||||
|
void set_enable(const T &v) {
|
||||||
|
if (v != _value) {
|
||||||
|
invalidate_count();
|
||||||
|
}
|
||||||
|
_value = v;
|
||||||
|
}
|
||||||
|
|
||||||
/// Sets if the parameter is unconfigured
|
/// Sets if the parameter is unconfigured
|
||||||
///
|
///
|
||||||
void set_default(const T &v) {
|
void set_default(const T &v) {
|
||||||
|
Loading…
Reference in New Issue
Block a user