mirror of https://github.com/ArduPilot/ardupilot
AP_Param: make it safe to change the type of a parameter
if the type is changed then the value will revert to its default value
This commit is contained in:
parent
2f5ade4810
commit
8454246fae
|
@ -276,7 +276,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif // AP_NESTED_GROUPS_ENABLED
|
#endif // AP_NESTED_GROUPS_ENABLED
|
||||||
if (GROUP_ID(group_info, group_base, i, group_shift) == phdr.group_element) {
|
if (GROUP_ID(group_info, group_base, i, group_shift) == phdr.group_element && type == phdr.type) {
|
||||||
// found a group element
|
// found a group element
|
||||||
*ptr = (void*)(PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset));
|
*ptr = (void*)(PGM_POINTER(&_var_info[vindex].ptr) + PGM_UINT16(&group_info[i].offset));
|
||||||
return &_var_info[vindex];
|
return &_var_info[vindex];
|
||||||
|
@ -297,14 +297,15 @@ const struct AP_Param::Info *AP_Param::find_by_header(struct Param_header phdr,
|
||||||
// not the right key
|
// not the right key
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (type != AP_PARAM_GROUP) {
|
if (type == AP_PARAM_GROUP) {
|
||||||
// if its not a group then we are done
|
const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info);
|
||||||
|
return find_by_header_group(phdr, ptr, i, group_info, 0, 0);
|
||||||
|
}
|
||||||
|
if (type == phdr.type) {
|
||||||
|
// found it
|
||||||
*ptr = (void*)PGM_POINTER(&_var_info[i].ptr);
|
*ptr = (void*)PGM_POINTER(&_var_info[i].ptr);
|
||||||
return &_var_info[i];
|
return &_var_info[i];
|
||||||
}
|
}
|
||||||
|
|
||||||
const struct GroupInfo *group_info = (const struct GroupInfo *)PGM_POINTER(&_var_info[i].group_info);
|
|
||||||
return find_by_header_group(phdr, ptr, i, group_info, 0, 0);
|
|
||||||
}
|
}
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue