mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_HAL_ChibiOS: replace NO_FASTBOOT with AP_FASTBOOT_ENABLED
This commit is contained in:
parent
f437f61db2
commit
349dd5089c
@ -84,7 +84,7 @@ int main(void)
|
|||||||
stm32_flash_unprotect_flash();
|
stm32_flash_unprotect_flash();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef NO_FASTBOOT
|
#if AP_FASTBOOT_ENABLED
|
||||||
enum rtc_boot_magic m = check_fast_reboot();
|
enum rtc_boot_magic m = check_fast_reboot();
|
||||||
bool was_watchdog = stm32_was_watchdog_reset();
|
bool was_watchdog = stm32_was_watchdog_reset();
|
||||||
if (was_watchdog) {
|
if (was_watchdog) {
|
||||||
@ -151,7 +151,7 @@ int main(void)
|
|||||||
// if we fail to boot properly we want to pause in bootloader to give
|
// if we fail to boot properly we want to pause in bootloader to give
|
||||||
// a chance to load new app code
|
// a chance to load new app code
|
||||||
set_fast_reboot(RTC_BOOT_OFF);
|
set_fast_reboot(RTC_BOOT_OFF);
|
||||||
#endif
|
#endif // AP_FASTBOOT_ENABLED
|
||||||
|
|
||||||
#ifdef HAL_GPIO_PIN_STAY_IN_BOOTLOADER
|
#ifdef HAL_GPIO_PIN_STAY_IN_BOOTLOADER
|
||||||
// optional "stay in bootloader" pin
|
// optional "stay in bootloader" pin
|
||||||
|
@ -285,7 +285,7 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
|||||||
AP::FS().unmount();
|
AP::FS().unmount();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(NO_FASTBOOT)
|
#if AP_FASTBOOT_ENABLED
|
||||||
// setup RTC for fast reboot
|
// setup RTC for fast reboot
|
||||||
set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST);
|
set_fast_reboot(hold_in_bootloader?RTC_BOOT_HOLD:RTC_BOOT_FAST);
|
||||||
#endif
|
#endif
|
||||||
|
@ -209,7 +209,7 @@ uint32_t get_fattime()
|
|||||||
return fattime;
|
return fattime;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if !defined(NO_FASTBOOT)
|
#if AP_FASTBOOT_ENABLED
|
||||||
|
|
||||||
// get RTC backup registers starting at given idx
|
// get RTC backup registers starting at given idx
|
||||||
void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n)
|
void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n)
|
||||||
@ -272,7 +272,7 @@ void set_fast_reboot(enum rtc_boot_magic v)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#else // NO_FASTBOOT
|
#else // AP_FASTBOOT_ENABLED is not set
|
||||||
|
|
||||||
// set n RTC backup registers starting at given idx
|
// set n RTC backup registers starting at given idx
|
||||||
void set_rtc_backup(uint8_t idx, const uint32_t *v, uint8_t n)
|
void set_rtc_backup(uint8_t idx, const uint32_t *v, uint8_t n)
|
||||||
@ -289,7 +289,7 @@ void get_rtc_backup(uint8_t idx, uint32_t *v, uint8_t n)
|
|||||||
(void)v;
|
(void)v;
|
||||||
(void)n;
|
(void)n;
|
||||||
}
|
}
|
||||||
#endif // NO_FASTBOOT
|
#endif // AP_FASTBOOT_ENABLED
|
||||||
|
|
||||||
/*
|
/*
|
||||||
enable peripheral power if needed This is done late to prevent
|
enable peripheral power if needed This is done late to prevent
|
||||||
|
@ -20,6 +20,10 @@
|
|||||||
#define AP_WATCHDOG_SAVE_FAULT_ENABLED 1
|
#define AP_WATCHDOG_SAVE_FAULT_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_FASTBOOT_ENABLED
|
||||||
|
#define AP_FASTBOOT_ENABLED 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
extern "C" {
|
extern "C" {
|
||||||
#endif
|
#endif
|
||||||
|
@ -132,7 +132,7 @@ define DMA_RESERVE_SIZE 0
|
|||||||
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
||||||
|
|
||||||
define IOMCU_FW TRUE
|
define IOMCU_FW TRUE
|
||||||
define NO_FASTBOOT
|
define AP_FASTBOOT_ENABLED 0
|
||||||
IOMCU_FW 1
|
IOMCU_FW 1
|
||||||
MAIN_STACK 0x200
|
MAIN_STACK 0x200
|
||||||
PROCESS_STACK 0x250
|
PROCESS_STACK 0x250
|
||||||
|
@ -132,7 +132,7 @@ define DMA_RESERVE_SIZE 0
|
|||||||
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
define SOFTSIG_MAX_SIGNAL_TRANSITIONS 128
|
||||||
|
|
||||||
define IOMCU_FW TRUE
|
define IOMCU_FW TRUE
|
||||||
define NO_FASTBOOT
|
define AP_FASTBOOT_ENABLED 0
|
||||||
IOMCU_FW 1
|
IOMCU_FW 1
|
||||||
MAIN_STACK 0x200
|
MAIN_STACK 0x200
|
||||||
PROCESS_STACK 0x250
|
PROCESS_STACK 0x250
|
||||||
|
Loading…
Reference in New Issue
Block a user