mirror of https://github.com/ArduPilot/ardupilot
AP_Param: fixed handling of group_element=255 in sentinal detection
EK3_DRAG_BCOEF_Y has a group element of 255, which was being detected as a sentinal
This commit is contained in:
parent
85e3772759
commit
eac027b5c5
|
@ -696,11 +696,11 @@ void AP_Param::set_key(Param_header &phdr, uint16_t key)
|
||||||
*/
|
*/
|
||||||
bool AP_Param::is_sentinal(const Param_header &phdr)
|
bool AP_Param::is_sentinal(const Param_header &phdr)
|
||||||
{
|
{
|
||||||
// note that this is an ||, not an &&, as this makes us more
|
// note that this is an ||, not an && on the key and group, as
|
||||||
// robust to power off while adding a variable to EEPROM
|
// this makes us more robust to power off while adding a variable
|
||||||
|
// to EEPROM
|
||||||
if (phdr.type == _sentinal_type ||
|
if (phdr.type == _sentinal_type ||
|
||||||
get_key(phdr) == _sentinal_key ||
|
get_key(phdr) == _sentinal_key) {
|
||||||
phdr.group_element == _sentinal_group) {
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
// also check for 0xFFFFFFFF and 0x00000000, which are the fill
|
// also check for 0xFFFFFFFF and 0x00000000, which are the fill
|
||||||
|
|
Loading…
Reference in New Issue