mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: add option for NO_FASTBOOT build and enable it for iomcu
This commit is contained in:
parent
6622c9b8fd
commit
8ac38d73f7
|
@ -147,7 +147,7 @@
|
||||||
* @brief Enables the RTC subsystem.
|
* @brief Enables the RTC subsystem.
|
||||||
*/
|
*/
|
||||||
#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
|
#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
|
||||||
#define HAL_USE_RTC TRUE
|
#define HAL_USE_RTC FALSE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -219,7 +219,7 @@ uint32_t get_fattime()
|
||||||
return fattime;
|
return fattime;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(HAL_USE_RTC) && HAL_USE_RTC
|
#if !defined(NO_FASTBOOT)
|
||||||
// get RTC backup register 0
|
// get RTC backup register 0
|
||||||
static uint32_t get_rtc_backup0(void)
|
static uint32_t get_rtc_backup0(void)
|
||||||
{
|
{
|
||||||
|
@ -253,7 +253,7 @@ void set_fast_reboot(enum rtc_boot_magic v)
|
||||||
set_rtc_backup0(v);
|
set_rtc_backup0(v);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //HAL_USE_RTC
|
#endif //NO_FASTBOOT
|
||||||
|
|
||||||
/*
|
/*
|
||||||
enable peripheral power if needed This is done late to prevent
|
enable peripheral power if needed This is done late to prevent
|
||||||
|
|
|
@ -98,7 +98,7 @@ define NO_DATAFLASH TRUE
|
||||||
define DMA_RESERVE_SIZE 0
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
define IOMCU_FW TRUE
|
define IOMCU_FW TRUE
|
||||||
|
define NO_FASTBOOT
|
||||||
IOMCU_FW 1
|
IOMCU_FW 1
|
||||||
MAIN_STACK 0x200
|
MAIN_STACK 0x200
|
||||||
PROCESS_STACK 0x250
|
PROCESS_STACK 0x250
|
Loading…
Reference in New Issue