mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Param: Add static assert on NVM struct sizes
This commit is contained in:
parent
4cd39a4619
commit
741abaf760
@ -518,6 +518,7 @@ private:
|
|||||||
uint8_t revision;
|
uint8_t revision;
|
||||||
uint8_t spare;
|
uint8_t spare;
|
||||||
};
|
};
|
||||||
|
static_assert(sizeof(struct EEPROM_header) == 4, "Bad EEPROM_header size!");
|
||||||
|
|
||||||
static uint16_t sentinal_offset;
|
static uint16_t sentinal_offset;
|
||||||
|
|
||||||
@ -540,6 +541,7 @@ private:
|
|||||||
uint32_t key_high : 1;
|
uint32_t key_high : 1;
|
||||||
uint32_t group_element : 18;
|
uint32_t group_element : 18;
|
||||||
};
|
};
|
||||||
|
static_assert(sizeof(struct Param_header) == 4, "Bad Param_header size!");
|
||||||
|
|
||||||
// number of bits in each level of nesting of groups
|
// number of bits in each level of nesting of groups
|
||||||
static const uint8_t _group_level_shift = 6;
|
static const uint8_t _group_level_shift = 6;
|
||||||
|
Loading…
Reference in New Issue
Block a user