mirror of https://github.com/ArduPilot/ardupilot
AP_Param: added an initialised() method
this will be used by the compass code
This commit is contained in:
parent
677df0fe1c
commit
6f080742b8
|
@ -206,6 +206,12 @@ bool AP_Param::setup(const AP_Param::Info *info, uint8_t num_vars, uint16_t eepr
|
|||
return true;
|
||||
}
|
||||
|
||||
// check if AP_Param has been initialised
|
||||
bool AP_Param::initialised(void)
|
||||
{
|
||||
return _var_info != NULL;
|
||||
}
|
||||
|
||||
// find the info structure given a header and a group_info table
|
||||
// return the Info structure and a pointer to the variables storage
|
||||
const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header phdr, void **ptr,
|
||||
|
|
|
@ -80,6 +80,9 @@ public:
|
|||
// wrong version is found
|
||||
static bool setup(const struct Info *info, uint8_t num_vars, uint16_t eeprom_size);
|
||||
|
||||
// return true if AP_Param has been initialised via setup()
|
||||
static bool initialised(void);
|
||||
|
||||
/// Copy the variable's name, prefixed by any containing group name, to a buffer.
|
||||
///
|
||||
/// If the variable has no name, the buffer will contain an empty string.
|
||||
|
|
Loading…
Reference in New Issue