HAL_ChibiOS: added FreeflyRTK GPS build
a F732 based GPS peripheral
This commit is contained in:
parent
a23e821f94
commit
b7fffe35f9
89
libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat
Normal file
89
libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef-bl.dat
Normal file
@ -0,0 +1,89 @@
|
|||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32F7xx STM32F732xx
|
||||||
|
|
||||||
|
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 1028
|
||||||
|
|
||||||
|
# setup build for a peripheral firmware
|
||||||
|
env AP_PERIPH 1
|
||||||
|
|
||||||
|
# crystal frequency
|
||||||
|
OSCILLATOR_HZ 16000000
|
||||||
|
|
||||||
|
# assume 512k flash part
|
||||||
|
FLASH_SIZE_KB 512
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER OTG1
|
||||||
|
|
||||||
|
PC7 USB_RESET_N OUTPUT PUSHPULL HIGH
|
||||||
|
|
||||||
|
# use safety button to stay in bootloader
|
||||||
|
PC14 STAY_IN_BOOTLOADER INPUT PULLDOWN
|
||||||
|
define HAL_STAY_IN_BOOTLOADER_VALUE 1
|
||||||
|
|
||||||
|
PA6 LED_BOOTLOADER OUTPUT HIGH
|
||||||
|
define HAL_LED_ON 0
|
||||||
|
|
||||||
|
# Now we define the pins that USB is connected on.
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
define HAL_USE_SERIAL FALSE
|
||||||
|
|
||||||
|
define STM32_SERIAL_USE_USART1 FALSE
|
||||||
|
define STM32_SERIAL_USE_USART2 FALSE
|
||||||
|
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
|
||||||
|
PB8 CAN1_RX CAN1
|
||||||
|
PB9 CAN1_TX CAN1
|
||||||
|
|
||||||
|
define HAL_USE_CAN TRUE
|
||||||
|
define STM32_CAN_USE_CAN1 TRUE
|
||||||
|
|
||||||
|
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
# make bl baudrate match debug baudrate for easier debugging
|
||||||
|
define BOOTLOADER_BAUDRATE 57600
|
||||||
|
|
||||||
|
# use a small bootloader timeout
|
||||||
|
define HAL_BOOTLOADER_TIMEOUT 1000
|
||||||
|
|
||||||
|
# reserve 256 bytes for comms between app and bootloader
|
||||||
|
RAM_RESERVE_START 256
|
||||||
|
|
||||||
|
# Add CS pins to ensure they are high in bootloader
|
||||||
|
PA15 IMU_CS CS
|
172
libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat
Normal file
172
libraries/AP_HAL_ChibiOS/hwdef/FreeflyRTK/hwdef.dat
Normal file
@ -0,0 +1,172 @@
|
|||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
# MCU class and specific type
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32F7xx STM32F732xx
|
||||||
|
|
||||||
|
# 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 1028
|
||||||
|
|
||||||
|
# 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
|
||||||
|
|
||||||
|
# order of UARTs
|
||||||
|
SERIAL_ORDER OTG1 USART2 USART3
|
||||||
|
|
||||||
|
# a LED to flash (disabled as used for safety LED)
|
||||||
|
# PA6 LED OUTPUT HIGH
|
||||||
|
# define HAL_LED_ON 0
|
||||||
|
|
||||||
|
# USART2 for F9P GPS UART2
|
||||||
|
PA2 USART2_TX USART2 NODMA
|
||||||
|
PA3 USART2_RX USART2 NODMA
|
||||||
|
|
||||||
|
# USART3 for F9P GPS UART1
|
||||||
|
PB10 USART3_TX USART3
|
||||||
|
PB11 USART3_RX USART3
|
||||||
|
|
||||||
|
# Now we define the pins that USB is connected on.
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
# SWD debugging
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
# two I2C buses
|
||||||
|
PB7 I2C1_SDA I2C1
|
||||||
|
PB6 I2C1_SCL I2C1
|
||||||
|
|
||||||
|
PC9 I2C3_SDA I2C3
|
||||||
|
PA8 I2C3_SCL I2C3
|
||||||
|
|
||||||
|
# adjust I2C timing from Stm32CubeMX, with 100ns rise, 100ns fall
|
||||||
|
define HAL_I2C_F7_100_TIMINGR 0x10906999
|
||||||
|
|
||||||
|
define HAL_USE_I2C TRUE
|
||||||
|
|
||||||
|
define STM32_I2C_USE_I2C1 TRUE
|
||||||
|
define STM32_I2C_USE_I2C3 TRUE
|
||||||
|
|
||||||
|
define HAL_I2C_CLEAR_ON_TIMEOUT 0
|
||||||
|
|
||||||
|
define HAL_I2C_INTERNAL_MASK 3
|
||||||
|
|
||||||
|
I2C_ORDER I2C1 I2C3
|
||||||
|
|
||||||
|
# one SPI bus
|
||||||
|
PB3 SPI3_SCK SPI3
|
||||||
|
PC11 SPI3_MISO SPI3
|
||||||
|
PC12 SPI3_MOSI SPI3
|
||||||
|
|
||||||
|
# SPI CS
|
||||||
|
PA15 IMU_CS CS
|
||||||
|
|
||||||
|
# SPI devices
|
||||||
|
SPIDEV lsm6ds3 SPI3 DEVID1 IMU_CS MODE0 1*MHZ 8*MHZ
|
||||||
|
|
||||||
|
# compass
|
||||||
|
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_PITCH_90
|
||||||
|
|
||||||
|
# baro
|
||||||
|
BARO BMP388 I2C:0:0x77
|
||||||
|
|
||||||
|
# safety LED, active low is same as main LED
|
||||||
|
PA6 SAFE_LED OUTPUT HIGH
|
||||||
|
define SAFE_LED_ON 0
|
||||||
|
|
||||||
|
# safety button
|
||||||
|
PC14 SAFE_BUTTON INPUT FLOATING
|
||||||
|
define HAL_SAFE_BUTTON_ON 1
|
||||||
|
|
||||||
|
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
|
||||||
|
PB8 CAN1_RX CAN1
|
||||||
|
PB9 CAN1_TX CAN1
|
||||||
|
|
||||||
|
# use DNA
|
||||||
|
define HAL_CAN_DEFAULT_NODE_ID 0
|
||||||
|
|
||||||
|
define CAN_APP_NODE_NAME "org.ardupilot.FreeflyRTK"
|
||||||
|
|
||||||
|
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+Buzzer+NeoPixels
|
||||||
|
define HAL_PERIPH_ENABLE_GPS
|
||||||
|
define HAL_PERIPH_ENABLE_MAG
|
||||||
|
define HAL_PERIPH_ENABLE_BARO
|
||||||
|
define HAL_PERIPH_ENABLE_RC_OUT
|
||||||
|
define HAL_PERIPH_ENABLE_NOTIFY
|
||||||
|
|
||||||
|
# use NCP5623 RGB LED on I2C1
|
||||||
|
define BUILD_DEFAULT_LED_TYPE 128
|
||||||
|
|
||||||
|
define BARO_MAX_INSTANCES 1
|
||||||
|
|
||||||
|
define HAL_PERIPH_GPS_PORT_DEFAULT 2
|
||||||
|
|
||||||
|
# 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
|
||||||
|
|
||||||
|
# listen for reboot command from uploader.py script
|
||||||
|
# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0
|
||||||
|
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
Loading…
Reference in New Issue
Block a user