mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_ChibiOS: added HolybroGPS AP_Periph port
This commit is contained in:
parent
b6543e7a85
commit
5529ba36e2
97
libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat
Normal file
97
libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef-bl.dat
Normal file
@ -0,0 +1,97 @@
|
|||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32F4xx STM32F412Rx
|
||||||
|
|
||||||
|
FLASH_RESERVE_START_KB 0
|
||||||
|
|
||||||
|
# two sectors for bootloader, two for storage
|
||||||
|
FLASH_BOOTLOADER_LOAD_KB 64
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID 1035
|
||||||
|
|
||||||
|
# setup build for a peripheral firmware
|
||||||
|
env AP_PERIPH 1
|
||||||
|
|
||||||
|
# debug on USART2
|
||||||
|
STDOUT_SERIAL SD2
|
||||||
|
STDOUT_BAUDRATE 57600
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 16000000
|
||||||
|
|
||||||
|
define CH_CFG_ST_FREQUENCY 1000000
|
||||||
|
|
||||||
|
# assume 512k flash part
|
||||||
|
FLASH_SIZE_KB 512
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER USART2
|
||||||
|
|
||||||
|
# workaround missing define in headers
|
||||||
|
define RCC_AHB1RSTR_OTGHRST 0x20000000
|
||||||
|
|
||||||
|
# blue LED
|
||||||
|
PB15 LED_BOOTLOADER OUTPUT HIGH
|
||||||
|
define HAL_LED_ON 0
|
||||||
|
|
||||||
|
# USART2
|
||||||
|
PA2 USART2_TX USART2
|
||||||
|
PA3 USART2_RX USART2
|
||||||
|
|
||||||
|
# SWD debugging
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
define HAL_USE_SERIAL TRUE
|
||||||
|
|
||||||
|
define STM32_SERIAL_USE_USART1 FALSE
|
||||||
|
define STM32_SERIAL_USE_USART2 TRUE
|
||||||
|
define STM32_SERIAL_USE_USART3 FALSE
|
||||||
|
|
||||||
|
define HAL_NO_GPIO_IRQ
|
||||||
|
define HAL_USE_EMPTY_IO TRUE
|
||||||
|
|
||||||
|
# avoid timer and RCIN threads to save memory
|
||||||
|
define HAL_NO_TIMER_THREAD
|
||||||
|
define HAL_NO_RCIN_THREAD
|
||||||
|
|
||||||
|
define HAL_USE_RTC FALSE
|
||||||
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
||||||
|
define NO_DATAFLASH TRUE
|
||||||
|
|
||||||
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
define PERIPH_FW TRUE
|
||||||
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
|
define HAL_USE_EMPTY_STORAGE 1
|
||||||
|
define HAL_STORAGE_SIZE 16384
|
||||||
|
|
||||||
|
# enable CAN support
|
||||||
|
|
||||||
|
PA11 CAN1_RX CAN1
|
||||||
|
PA12 CAN1_TX CAN1
|
||||||
|
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
|
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"
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
# make bl baudrate match debug baudrate for easier debugging
|
||||||
|
define BOOTLOADER_BAUDRATE 57600
|
||||||
|
|
||||||
|
# use a smaller bootloader timeout
|
||||||
|
define HAL_BOOTLOADER_TIMEOUT 2500
|
||||||
|
|
||||||
|
# reserve 256 bytes for comms between app and bootloader
|
||||||
|
RAM_RESERVE_START 256
|
||||||
|
|
||||||
|
# Add CS pins to ensure they are high in bootloader
|
||||||
|
PA8 ACC_CS CS
|
182
libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat
Normal file
182
libraries/AP_HAL_ChibiOS/hwdef/HolybroGPS/hwdef.dat
Normal file
@ -0,0 +1,182 @@
|
|||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
# MCU class and specific type
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32F4xx STM32F412Rx
|
||||||
|
|
||||||
|
# bootloader starts firmware at 64k
|
||||||
|
FLASH_RESERVE_START_KB 64
|
||||||
|
|
||||||
|
# store parameters in pages 2 and 3
|
||||||
|
define STORAGE_FLASH_PAGE 2
|
||||||
|
define HAL_STORAGE_SIZE 8192
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID 1035
|
||||||
|
|
||||||
|
# setup build for a peripheral firmware
|
||||||
|
env AP_PERIPH 1
|
||||||
|
|
||||||
|
STM32_ST_USE_TIMER 5
|
||||||
|
|
||||||
|
# enable watchdog
|
||||||
|
define HAL_WATCHDOG_ENABLED_DEFAULT true
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 16000000
|
||||||
|
|
||||||
|
define CH_CFG_ST_FREQUENCY 1000000
|
||||||
|
|
||||||
|
# assume 512k flash part
|
||||||
|
FLASH_SIZE_KB 512
|
||||||
|
|
||||||
|
# debug on USART2
|
||||||
|
STDOUT_SERIAL SD2
|
||||||
|
STDOUT_BAUDRATE 57600
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER USART2 USART1
|
||||||
|
|
||||||
|
# sensor power control
|
||||||
|
PC15 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||||
|
|
||||||
|
# LEDs
|
||||||
|
PB15 LED OUTPUT HIGH GPIO(2) # blue
|
||||||
|
PA7 LED_R OUTPUT HIGH GPIO(0)
|
||||||
|
PB14 LED_G OUTPUT HIGH GPIO(1)
|
||||||
|
|
||||||
|
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
|
||||||
|
|
||||||
|
define HAL_HAVE_PIXRACER_LED
|
||||||
|
|
||||||
|
# USART1, GPS
|
||||||
|
PA9 USART1_TX USART1 NODMA
|
||||||
|
PA10 USART1_RX USART1 NODMA
|
||||||
|
|
||||||
|
# USART2, debug
|
||||||
|
PA2 USART2_TX USART2
|
||||||
|
PA3 USART2_RX USART2
|
||||||
|
|
||||||
|
# SWD debugging
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
# I2C1 bus
|
||||||
|
PB7 I2C1_SDA I2C1
|
||||||
|
PB6 I2C1_SCL I2C1
|
||||||
|
|
||||||
|
# I2C2 bus
|
||||||
|
PB3 I2C2_SDA I2C2
|
||||||
|
PB10 I2C2_SCL I2C2
|
||||||
|
|
||||||
|
define HAL_I2C_INTERNAL_MASK 3
|
||||||
|
|
||||||
|
# I2C buses
|
||||||
|
I2C_ORDER I2C1 I2C2
|
||||||
|
|
||||||
|
# one SPI bus
|
||||||
|
PA5 SPI1_SCK SPI1
|
||||||
|
PA6 SPI1_MISO SPI1
|
||||||
|
PB5 SPI1_MOSI SPI1
|
||||||
|
|
||||||
|
# SPI CS
|
||||||
|
PA8 ACC_CS CS
|
||||||
|
|
||||||
|
# version sense
|
||||||
|
PA0 HW_REV_SENSE INPUT
|
||||||
|
PA1 HW_VER_SENSE INPUT
|
||||||
|
PB1 HW_VER_REV_DRIVE INPUT
|
||||||
|
|
||||||
|
# GPS PPS
|
||||||
|
PA15 GPS_PPS_IN INPUT
|
||||||
|
|
||||||
|
|
||||||
|
# SPI devices
|
||||||
|
SPIDEV bmi088_a SPI1 DEVID1 ACC_CS MODE3 10*MHZ 10*MHZ
|
||||||
|
|
||||||
|
# compass
|
||||||
|
COMPASS BMM150 I2C:0:0x10 false ROTATION_YAW_90
|
||||||
|
|
||||||
|
# baro
|
||||||
|
BARO BMP388 I2C:0:0x77
|
||||||
|
|
||||||
|
# IMU
|
||||||
|
IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
|
||||||
|
|
||||||
|
define HAL_BARO_ALLOW_INIT_NO_BARO
|
||||||
|
|
||||||
|
define HAL_USE_ADC FALSE
|
||||||
|
define STM32_ADC_USE_ADC1 FALSE
|
||||||
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
||||||
|
|
||||||
|
define HAL_NO_GPIO_IRQ
|
||||||
|
|
||||||
|
# avoid RCIN thread to save memory
|
||||||
|
define HAL_NO_RCIN_THREAD
|
||||||
|
|
||||||
|
define HAL_USE_RTC FALSE
|
||||||
|
define DISABLE_SERIAL_ESC_COMM TRUE
|
||||||
|
define NO_DATAFLASH TRUE
|
||||||
|
|
||||||
|
define DMA_RESERVE_SIZE 0
|
||||||
|
|
||||||
|
define PERIPH_FW TRUE
|
||||||
|
|
||||||
|
define HAL_DISABLE_LOOP_DELAY
|
||||||
|
|
||||||
|
# enable CAN support
|
||||||
|
|
||||||
|
PA11 CAN1_RX CAN1
|
||||||
|
PA12 CAN1_TX CAN1
|
||||||
|
PB2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
|
PB12 CAN2_RX CAN2
|
||||||
|
PB13 CAN2_TX CAN2
|
||||||
|
PA4 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
define CAN_APP_NODE_NAME "org.ardupilot.HolybroGPS"
|
||||||
|
|
||||||
|
define HAL_NO_GCS
|
||||||
|
define HAL_NO_LOGGING
|
||||||
|
define HAL_NO_MONITOR_THREAD
|
||||||
|
|
||||||
|
define HAL_MINIMIZE_FEATURES 0
|
||||||
|
|
||||||
|
define HAL_BUILD_AP_PERIPH
|
||||||
|
|
||||||
|
define HAL_DEVICE_THREAD_STACK 768
|
||||||
|
|
||||||
|
# we setup a small defaults.parm
|
||||||
|
define AP_PARAM_MAX_EMBEDDED_PARAM 256
|
||||||
|
|
||||||
|
# disable dual GPS and GPS blending to save flash space
|
||||||
|
define GPS_MAX_RECEIVERS 1
|
||||||
|
define GPS_MAX_INSTANCES 1
|
||||||
|
define HAL_COMPASS_MAX_SENSORS 1
|
||||||
|
|
||||||
|
# GPS+MAG+BARO+LEDs
|
||||||
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
|
define HAL_PERIPH_ENABLE_MAG
|
||||||
|
define HAL_PERIPH_ENABLE_BARO
|
||||||
|
define HAL_PERIPH_ENABLE_NOTIFY
|
||||||
|
define HAL_PERIPH_ENABLE_RC_OUT
|
||||||
|
|
||||||
|
# GPS on 2nd port
|
||||||
|
define HAL_PERIPH_GPS_PORT_DEFAULT 1
|
||||||
|
|
||||||
|
# enable NCP5623 on 2nd I2C bus
|
||||||
|
define BUILD_DEFAULT_LED_TYPE 128
|
||||||
|
|
||||||
|
# use the app descriptor needed by MissionPlanner for CAN upload
|
||||||
|
env APP_DESCRIPTOR MissionPlanner
|
||||||
|
|
||||||
|
# reserve 256 bytes for comms between app and bootloader
|
||||||
|
RAM_RESERVE_START 256
|
Loading…
Reference in New Issue
Block a user