mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_HAL_ChibiOS: remove legacy define WATCHDOG_DISABLED
This commit is contained in:
parent
724b0908e0
commit
f84572a545
@ -20,7 +20,6 @@ FLASH_RESERVE_START_KB 0
|
|||||||
# the H757 has 128k sectors, assign 2 sectors for BL
|
# the H757 has 128k sectors, assign 2 sectors for BL
|
||||||
FLASH_BOOTLOADER_LOAD_KB 256
|
FLASH_BOOTLOADER_LOAD_KB 256
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 24000000
|
OSCILLATOR_HZ 24000000
|
||||||
|
@ -4,7 +4,6 @@
|
|||||||
# MCU class and specific type
|
# MCU class and specific type
|
||||||
MCU STM32H7xx STM32H757xx
|
MCU STM32H7xx STM32H757xx
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
@ -12,7 +12,6 @@ USB_STRING_PRODUCT "%BOARD%"
|
|||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 25000000
|
OSCILLATOR_HZ 25000000
|
||||||
|
@ -14,7 +14,6 @@ USB_STRING_PRODUCT "%BOARD%"
|
|||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 25000000
|
OSCILLATOR_HZ 25000000
|
||||||
|
@ -12,7 +12,6 @@ USB_STRING_PRODUCT "%BOARD%"
|
|||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 25000000
|
OSCILLATOR_HZ 25000000
|
||||||
|
@ -14,7 +14,6 @@ USB_STRING_PRODUCT "%BOARD%"
|
|||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
|
||||||
define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 25000000
|
OSCILLATOR_HZ 25000000
|
||||||
|
@ -12,7 +12,6 @@ env OPTIMIZE -O2
|
|||||||
USB_STRING_MANUFACTURER "ArduPilot"
|
USB_STRING_MANUFACTURER "ArduPilot"
|
||||||
USB_STRING_PRODUCT "%BOARD%"
|
USB_STRING_PRODUCT "%BOARD%"
|
||||||
|
|
||||||
#define WATCHDOG_DISABLED
|
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 25000000
|
OSCILLATOR_HZ 25000000
|
||||||
|
Loading…
Reference in New Issue
Block a user