Browse Source

AP_Param: make configured() const

master
Peter Barker 8 years ago committed by Randy Mackay
parent
commit
a481e52861
  1. 4
      libraries/AP_Param/AP_Param.cpp
  2. 6
      libraries/AP_Param/AP_Param.h

4
libraries/AP_Param/AP_Param.cpp

@ -1070,7 +1070,7 @@ bool AP_Param::load(void) @@ -1070,7 +1070,7 @@ bool AP_Param::load(void)
return true;
}
bool AP_Param::configured_in_storage(void)
bool AP_Param::configured_in_storage(void) const
{
uint32_t group_element = 0;
const struct GroupInfo *ginfo;
@ -1100,7 +1100,7 @@ bool AP_Param::configured_in_storage(void) @@ -1100,7 +1100,7 @@ bool AP_Param::configured_in_storage(void)
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;
const struct GroupInfo *ginfo;

6
libraries/AP_Param/AP_Param.h

@ -350,13 +350,13 @@ public: @@ -350,13 +350,13 @@ public:
static bool check_var_info(void);
// 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
bool configured_in_storage(void);
bool configured_in_storage(void) const;
// 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
static uint16_t count_parameters(void);

Loading…
Cancel
Save