mirror of https://github.com/ArduPilot/ardupilot
hwdef: remove stray HAL_BUILD_AP_PERIPH defines
this is added by defaults_periph
This commit is contained in:
parent
5fb4e1e285
commit
47716e2338
|
@ -8,8 +8,6 @@ MCU STM32H7xx STM32H757xx
|
||||||
define CORE_CM7
|
define CORE_CM7
|
||||||
define SMPS_PWR
|
define SMPS_PWR
|
||||||
|
|
||||||
define HAL_BUILD_AP_PERIPH
|
|
||||||
|
|
||||||
# board ID for firmware load
|
# board ID for firmware load
|
||||||
APJ_BOARD_ID 1079
|
APJ_BOARD_ID 1079
|
||||||
|
|
||||||
|
|
|
@ -97,7 +97,6 @@ PA12 CAN1_TX CAN1
|
||||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_BUILD_AP_PERIPH
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# disable dual GPS and GPS blending to save flash space
|
# disable dual GPS and GPS blending to save flash space
|
||||||
|
|
|
@ -106,7 +106,6 @@ PB9 CAN1_TX CAN1
|
||||||
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
define HAL_NO_MONITOR_THREAD
|
define HAL_NO_MONITOR_THREAD
|
||||||
define HAL_BUILD_AP_PERIPH
|
|
||||||
define HAL_DEVICE_THREAD_STACK 768
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
# we setup a small defaults.parm
|
# we setup a small defaults.parm
|
||||||
|
|
|
@ -20,8 +20,6 @@ FLASH_SIZE_KB 2048
|
||||||
# setup build for a peripheral firmware
|
# setup build for a peripheral firmware
|
||||||
env AP_PERIPH 1
|
env AP_PERIPH 1
|
||||||
|
|
||||||
define HAL_BUILD_AP_PERIPH
|
|
||||||
|
|
||||||
# bootloader is installed at zero offset
|
# bootloader is installed at zero offset
|
||||||
FLASH_RESERVE_START_KB 128
|
FLASH_RESERVE_START_KB 128
|
||||||
FLASH_BOOTLOADER_LOAD_KB 128
|
FLASH_BOOTLOADER_LOAD_KB 128
|
||||||
|
|
Loading…
Reference in New Issue