mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Networking: panic if bad memory alignment
This commit is contained in:
parent
cf6fd6717b
commit
724b0908e0
@ -194,6 +194,11 @@ static bool allocate_buffers()
|
||||
rasr++;
|
||||
}
|
||||
void *mem = malloc_eth_safe(size);
|
||||
// ensure our memory is aligned
|
||||
// ref. Cortex-M7 peripherals PM0253, section 4.6.4 MPU region base address register
|
||||
if (((uint32_t)mem) % size) {
|
||||
AP_HAL::panic("Bad alignment of ETH memory");
|
||||
}
|
||||
if (mem == nullptr) {
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user