mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
hwdef:update storage pages and enable watchdog
This commit is contained in:
parent
bc0954e124
commit
a553cb08b1
@ -7,8 +7,8 @@ MCU STM32F4xx STM32F405xx
|
|||||||
FLASH_RESERVE_START_KB 64
|
FLASH_RESERVE_START_KB 64
|
||||||
FLASH_SIZE_KB 1024
|
FLASH_SIZE_KB 1024
|
||||||
|
|
||||||
# store parameters in pages 11 and 12
|
# store parameters in pages 2 and 3
|
||||||
STORAGE_FLASH_PAGE 1
|
STORAGE_FLASH_PAGE 2
|
||||||
define HAL_STORAGE_SIZE 15360
|
define HAL_STORAGE_SIZE 15360
|
||||||
|
|
||||||
# board ID for firmware load
|
# board ID for firmware load
|
||||||
@ -20,6 +20,7 @@ define STM32_ST_USE_TIMER 5
|
|||||||
define CH_CFG_ST_RESOLUTION 32
|
define CH_CFG_ST_RESOLUTION 32
|
||||||
|
|
||||||
# enable watchdog
|
# enable watchdog
|
||||||
|
define HAL_WATCHDOG_ENABLED_DEFAULT true
|
||||||
|
|
||||||
# crystal frequency
|
# crystal frequency
|
||||||
OSCILLATOR_HZ 16000000
|
OSCILLATOR_HZ 16000000
|
||||||
@ -128,4 +129,3 @@ PC7 M9SB INPUT
|
|||||||
|
|
||||||
# allow for reboot command for faster development
|
# allow for reboot command for faster development
|
||||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user