mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: unhide groups when generating parameters in autotest
This commit is contained in:
parent
dd7d41b1f3
commit
2bd13af43d
@ -78,6 +78,8 @@ void AP_Param::eeprom_write_check(const void *ptr, uint16_t ofs, uint8_t size)
|
||||
_storage.write_block(ofs, ptr, size);
|
||||
}
|
||||
|
||||
bool AP_Param::_hide_disabled_groups = true;
|
||||
|
||||
// write a sentinal value at the given offset
|
||||
void AP_Param::write_sentinal(uint16_t ofs)
|
||||
{
|
||||
@ -1460,7 +1462,8 @@ AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype)
|
||||
ginfo, group_nesting, &idx);
|
||||
if (info && ginfo &&
|
||||
(ginfo->flags & AP_PARAM_FLAG_ENABLE) &&
|
||||
((AP_Int8 *)ap)->get() == 0) {
|
||||
((AP_Int8 *)ap)->get() == 0 &&
|
||||
_hide_disabled_groups) {
|
||||
/*
|
||||
this is a disabled parameter tree, include this
|
||||
parameter but not others below it. We need to keep
|
||||
|
@ -346,6 +346,8 @@ public:
|
||||
// count of parameters in tree
|
||||
static uint16_t count_parameters(void);
|
||||
|
||||
static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }
|
||||
|
||||
private:
|
||||
/// EEPROM header
|
||||
///
|
||||
@ -493,6 +495,8 @@ private:
|
||||
static const uint8_t k_EEPROM_magic0 = 0x50;
|
||||
static const uint8_t k_EEPROM_magic1 = 0x41; ///< "AP"
|
||||
static const uint8_t k_EEPROM_revision = 6; ///< current format revision
|
||||
|
||||
static bool _hide_disabled_groups;
|
||||
};
|
||||
|
||||
/// Template class for scalar variables.
|
||||
|
Loading…
Reference in New Issue
Block a user