mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
hwdef: removed most CAN_APP_NODE_NAME defines
both bootloader and AP_Periph now default to "org.ardupilot.BOARD_NAME". This makes it much easier to find the right firmware for update
This commit is contained in:
parent
fb5dba9d86
commit
ea51aea2e5
@ -63,8 +63,6 @@ PA12 CAN1_TX CAN1
|
||||
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -123,7 +123,6 @@ define HAL_PERIPH_ENABLE_NOTIFY
|
||||
# GPS on 2nd port
|
||||
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ARK_GPS"
|
||||
|
||||
|
||||
|
||||
|
@ -63,8 +63,6 @@ PA12 CAN1_TX CAN1
|
||||
PB12 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PB13 GPIO_CAN1_TERM OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -135,4 +135,3 @@ define HAL_PERIPH_ENABLE_RC_OUT
|
||||
# GPS on 2nd port
|
||||
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ARK_RTK_GPS"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_DLVR_Airspeed"
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1104
|
||||
|
||||
|
@ -3,8 +3,6 @@ include ../f103-periph/hwdef.inc
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1104
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_DLVR_Airspeed"
|
||||
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed"
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1077
|
||||
|
||||
|
@ -3,8 +3,6 @@ include ../f103-periph/hwdef.inc
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1077
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_Airspeed"
|
||||
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
@ -3,8 +3,6 @@
|
||||
MCU STM32L431 STM32L431xx
|
||||
APJ_BOARD_ID 1109
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_GNSS_F9P"
|
||||
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
env AP_PERIPH 1
|
||||
|
@ -1,8 +1,6 @@
|
||||
# MCU class and specific type
|
||||
MCU STM32L431 STM32L431xx
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_GNSS_F9P"
|
||||
|
||||
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
||||
FLASH_RESERVE_START_KB 40
|
||||
FLASH_SIZE_KB 256
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../AeroFox-PMU/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_PMU"
|
||||
|
@ -1,8 +1,6 @@
|
||||
# MCU class and specific type
|
||||
MCU STM32L431 STM32L431xx
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_PMU"
|
||||
|
||||
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
||||
FLASH_RESERVE_START_KB 40
|
||||
FLASH_SIZE_KB 256
|
||||
|
@ -67,9 +67,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.birdcandy"
|
||||
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -96,11 +96,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.birdcandy"
|
||||
|
||||
define HAL_GCS_ENABLED 0
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
@ -67,9 +67,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP"
|
||||
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -92,8 +92,6 @@ PA4 RTK_RESET_N OUTPUT HIGH
|
||||
# PPS
|
||||
PA7 PPS INPUT PULLUP
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.C-RTK2-HP"
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -69,9 +69,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -126,10 +126,6 @@ PB9 CAN1_TX CAN1
|
||||
PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps"
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
||||
|
@ -69,6 +69,3 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405"
|
||||
|
@ -115,8 +115,6 @@ define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixF405"
|
||||
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_ENABLE_RC_OUT
|
||||
|
@ -70,5 +70,3 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496"
|
||||
|
@ -118,8 +118,6 @@ define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496"
|
||||
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_ENABLE_RC_OUT
|
||||
|
@ -58,6 +58,3 @@ PD1 CAN1_TX CAN1
|
||||
PB6 CAN2_TX CAN2
|
||||
PB12 CAN2_RX CAN2
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph"
|
||||
|
@ -49,8 +49,6 @@ define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
define HAL_PERIPH_ENABLE_BATTERY
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeBlack-periph"
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
||||
# use blue LED
|
||||
|
@ -47,9 +47,6 @@ define HAL_NO_RCIN_THREAD
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph"
|
||||
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
||||
# use blue LED
|
||||
|
@ -58,6 +58,3 @@ PD1 CAN1_TX CAN1
|
||||
PB6 CAN2_TX CAN2
|
||||
PB12 CAN2_RX CAN2
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph"
|
||||
|
@ -43,9 +43,6 @@ define HAL_NO_RCIN_THREAD
|
||||
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CubeOrange-periph"
|
||||
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
||||
# use blue LED
|
||||
|
@ -50,4 +50,3 @@ PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.CubePilotCANMod-periph"
|
||||
|
@ -52,8 +52,6 @@ PG0 SHUTDOWNCAN OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.CubePilotCANMod-periph"
|
||||
|
||||
# override following defines as needed
|
||||
define HAL_USE_ADC FALSE
|
||||
STORAGE_FLASH_PAGE 14
|
||||
|
@ -63,8 +63,6 @@ define HAL_DISABLE_LOOP_DELAY
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -116,8 +116,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -85,7 +85,5 @@ define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC"
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB12 IMU_CS CS
|
||||
|
@ -149,7 +149,5 @@ define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.G4-ESC"
|
||||
|
||||
# don't share any DMA channels (there are enough for everyone)
|
||||
DMA_NOSHARE *
|
||||
|
@ -70,6 +70,4 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8
|
||||
|
||||
PB13 VBUS INPUT OPENDRAIN
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
define BOOTLOADER_DEBUG SD1
|
||||
|
@ -81,8 +81,6 @@ PG6 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
|
||||
EXT_FLASH_SIZE_MB 32
|
||||
|
||||
# bootloader embedding / bootloader flashing not available
|
||||
|
@ -71,5 +71,4 @@ QSPIDEV mt25q QUADSPI1 MODE1 120*MHZ 24 8
|
||||
PB13 VBUS INPUT OPENDRAIN
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
define BOOTLOADER_DEBUG SD1
|
||||
|
@ -81,8 +81,6 @@ PG6 QUADSPI_BK1_NCS QUADSPI1
|
||||
PB2 QUADSPI_CLK QUADSPI1
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.cubepilot.H757"
|
||||
|
||||
# EXT_FLASH_SIZE_MB 32
|
||||
|
||||
# bootloader embedding / bootloader flashing not available
|
||||
|
@ -53,8 +53,6 @@ PA14 JTCK-SWCLK SWD
|
||||
|
||||
define AP_PERIPH_HAVE_LED
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.here4"
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER
|
||||
define HAL_USE_UART FALSE
|
||||
|
@ -106,8 +106,6 @@ SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
|
||||
|
||||
BARO MS56XX SPI:ms5611
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.Here4AP"
|
||||
|
||||
# WS2812 LED
|
||||
PB8 TIM4_CH3 TIM4 PWM(1)
|
||||
PB9 TIM4_CH4 TIM4 PWM(2)
|
||||
|
@ -147,6 +147,4 @@ PB2 BOOT1 INPUT
|
||||
# passthrough CAN1
|
||||
define HAL_DEFAULT_CPORT 1
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
|
||||
|
||||
FULL_CHIBIOS_BOOTLOADER 1
|
||||
|
@ -195,8 +195,6 @@ PB2 BOOT1 INPUT
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
|
||||
|
||||
# disabled compass cal as it doesn't work for now
|
||||
# define COMPASS_CAL_ENABLED 1
|
||||
|
||||
|
@ -70,9 +70,5 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed"
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB12 IMU_CS CS
|
||||
|
@ -112,8 +112,6 @@ define HAL_NO_RCOUT_THREAD
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Hitec-Airspeed"
|
||||
|
||||
# don't share any DMA channels (there are enough for everyone)
|
||||
DMA_NOSHARE *
|
||||
|
||||
|
@ -87,5 +87,3 @@ define HAL_STAY_IN_BOOTLOADER_VALUE 0
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB1 MAG_CS CS
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic"
|
||||
|
@ -148,8 +148,6 @@ PA7 LED_BUS_I2C OUTPUT LOW
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HitecMosaic"
|
||||
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
|
@ -68,8 +68,6 @@ PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_Compass"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -90,8 +90,6 @@ PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_Compass"
|
||||
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
@ -72,8 +72,6 @@ PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -118,8 +118,6 @@ PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PB14 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroG4_GPS"
|
||||
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
@ -72,9 +72,6 @@ PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS"
|
||||
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -137,8 +137,6 @@ PB13 CAN2_TX CAN2
|
||||
PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS"
|
||||
|
||||
define HAL_NO_LOGGING
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
|
@ -7,4 +7,3 @@ PD1 CAN1_TX CAN1
|
||||
|
||||
env AP_PERIPH 1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph"
|
||||
|
@ -26,8 +26,6 @@ define HAL_PERIPH_ENABLE_RC_OUT
|
||||
define HAL_PERIPH_ENABLE_BATTERY
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekH743-periph"
|
||||
|
||||
# single GPS, compass and RF for peripherals
|
||||
define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BattMon"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BattMon"
|
||||
|
||||
# enable battery monitor
|
||||
define HAL_PERIPH_ENABLE_BATTERY
|
||||
define AP_BATTERY_INA239_ENABLED 1
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-DShot"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
|
||||
undef SERIAL_ORDER
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-EFI"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-GPS"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-GPS"
|
||||
|
||||
# enable GPS and compass
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define GPS_MAX_RATE_MS 200
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-HWtelem"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-HWtelem"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph"
|
||||
|
||||
|
||||
# --------------------- PWM -----------------------
|
||||
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50)
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Proximity"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Proximity"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-RC"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder"
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../MatekL431/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Rangefinder"
|
||||
|
||||
define HAL_USE_ADC FALSE
|
||||
define STM32_ADC_USE_ADC1 FALSE
|
||||
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||
|
@ -1,3 +1,2 @@
|
||||
include ../MatekL431/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-BDShot"
|
||||
|
@ -70,6 +70,3 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476"
|
||||
|
@ -94,11 +94,6 @@ define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L476"
|
||||
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_GPS_PORT_DEFAULT 0
|
||||
|
||||
|
@ -76,6 +76,3 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496"
|
||||
|
@ -101,11 +101,6 @@ define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Nucleo-L496"
|
||||
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
|
@ -50,8 +50,4 @@ PE15 MAG_CS CS
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Pixracer-periph"
|
||||
|
||||
|
||||
|
||||
PB8 STAY_IN_BOOTLOADER INPUT FLOATING # if pulled low stay in bootloader
|
||||
|
@ -51,9 +51,6 @@ define STM32_ADC_USE_ADC1 TRUE
|
||||
define HAL_DISABLE_ADC_DRIVER FALSE
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Pixracer_periph"
|
||||
|
||||
|
||||
define AP_SCRIPTING_ENABLED 0
|
||||
|
||||
MAIN_STACK 0x2000
|
||||
|
@ -50,8 +50,6 @@ PA14 JTCK-SWCLK SWD
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405"
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
|
@ -67,8 +67,6 @@ CAN_ORDER 1
|
||||
|
||||
# use DNA for node allocation
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F405"
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER USART1 EMPTY EMPTY USART2
|
||||
|
||||
|
@ -47,8 +47,6 @@ PA14 JTCK-SWCLK SWD
|
||||
PA11 CAN1_RX CAN1
|
||||
PA12 CAN1_TX CAN1
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412"
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
|
||||
|
@ -98,7 +98,6 @@ PA12 CAN1_TX CAN1
|
||||
|
||||
# use DNA
|
||||
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F412"
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
|
@ -60,8 +60,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P"
|
||||
|
||||
# make bl baudrate match debug baudrate for easier debugging
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
|
||||
|
@ -108,8 +108,6 @@ PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
PC1 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-F9P"
|
||||
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
define HAL_DEVICE_THREAD_STACK 768
|
||||
|
@ -67,7 +67,5 @@ define BOOTLOADER_BAUDRATE 57600
|
||||
# use a small bootloader timeout
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PB12 MAG_CS CS
|
||||
|
@ -99,8 +99,6 @@ define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_LOGGING
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.Sierra-L431"
|
||||
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_AIRSPEED
|
||||
define AIRSPEED_MAX_SENSORS 1
|
||||
|
@ -16,9 +16,6 @@ env AP_PERIPH 1
|
||||
|
||||
define HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
||||
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
|
@ -7,8 +7,6 @@ define STM32F107_MCUCONF
|
||||
|
||||
define HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_ZubaxGNSS"
|
||||
|
||||
# bootloader starts firmware at 34k
|
||||
FLASH_RESERVE_START_KB 34
|
||||
|
||||
|
@ -1,5 +1,4 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb"
|
||||
|
||||
|
||||
|
@ -3,9 +3,6 @@ include ../f103-periph/hwdef.inc
|
||||
#STDOUT_SERIAL SD1
|
||||
#STDOUT_BAUDRATE 115200
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_adsb"
|
||||
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
define AIRSPEED_MAX_SENSORS 1
|
||||
|
||||
|
@ -1,5 +1,4 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed"
|
||||
|
||||
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../f103-periph/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103_airspeed"
|
||||
|
||||
|
||||
define HAL_AIRSPEED_BUS_DEFAULT 0
|
||||
|
||||
|
@ -1,4 +1,3 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"
|
||||
|
@ -1,8 +1,6 @@
|
||||
include ../f103-periph/hwdef.inc
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_gps"
|
||||
|
||||
# and support all external compass types
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
# .... except BMM150:
|
||||
|
@ -2,4 +2,3 @@ include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
# start with a fixed node ID so the board is usable without DNA
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC"
|
||||
|
@ -1,6 +1,4 @@
|
||||
include ../f103-periph/hwdef.inc
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_HWESC"
|
||||
|
||||
define HAL_PERIPH_ENABLE_HWESC
|
||||
|
@ -1,5 +1,4 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph"
|
||||
|
||||
|
||||
|
@ -1,7 +1,5 @@
|
||||
include ../f103-periph/hwdef.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.f103Qiotek_Periph"
|
||||
|
||||
|
||||
undef HAL_COMPASS_MAX_SENSORS 1
|
||||
define HAL_COMPASS_MAX_SENSORS 2
|
||||
|
@ -1,6 +1,4 @@
|
||||
include ../f103-periph/hwdef-bl.inc
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.ap_periph_rangefinder"
|
||||
|
||||
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user