diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c index fb72506126..1651faaab2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.c @@ -260,8 +260,10 @@ enum rtc_boot_magic check_fast_reboot(void) // set RTC register for a fast reboot void set_fast_reboot(enum rtc_boot_magic v) { - uint32_t vv = (uint32_t)v; - set_rtc_backup(0, &vv, 1); + if (check_fast_reboot() != v) { + uint32_t vv = (uint32_t)v; + set_rtc_backup(0, &vv, 1); + } } #else // NO_FASTBOOT diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 2705e053f0..d5ad9f7dc1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -58,7 +58,8 @@ enum rtc_boot_magic { RTC_BOOT_OFF = 0, RTC_BOOT_HOLD = 0xb0070001, RTC_BOOT_FAST = 0xb0070002, - RTC_BOOT_CANBL = 0xb0080000 // ORd with 8 bit local node ID + RTC_BOOT_CANBL = 0xb0080000, // ORd with 8 bit local node ID + RTC_BOOT_FWOK = 0xb0093a26 // indicates FW ran for 30s }; // see if RTC registers is setup for a fast reboot