AP_Param: make configured() const

This commit is contained in:
Peter Barker 2017-01-20 13:29:17 +11:00 committed by Randy Mackay
parent ab13b3beaf
commit a481e52861
2 changed files with 5 additions and 5 deletions

View File

@ -1070,7 +1070,7 @@ bool AP_Param::load(void)
return true; return true;
} }
bool AP_Param::configured_in_storage(void) bool AP_Param::configured_in_storage(void) const
{ {
uint32_t group_element = 0; uint32_t group_element = 0;
const struct GroupInfo *ginfo; const struct GroupInfo *ginfo;
@ -1100,7 +1100,7 @@ bool AP_Param::configured_in_storage(void)
return scan(&phdr, &ofs) && (phdr.type == AP_PARAM_VECTOR3F || idx == 0); return scan(&phdr, &ofs) && (phdr.type == AP_PARAM_VECTOR3F || idx == 0);
} }
bool AP_Param::configured_in_defaults_file(void) bool AP_Param::configured_in_defaults_file(void) const
{ {
uint32_t group_element = 0; uint32_t group_element = 0;
const struct GroupInfo *ginfo; const struct GroupInfo *ginfo;

View File

@ -350,13 +350,13 @@ public:
static bool check_var_info(void); static bool check_var_info(void);
// return true if the parameter is configured in the defaults file // return true if the parameter is configured in the defaults file
bool configured_in_defaults_file(void); bool configured_in_defaults_file(void) const;
// return true if the parameter is configured in EEPROM/FRAM // return true if the parameter is configured in EEPROM/FRAM
bool configured_in_storage(void); bool configured_in_storage(void) const;
// return true if the parameter is configured // return true if the parameter is configured
bool configured(void) { return configured_in_defaults_file() || configured_in_storage(); } bool configured(void) const { return configured_in_defaults_file() || configured_in_storage(); }
// count of parameters in tree // count of parameters in tree
static uint16_t count_parameters(void); static uint16_t count_parameters(void);