mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS:hwdef/common: disable second core on dual core MCUs
This commit is contained in:
parent
f24dd1d75f
commit
d4df6e0fa8
|
@ -269,6 +269,9 @@ void __early_init(void) {
|
|||
STM32_NOCACHE_MPU_REGION_2_SIZE |
|
||||
MPU_RASR_ENABLE);
|
||||
#endif
|
||||
#if defined(DUAL_CORE)
|
||||
stm32_disable_cm4_core(); // disable second core
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -581,3 +581,31 @@ bool check_limit_flash_1M(void)
|
|||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(DUAL_CORE)
|
||||
void stm32_disable_cm4_core() {
|
||||
// Turn off second core for now
|
||||
if ((FLASH->OPTSR_CUR & FLASH_OPTSR_BCM4)) {
|
||||
//unlock flash
|
||||
if (FLASH->OPTCR & FLASH_OPTCR_OPTLOCK) {
|
||||
/* Unlock sequence */
|
||||
FLASH->OPTKEYR = 0x08192A3B;
|
||||
FLASH->OPTKEYR = 0x4C5D6E7F;
|
||||
}
|
||||
while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) {
|
||||
}
|
||||
// disable core boot
|
||||
FLASH->OPTSR_PRG &= ~FLASH_OPTSR_BCM4;
|
||||
// start programming
|
||||
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
|
||||
// wait for completion by checking busy bit
|
||||
while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) {
|
||||
}
|
||||
// lock flash
|
||||
FLASH->OPTCR |= FLASH_OPTCR_OPTLOCK;
|
||||
while (FLASH->OPTSR_CUR & FLASH_OPTSR_OPT_BUSY) {
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // DUAL_CORE
|
||||
|
|
|
@ -191,6 +191,8 @@ extern stkalign_t __main_stack_end__;
|
|||
extern stkalign_t __main_thread_stack_base__;
|
||||
extern stkalign_t __main_thread_stack_end__;
|
||||
|
||||
void stm32_disable_cm4_core(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue