mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_Param: add in nested group offset in load for conversion
This commit is contained in:
parent
c15fa950c0
commit
71b6d3e33d
@ -935,7 +935,13 @@ bool AP_Param::load(void)
|
|||||||
// if the value isn't stored in EEPROM then set the default value
|
// if the value isn't stored in EEPROM then set the default value
|
||||||
if (ginfo != NULL) {
|
if (ginfo != NULL) {
|
||||||
ptrdiff_t base = (ptrdiff_t)info->ptr;
|
ptrdiff_t base = (ptrdiff_t)info->ptr;
|
||||||
set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset),
|
|
||||||
|
// add in nested group offset
|
||||||
|
ptrdiff_t group_offset = 0;
|
||||||
|
for (uint8_t i=0; i<group_nesting.level; i++) {
|
||||||
|
group_offset += group_nesting.group_ret[i]->offset;
|
||||||
|
}
|
||||||
|
set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset + group_offset),
|
||||||
get_default_value(&ginfo->def_value));
|
get_default_value(&ginfo->def_value));
|
||||||
} else {
|
} else {
|
||||||
set_value((enum ap_var_type)phdr.type, (void*)info->ptr,
|
set_value((enum ap_var_type)phdr.type, (void*)info->ptr,
|
||||||
|
Loading…
Reference in New Issue
Block a user