HAL_ChibiOS: added RTC_BOOT_FWOK value for RTC reboot register

this is used in CAN firmware to know if the main app firmware has run
for long enough to be considered good
This commit is contained in:
Andrew Tridgell 2019-10-26 12:41:26 +11:00
parent f777a37826
commit fc8d9e8af5
2 changed files with 6 additions and 3 deletions

View File

@ -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

View File

@ -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