mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
hwdef: add Aerofox GNSS F9P module
This commit is contained in:
parent
641b086c0f
commit
91f3e3a9a7
45
libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat
Normal file
45
libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef-bl.dat
Normal file
@ -0,0 +1,45 @@
|
||||
# hw definition file AeroFox_GNSS_F9P CAN node
|
||||
# MCU class and specific type
|
||||
MCU STM32L431 STM32L431xx
|
||||
APJ_BOARD_ID 1109
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.AeroFox_GNSS_F9P"
|
||||
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
env AP_PERIPH 1
|
||||
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 36
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
APP_START_OFFSET_KB 4
|
||||
|
||||
PB3 LED_BOOTLOADER OUTPUT LOW
|
||||
define HAL_LED_ON 0
|
||||
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
define BOOTLOADER_BAUDRATE 57600
|
||||
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||
|
||||
define HAL_USE_SERIAL FALSE
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 32
|
||||
define HAL_USE_EMPTY_IO TRUE
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
MAIN_STACK 0x800
|
||||
PROCESS_STACK 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
PA4 MAG_CS CS
|
||||
PB2 SPARE_CS CS
|
118
libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat
Normal file
118
libraries/AP_HAL_ChibiOS/hwdef/AeroFox-GNSS_F9P/hwdef.dat
Normal file
@ -0,0 +1,118 @@
|
||||
# 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
|
||||
|
||||
# store parameters in pages 18 and 19
|
||||
STORAGE_FLASH_PAGE 18
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 15
|
||||
define CH_CFG_ST_RESOLUTION 16
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1109
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
env AP_PERIPH 1
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
define DMA_RESERVE_SIZE 0
|
||||
|
||||
# MAIN_STACK is stack for ISR handlers
|
||||
MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
define HAL_GCS_ENABLED 0
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_LOGGING
|
||||
|
||||
# we setup a small defaults.parm
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
# blue LED0 marked as ACT
|
||||
PB3 LED OUTPUT HIGH
|
||||
define HAL_LED_ON 1
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# I2C bus
|
||||
I2C_ORDER I2C2
|
||||
PB13 I2C2_SCL I2C2
|
||||
PB14 I2C2_SDA I2C2
|
||||
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# CAN bus
|
||||
CAN_ORDER 1
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||
define HAL_CAN_POOL_SIZE 12000
|
||||
|
||||
# UARTs
|
||||
SERIAL_ORDER USART1 EMPTY EMPTY
|
||||
|
||||
# USART1
|
||||
PB6 USART1_TX USART1 SPEED_HIGH
|
||||
PB7 USART1_RX USART1 SPEED_HIGH
|
||||
|
||||
# allow for reboot command for faster development
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
# keep ROMFS uncompressed as we don't have enough RAM
|
||||
# to uncompress the bootloader at runtime
|
||||
env ROMFS_UNCOMPRESSED True
|
||||
|
||||
# enable GPS and compass
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define GPS_MAX_RATE_MS 200
|
||||
define GPS_MAX_RECEIVERS 1
|
||||
define GPS_MAX_INSTANCES 1
|
||||
define HAL_PERIPH_GPS_PORT_DEFAULT 0
|
||||
|
||||
# allow for F9P GPS modules with moving baseline
|
||||
define GPS_MOVING_BASELINE 1
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_COMPASS_MAX_SENSORS 1
|
||||
|
||||
# QMC5883L for different board varients
|
||||
COMPASS QMC5883L I2C:0:0xd false ROTATION_YAW_180
|
||||
|
||||
# no ADC pins
|
||||
define HAL_USE_ADC FALSE
|
||||
|
||||
# disable unnecessary threads
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
define HAL_NO_RCIN_THREAD
|
||||
define HAL_NO_TIMER_THREAD
|
||||
|
||||
# enable LED
|
||||
define HAL_PERIPH_ENABLE_RC_OUT
|
||||
define HAL_PERIPH_ENABLE_NOTIFY
|
||||
|
||||
#GPIO LED
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
PB2 LED_RED OUTPUT OPENDRAIN HIGH GPIO(0)
|
||||
PB4 LED_GREEN OUTPUT OPENDRAIN LOW GPIO(1)
|
||||
PB5 LED_BLUE OUTPUT OPENDRAIN LOW GPIO(2)
|
||||
define HAL_GPIO_A_LED_PIN 0
|
||||
define HAL_GPIO_B_LED_PIN 1
|
||||
define HAL_GPIO_C_LED_PIN 2
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
Loading…
Reference in New Issue
Block a user