mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Bootloader: use RTC sig for fast boot
This commit is contained in:
parent
2b7b499c63
commit
b6e057dfb9
@ -26,6 +26,7 @@
|
||||
#include "hal.h"
|
||||
#include "hwdef.h"
|
||||
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
||||
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
|
||||
#include "support.h"
|
||||
#include "bl_protocol.h"
|
||||
|
||||
@ -35,6 +36,10 @@ extern "C" {
|
||||
|
||||
struct boardinfo board_info;
|
||||
|
||||
#ifndef HAL_BOOTLOADER_TIMEOUT
|
||||
#define HAL_BOOTLOADER_TIMEOUT 5000
|
||||
#endif
|
||||
|
||||
int main(void)
|
||||
{
|
||||
init_uarts();
|
||||
@ -48,8 +53,27 @@ int main(void)
|
||||
|
||||
flash_init();
|
||||
|
||||
bool try_boot = false;
|
||||
uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;
|
||||
|
||||
enum rtc_boot_magic m = check_fast_reboot();
|
||||
if (m == RTC_BOOT_HOLD) {
|
||||
timeout = 0;
|
||||
} else if (m == RTC_BOOT_FAST) {
|
||||
try_boot = true;
|
||||
timeout = 0;
|
||||
}
|
||||
|
||||
// if we fail to boot properly we want to pause in bootloader to give
|
||||
// a chance to load new app code
|
||||
set_fast_reboot(RTC_BOOT_OFF);
|
||||
|
||||
if (try_boot) {
|
||||
jump_to_app();
|
||||
}
|
||||
|
||||
while (true) {
|
||||
bootloader(5000);
|
||||
bootloader(timeout);
|
||||
jump_to_app();
|
||||
}
|
||||
}
|
||||
|
@ -367,3 +367,4 @@ void port_setbaud(uint32_t baudrate)
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -33,6 +33,9 @@ uint32_t get_mcu_id(void);
|
||||
uint32_t get_mcu_desc(uint32_t len, uint8_t *buf);
|
||||
bool check_limit_flash_1M(void);
|
||||
|
||||
uint32_t board_get_rtc_signature(void);
|
||||
void board_set_rtc_signature(uint32_t sig);
|
||||
|
||||
void led_on(unsigned led);
|
||||
void led_off(unsigned led);
|
||||
void led_toggle(unsigned led);
|
||||
|
Loading…
Reference in New Issue
Block a user