mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: make check_limit_flash_1M() available in main firmware
This commit is contained in:
parent
b5a5241f96
commit
d3e4cc59b0
|
@ -558,3 +558,20 @@ unsigned int stm32_rand_generate_nonblocking(unsigned char* output, unsigned int
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // #if HAL_USE_HW_RNG && defined(RNG)
|
#endif // #if HAL_USE_HW_RNG && defined(RNG)
|
||||||
|
|
||||||
|
/*
|
||||||
|
see if we should limit flash to 1M on devices with older revisions of STM32F427
|
||||||
|
*/
|
||||||
|
bool check_limit_flash_1M(void)
|
||||||
|
{
|
||||||
|
#ifdef STM32F427xx
|
||||||
|
const uint16_t revid = (*(uint32_t *)DBGMCU_BASE) >> 16;
|
||||||
|
static const uint16_t badrevs[4] = { 0x1000, 0x1001, 0x1003, 0x1007 };
|
||||||
|
for (uint8_t i=0; i<4; i++) {
|
||||||
|
if (revid == badrevs[i]) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
|
@ -54,6 +54,11 @@ uint64_t stm32_get_utc_usec(void);
|
||||||
// hook for FAT timestamps
|
// hook for FAT timestamps
|
||||||
uint32_t get_fattime(void);
|
uint32_t get_fattime(void);
|
||||||
|
|
||||||
|
/*
|
||||||
|
see if we should limit flash to 1M on devices with older revisions of STM32F427
|
||||||
|
*/
|
||||||
|
bool check_limit_flash_1M(void);
|
||||||
|
|
||||||
// one-time programmable area
|
// one-time programmable area
|
||||||
#if defined(FLASH_OTP_BASE)
|
#if defined(FLASH_OTP_BASE)
|
||||||
#define OTP_BASE FLASH_OTP_BASE
|
#define OTP_BASE FLASH_OTP_BASE
|
||||||
|
|
Loading…
Reference in New Issue