mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: assert that storage size is an even number of storage-lines
This commit is contained in:
parent
c4ed6d0e96
commit
bff97eb150
|
@ -34,6 +34,9 @@
|
|||
#define CH_STORAGE_LINE_SIZE (1<<CH_STORAGE_LINE_SHIFT)
|
||||
#define CH_STORAGE_NUM_LINES (CH_STORAGE_SIZE/CH_STORAGE_LINE_SIZE)
|
||||
|
||||
static_assert(CH_STORAGE_SIZE % CH_STORAGE_LINE_SIZE == 0,
|
||||
"Storage is not multiple of line size");
|
||||
|
||||
class ChibiOS::Storage : public AP_HAL::Storage {
|
||||
public:
|
||||
void init() override {}
|
||||
|
|
Loading…
Reference in New Issue