HAL_ChibiOS: updated to latest hw definitions from master

This commit is contained in:
Andrew Tridgell 2018-11-06 08:44:07 +11:00
parent 9f8ec3849c
commit 633ba4ef20
19 changed files with 1208 additions and 174 deletions

View File

@ -0,0 +1,47 @@
# hw definition file for processing by chibios_pins.py
# for Furious FPV F35 Lightning type hardware bootloader
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 135
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
FLASH_SIZE_KB 1024
# the location where the bootloader will put the firmware
define FLASH_BOOTLOADER_LOAD_KB 64
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
# board voltage
STM32_VDD 330U
# order of UARTs
UART_ORDER OTG1 USART1 USART2 UART5
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# UART1
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# UART2
PA2 USART2_TX USART2
PA3 USART2_RX USART2
# UART5
PC12 UART5_TX UART5
PD2 UART5_RX UART5
PC10 LED_BOOTLOADER OUTPUT LOW GPIO(0)
define HAL_LED_ON 0

View File

@ -0,0 +1,170 @@
# hw definition file for processing by chibios_hwdef.py
# for Furious FPV F35 Lightning type hardware
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 135
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# board voltage
STM32_VDD 330U
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 64
# console
#STDOUT_SERIAL SD1
#STDOUT_BAUDRATE 57600
# order of I2C buses
I2C_ORDER I2C1
# order of UARTs (UART3RX used for RCInput, UART4RX and USART6RX not pinned out)
UART_ORDER OTG1 USART2 USART1 UART5 EMPTY UART4 USART6
# USB sensing
#PA9 VBUS INPUT OPENDRAIN
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# UART1 (telem1)
PA9 USART1_TX USART1
PA10 USART1_RX USART1
# UART2 (GPS)
PA2 USART2_TX USART2
PA3 USART2_RX USART2
# UART3RX (RCInput)
PB11 TIM2_CH4 TIM2 RCININT FLOAT LOW
PA8 SBUS_INVERT_RX OUTPUT
# UART4 (user), only TX pinned out
PA0 UART4_TX UART4
PC11 UART4_RX UART4
# UART5 (telem2)
PC12 UART5_TX UART5
PD2 UART5_RX UART5
# USART6 (user), only TX pinned out as "SPO" pin with hw inverter
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# ADCs
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
PC3 RSSI_IN ADC1 SCALE(2)
define BOARD_RSSI_ANA_PIN 13
# also could be used as analog airspeed input
#PC3 PRESSURE_SENS ADC1 SCALE(2)
# VDD sense pin
#PA4 VDD_5V_SENS ADC1 SCALE(2)
# LED
PC10 LED OUTPUT HIGH GPIO(57)
define HAL_GPIO_A_LED_PIN 57
# SPI
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
# CS pins
PC0 MPU9250_CS CS
PA4 OSD_CS CS
PC5 BMP280_CS CS
#PB12 SDCARD_CS CS
PC4 MPU9250_DRDY INPUT
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
#PA13 JTMS-SWDIO SWD
#PA14 JTCK-SWCLK SWD
# passive buzzer disabled, optional timers 2 and 5 used for RCinput and STM32
# PA1 TIM2_CH2 TIM2 GPIO(77) ALARM
# use active buzzer instead
PA1 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
define HAL_BUZZER_ON 1
define HAL_BUZZER_OFF 0
# I2C
PB6 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
# PWM pins S1-S6
define BOARD_PWM_COUNT_DEFAULT 6
define STM32_PWM_USE_ADVANCED TRUE
PC8 TIM8_CH3 TIM8 PWM(1) GPIO(50)
PC9 TIM8_CH4 TIM8 PWM(2) GPIO(51)
PB8 TIM4_CH3 TIM4 PWM(3) GPIO(52)
PB9 TIM4_CH4 TIM4 PWM(4) GPIO(53)
PB0 TIM3_CH3 TIM3 PWM(5) GPIO(54)
PB1 TIM3_CH4 TIM3 PWM(6) GPIO(55)
# SPI device table
SPIDEV mpu9250 SPI3 DEVID1 MPU9250_CS MODE3 4*MHZ 8*MHZ
SPIDEV bmp280 SPI3 DEVID2 BMP280_CS MODE3 1*MHZ 8*MHZ
SPIDEV osd SPI1 DEVID1 OSD_CS MODE0 10*MHZ 10*MHZ
#SPIDEV sdcard SPI2 DEVID1 SDCARD_CS MODE0 400*KHZ 25*MHZ
define HAL_INS_DEFAULT HAL_INS_MPU9250_SPI
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_90
# mag defines
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_AK8963_MPU9250
define HAL_COMPASS_AK8963_MPU9250_ROTATION ROTATION_YAW_90
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# baro defines
define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
define HAL_BARO_BMP280_NAME "bmp280"
# external baro probing
define HAL_PROBE_EXTERNAL_I2C_BAROS
# no onboard SD, filesystem support disabled until flash logging implemented
#define HAL_OS_FATFS_IO 1
#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# OSD support
define OSD_ENABLED ENABLED
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
# available storage
define HAL_STORAGE_SIZE 15360
define STORAGE_FLASH_PAGE 1
# defaults for battery monitoring
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 11
define HAL_BATT_CURR_PIN 12
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 25

View File

@ -128,19 +128,19 @@ define HAL_EXT_COMPASS_HMC5843_I2C_BUS 1
# PWM out pins
PA0 TIM2_CH1 TIM2 PWM(1)
PA1 TIM2_CH2 TIM2 PWM(2)
PA2 TIM2_CH3 TIM2 PWM(3)
PA3 TIM2_CH4 TIM2 PWM(4)
PE9 TIM1_CH1 TIM1 PWM(5)
PE11 TIM1_CH2 TIM1 PWM(6)
PE13 TIM1_CH3 TIM1 PWM(7)
PE14 TIM1_CH4 TIM1 PWM(8)
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50)
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52)
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
PE9 TIM1_CH1 TIM1 PWM(5) GPIO(54)
PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55)
PE13 TIM1_CH3 TIM1 PWM(7) GPIO(56)
PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57)
PD13 TIM4_CH2 TIM4 PWM(9)
PD12 TIM4_CH1 TIM4 PWM(10)
PD15 TIM4_CH4 TIM4 PWM(11)
PD14 TIM4_CH3 TIM4 PWM(12)
PD13 TIM4_CH2 TIM4 PWM(9) GPIO(58)
PD12 TIM4_CH1 TIM4 PWM(10) GPIO(59)
PD15 TIM4_CH4 TIM4 PWM(11) GPIO(60)
PD14 TIM4_CH3 TIM4 PWM(12) GPIO(61)
# also USART6_RX for serial RC
PC7 TIM8_CH2 TIM8 RCIN PULLUP LOW DMA_CH0

View File

@ -32,7 +32,14 @@ STM32_VDD 330U
I2C_ORDER I2C1
# order of UARTs (and USB), USART3 should be in second place to map order with the board's silk screen
UART_ORDER OTG1 USART3 USART1 USART2 UART4
UART_ORDER OTG1 USART3 USART1 USART2 UART4 UART7 USART6
# buzzer
PD15 TIM4_CH4 TIM4 GPIO(77) ALARM
#PD15 BUZZER OUTPUT GPIO(80) LOW
#define HAL_BUZZER_PIN 80
#define HAL_BUZZER_ON 1
#define HAL_BUZZER_OFF 0
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
@ -41,8 +48,6 @@ PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA2 LED0 OUTPUT LOW
# SPI1 for SDCard
PA4 SDCARD_CS CS
PA5 SPI1_SCK SPI1
@ -73,9 +78,11 @@ define HAL_BATT_VOLT_PIN 13
define HAL_BATT_CURR_PIN 12
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
PC5 RSSI_ADC ADC1
PA2 LED0 OUTPUT LOW
# USART1
PA10 USART1_RX USART1
PA9 USART1_TX USART1
@ -89,19 +96,24 @@ PB11 USART3_RX USART3
PB10 USART3_TX USART3
# UART4 (GPS2)
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA0 UART4_TX UART4 NODMA
PA1 UART4_RX UART4 NODMA
# UART6, RX only, for RCIN
# USART6, RX only for RCIN
PC7 TIM8_CH2 TIM8 RCININT FLOAT LOW
PC6 USART6_TX USART6 NODMA LOW
# UART7 USED BY ESC FROM ORIGINAL DESIGN
#PE7 UART7_RX UART7
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PB0 TIM3_CH3 TIM3 PWM(1)
PB1 TIM3_CH4 TIM3 PWM(2)
PE9 TIM1_CH1 TIM1 PWM(3)
PE11 TIM1_CH2 TIM1 PWM(4)
# Motors
PB1 TIM1_CH3N TIM1 PWM(1) GPIO(50)
PE9 TIM1_CH1 TIM1 PWM(2) GPIO(51)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PB0 TIM3_CH3 TIM3 PWM(4) GPIO(53)
PC9 TIM3_CH4 TIM3 PWM(5) GPIO(54)
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
DMA_PRIORITY S*
@ -131,7 +143,11 @@ define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_180
define HAL_OS_FATFS_IO 1
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED ENABLED
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
define BOARD_PWM_COUNT_DEFAULT 6
define STM32_PWM_USE_ADVANCED TRUE

View File

@ -26,11 +26,26 @@ define STORAGE_FLASH_PAGE 1
STM32_VDD 330U
# order of UARTs
UART_ORDER OTG1
UART_ORDER OTG1 USART1 USART3 UART4 UART5 USART6
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA9 USART1_TX USART1
PA10 USART1_RX USART1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PC10 USART3_TX USART3
PC11 USART3_RX USART3
PC12 UART5_TX UART5
PD2 UART5_RX UART5
PA14 LED_BOOTLOADER OUTPUT LOW GPIO(0)
PA13 LED_ACTIVITY OUTPUT LOW GPIO(1) # optional
define HAL_LED_ON 0

View File

@ -83,15 +83,15 @@ define HAL_GPIO_B_LED_PIN 1
#pwm output
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(59)
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(58)
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(26)
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(27)
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(39)
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(40)
PB14 TIM1_CH2N TIM1 PWM(7) GPIO(35)
PB15 TIM1_CH3N TIM1 PWM(8) GPIO(36)
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(41)
PB7 TIM4_CH2 TIM4 PWM(1) GPIO(50)
PB6 TIM4_CH1 TIM4 PWM(2) GPIO(51)
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52)
PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53)
PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54)
PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55)
PB14 TIM1_CH2N TIM1 PWM(7) GPIO(56)
PB15 TIM1_CH3N TIM1 PWM(8) GPIO(57)
PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58)
# SD CARD SPI
PB3 SPI3_SCK SPI3
@ -158,6 +158,7 @@ define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# define default battery setup
define HAL_BATT_MONITOR_DEFAULT 4
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 11

View File

@ -104,10 +104,10 @@ PC6 USART6_TX USART6
# UART7, RX only?
#PE7 UART7_RX UART7
PB0 TIM3_CH3 TIM3 PWM(1)
PB1 TIM3_CH4 TIM3 PWM(2)
PE9 TIM1_CH1 TIM1 PWM(3)
PE11 TIM1_CH2 TIM1 PWM(4)
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50)
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
PE9 TIM1_CH1 TIM1 PWM(3) GPIO(52)
PE11 TIM1_CH2 TIM1 PWM(4) GPIO(53)
define HAL_STORAGE_SIZE 16384
define STORAGE_FLASH_PAGE 1

View File

@ -24,7 +24,7 @@ FLASH_RESERVE_START_KB 64
I2C_ORDER I2C2
# order of UARTs
UART_ORDER OTG1 USART6 USART1
UART_ORDER OTG1 USART6 USART1 UART4
#adc
PC1 BAT_CURR_SENS ADC1 SCALE(1)
@ -58,6 +58,9 @@ PA9 USART1_TX USART1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# UART4 (ESC sensor)
PA1 UART4_RX UART4
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD

View File

@ -34,12 +34,12 @@ PC2 BAT_VOLT_SENS ADC1 SCALE(1)
PA0 RSSI_IN ADC1
#pwm output
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(26)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(27)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(17)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(16)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(15)
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(41)
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55)
PA4 MPU6000_CS CS
PA5 SPI1_SCK SPI1

View File

@ -1,20 +1,20 @@
# hw definition file for processing by chibios_hwdef.py
# for FMUv3 hardware (ie. for Pixhawk1, Pixhawk2 cube, XUAV2.1 etc)
# this hwdef.dat file contains a lot of comments so it can act as a
# This hwdef.dat file contains a lot of comments so it can act as a
# reference for developers adding new boards.
# the hwdef.dat file defines all the hardware peripherals and pins for
# The hwdef.dat file defines all the hardware peripherals and pins for
# a port of ArduPilot to a board using the ChibiOS HAL. You should be
# able to write the hwdef.dat file for a new board with just the
# schematic for the board
# schematic for the board.
# this file is processed by chibios_hwdef.py to create hwdef.h for
# This file is processed by chibios_hwdef.py to create hwdef.h for
# this board. You may find it useful to run chibios_hwdef.py manually
# when building this file for a new board. The resulting hwdef.h file
# is formatted to make it quite readable. It is strongly suggested
# that you read the resulting hwdef.h file when porting to a new board
# to make sure it has resulted in what you want
# to make sure it has resulted in what you want.
# You should read this file in conjunction with the schematic for your
# board, the datasheet for the MCU for your board and the python
@ -28,7 +28,7 @@
# particularly useful when doing a new hwdef.dat file as you can work
# out peripheral numbers given a port/pin name.
# we need to start off by saying what main CPU is on the board. There
# We need to start off by saying what main CPU is on the board. There
# are two CPU identifiers that you need to specify. The first is the
# ChibiOS MCU type. So far we only support STM32F4xx for all STM32F4
# board types. In the future we will add F7 and other MCU types
@ -44,73 +44,73 @@
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# we set a specific HAL_BOARD_SUBTYPE, allowing for custom config in
# We set a specific HAL_BOARD_SUBTYPE, allowing for custom config in
# drivers. For this to be used the subtype needs to be added to
# AP_HAL/AP_HAL_Boards.h as well
# AP_HAL/AP_HAL_Boards.h as well.
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
# now we need to specify the APJ_BOARD_ID. This is the ID that the
# Now we need to specify the APJ_BOARD_ID. This is the ID that the
# bootloader presents to GCS software so it knows if this firmware is
# suitable for the board. Please see
# https://github.com/ArduPilot/Bootloader/blob/master/hw_config.h for
# a list of current board IDs. If you add a new board type then please
# get it added to that repository so we don't get conflicts.
# Note that APJ is "ArduPilot JSON Firmware Format"
# Note that APJ is "ArduPilot JSON Firmware Format".
# board ID for firmware load
APJ_BOARD_ID 9
# now you need to say what crystal frequency you have for this
# Now you need to say what crystal frequency you have for this
# board. All of the clocks are scaled against this. Typical values are
# 24000000 or 8000000
# 24000000 or 8000000.
# crystal frequency
OSCILLATOR_HZ 24000000
# on some boards you will need to also set the various PLL values. See
# On some boards you will need to also set the various PLL values. See
# the defaults in common/mcuconf.h, and use the define mechanism
# explained later in this file to override values suitable for your
# board. Refer to your MCU datasheet or examples from supported boards
# in ChibiOS for the right values.
# now define the voltage the MCU runs at. This is needed for ChibiOS
# to set various internal driver limits. It is in 0.01 volt units
# Now define the voltage the MCU runs at. This is needed for ChibiOS
# to set various internal driver limits. It is in 0.01 volt units.
# board voltage
STM32_VDD 330U
# this is the STM32 timer that ChibiOS will use for the low level
# This is the STM32 timer that ChibiOS will use for the low level
# driver. This must be a 32 bit timer. We currently only support
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details.
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# now the size of flash in kilobytes, for creating the ld.script
# Now the size of flash in kilobytes, for creating the ld.script.
# flash size
FLASH_SIZE_KB 2048
# now define which UART is used for printf(). We rarely use printf()
# Now define which UART is used for printf(). We rarely use printf()
# in ChibiOS, so this is really only for debugging very early startup
# in drivers.
# serial port for stdout. This is optional. If you leave it out then
# output from printf() lines will be thrown away (you can stil use
# hal.console->printf() for the ArduPilot console, which is the first
# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a
# serial device name, and must be for a serial device for which pins
# are defined in this file. For example, SD7 is for UART7 (SD7 ==
# "serial device 7" in ChibiOS).
# Serial port for stdout. This is optional. If you leave it out then
# output from printf() lines will go to the ArduPilot console, which is the
# first UART in the UART_ORDER list. But note that some startup code
# runs before USB is set up.
# The value for STDOUT_SERIAL is a serial device name, and must be for a
# serial device for which pins are defined in this file. For example, SD7
# is for UART7 (SD7 == "serial device 7" in ChibiOS).
#STDOUT_SERIAL SD7
#STDOUT_BAUDRATE 57600
# now the USB setup, if you have USB. All of these settings are
# Now the USB setup, if you have USB. All of these settings are
# option, and the ones below are the defaults. It ends up creating a
# USB ID on Linux like this:
# /dev/serial/by-id/usb-ArduPilot_fmuv3_3E0031000B51353233343932-if00
# if creating a board for a RTF vehicle you may wish to customise these
# If creating a board for a RTF vehicle you may wish to customise these.
# USB setup
USB_VENDOR 0x0483 # ST
@ -119,23 +119,23 @@ USB_STRING_MANUFACTURER "ArduPilot"
USB_STRING_PRODUCT "%BOARD%"
USB_STRING_SERIAL "%SERIAL%"
# now define the order that I2C buses are presented in the hal.i2c API
# Now define the order that I2C buses are presented in the hal.i2c API
# in ArduPilot. For historical reasons inherited from HAL_PX4 the
# 'external' I2C bus should be bus 1 in hal.i2c, and internal I2C bus
# should be bus 0. On fmuv3 the STM32 I2C1 is our external bus and
# I2C2 is our internal bus, so we need to setup the order as I2C2
# followed by I2C1 in order to achieve the conventional order that
# drivers expect
# drivers expect.
# order of I2C buses
I2C_ORDER I2C2 I2C1
# now the UART order. These map to the hal.uartA to hal.uartF
# Now the UART order. These map to the hal.uartA to hal.uartF
# objects. If you use a shorter list then HAL_Empty::UARTDriver
# objects are substituted for later UARTs, or you can leave a gap by
# listing one or more of the uarts as EMPTY
# listing one or more of the uarts as EMPTY.
# the normal usage of this ordering is:
# The normal usage of this ordering is:
# 1) SERIAL0: console (primary mavlink, usually USB)
# 2) SERIAL3: primary GPS
# 3) SERIAL1: telem1
@ -146,15 +146,17 @@ I2C_ORDER I2C2 I2C1
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7
# if the board has an IOMCU connected via a UART then this defines the
# UART to talk to that MCU. Leave it out for boards with no IOMCU
# If the board has an IOMCU connected via a UART then this defines the
# UART to talk to that MCU. Leave it out for boards with no IOMCU.
# UART for IOMCU
IOMCU_UART USART6
# now we start on the pin definitions. Every pin used by ArduPilot
# needs to be in this file. The format is P+port+pin. So PC4 is portC
# pin4. For every pin the 2nd colum is the label. If this is a
# Now we start on the pin definitions. Every pin used by ArduPilot
# needs to be in this file. The pins in this file can be defined in any order.
# The format is P+port+pin. So PC4 is portC pin4.
# For every pin the second column is the label. If this is a
# peripheral that has an alternate function defined in the STM32
# datasheet then the label must be the name of that alternative
# function. The names are looked up in the python database for this
@ -164,48 +166,46 @@ IOMCU_UART USART6
# The third column is the peripheral type. This must be one of the
# following: UARTn, USARTn, OTGn, SPIn, I2Cn, ADCn, TIMn, SWD, SDIO,
# INPUT, OUTPUT, CS
# INPUT, OUTPUT, CS.
# the fourth and later columns are for modifiers on the pin. The
# possible modifiers are
# The fourth and later columns are for modifiers on the pin. The
# possible modifiers are:
# pin speed: SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH
# pullup: PULLUP, PULLDOWN, FLOATING
# out type: OPENDRAIN, PUSHPULL
# default value: LOW, HIGH
# Additionally, each class of pin peripheral can have extra modifiers
# suitable for that pin type. For example, for an OUTPUT you can map
# it to a GPIO number in hal.gpio using the GPIO(n) modifier. For ADC
# inputs you can apply a scaling factor (to bring it to unit volts)
# using the SCALE(x) modifier. See the examples below for more
# modifiers, or read the python code in chibios_hwdef.py
# suitable for that pin type. For example, for an OUTPUT you can map
# it to a GPIO number in hal.gpio using the GPIO(n) modifier. For ADC
# inputs you can apply a scaling factor (to bring it to unit volts)
# using the SCALE(x) modifier. See the examples below for more
# modifiers, or read the python code in chibios_hwdef.py.
# now we define UART4 which is for the GPS, which is a GPS. Be careful
# Now we define UART4 which is for the GPS. Be careful
# of the difference between USART and UART. Check the STM32F427xx.py
# if unsure which it is. For a UART we need to specify at least TX and
# RX pins.
# this pins in this file can be defined in any order.
# UART4 serial GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
# now define the primary battery connectors. The labels we choose hear
# Now define the primary battery connectors. The labels we choose here
# are used to create defines for pins in the various drivers, so
# choose names that match existing board setups where possible. Here
# we define two pins PA2 and PA3 for voltage and current sensing, with
# a scale factor of 1.0 and connected on ADC1. The pin number this
# maps to in hal.adc is automatically determined using the datasheet
# tables in STM32F427xx.py
# tables in STM32F427xx.py.
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
# now the VDD sense pin. This is used to sense primary board voltags
# Now the VDD sense pin. This is used to sense primary board voltage.
PA4 VDD_5V_SENS ADC1 SCALE(2)
# now the first SPI bus. At minimum you need SCK, MISO and MOSI pin
# Now the first SPI bus. At minimum you need SCK, MISO and MOSI pin
definitions. You can add speed modifiers if you want them, otherwise
the defaults for the peripheral class are used.
@ -213,54 +213,54 @@ PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# this defines an output pin which will default to output LOW. It is a
# pin that enables peripheral power on this board
# This defines an output pin which will default to output LOW. It is a
# pin that enables peripheral power on this board.
PA8 VDD_5V_PERIPH_EN OUTPUT LOW
# this is the pin that senses USB being connected. It is an input pin
# setup as OPENDRAIN
# This is the pin that senses USB being connected. It is an input pin
# setup as OPENDRAIN.
PA9 VBUS INPUT OPENDRAIN
# this is a commented out pin for talking to the debug uart on the
# This is a commented out pin for talking to the debug UART on the
# IOMCU, not used yet, but left as a comment (with a '#' in front) for
# future reference
# PA10 IO-debug-console
# now we define the pins that USB is connected on
# 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
# These are the pins for SWD debugging with a STlinkv2 or black-magic probe.
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# this defines the PWM pin for the buzzer (if there is one). It is
# This defines the PWM pin for the buzzer (if there is one). It is
# also mapped to a GPIO output so you can play with the buzzer via
# MAVLink relay commands if you want to
# MAVLink relay commands if you want to.
# PWM output for buzzer
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
# this defines a couple of general purpose outputs, mapped to GPIO
# numbers 1 and 2 for users
# This defines a couple of general purpose outputs, mapped to GPIO
# numbers 1 and 2 for users.
PB0 EXTERN_GPIO1 OUTPUT GPIO(1)
PB1 EXTERN_GPIO2 OUTPUT GPIO(2)
# this defines some input pins, currently unused
# This defines some input pins, currently unused.
PB2 BOOT1 INPUT
PB3 FMU_SW0 INPUT
# this defines the pins for the 2nd CAN interface, if available
# This defines the pins for the 2nd CAN interface, if available.
PB6 CAN2_TX CAN2
PB12 CAN2_RX CAN2
# now the first I2C bus. The pin speeds are automatically setup
# Now the first I2C bus. The pin speeds are automatically setup
# correctly, but can be overridden here if needed.
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# now the 2nd I2C bus
# the 2nd I2C bus
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
@ -269,31 +269,31 @@ PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# this input pin is used to detect that power is valid on USB
# This input pin is used to detect that power is valid on USB.
PC0 VBUS_VALID INPUT
# this defines the CS pin for the magnetometer and first IMU. Note
# This defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
# SPI bus
# SPI bus.
PC1 MAG_CS CS
PC2 MPU_CS CS
# this defines more ADC inputs
# This defines more ADC inputs.
PC3 AUX_POWER ADC1 SCALE(1)
PC4 AUX_ADC2 ADC1 SCALE(1)
# and the analog input for airspeed (rarely used these days)
# And the analog input for airspeed (rarely used these days).
PC5 PRESSURE_SENS ADC1 SCALE(2)
# this sets up the UART for talking to the IOMCU. Note that it is
# This sets up the UART for talking to the IOMCU. Note that it is
# vital that this UART has DMA available. See the DMA settings below
# for more information
# for more information.
# USART6 to IO
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# now setup the pins for the microSD card, if available
# Now setup the pins for the microSD card, if available.
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
@ -301,8 +301,8 @@ PC11 SDIO_D3 SDIO
PC12 SDIO_CK SDIO
PD2 SDIO_CMD SDIO
# more CS pins for more sensors. The labels for all CS pins need to
# match the SPI device table later in this file
# More CS pins for more sensors. The labels for all CS pins need to
# match the SPI device table later in this file.
PC13 GYRO_EXT_CS CS
PC14 BARO_EXT_CS CS
PC15 ACCEL_EXT_CS CS
@ -313,29 +313,29 @@ PE4 MPU_EXT_CS CS
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# Another USART, this one for telem1. This one has RTS and CTS lines
# Another USART, this one for telem1. This one has RTS and CTS lines.
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# the telem2 USART, also with RTS/CTS available
# The telem2 USART, also with RTS/CTS available.
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
# the CS pin for FRAM (ramtron). This one is marked as using
# SPEED_VERYLOW, which matches the HAL_PX4 setup
# The CS pin for FRAM (ramtron). This one is marked as using
# SPEED_VERYLOW, which matches the HAL_PX4 setup.
PD10 FRAM_CS CS SPEED_VERYLOW
# now we start defining some PWM pins. We also map these pins to GPIO
# Now we start defining some PWM pins. We also map these pins to GPIO
# values, so users can set BRD_PWM_COUNT to choose how many of the PWM
# outputs on the primary MCU are setup as PWM and how many as
# GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs
# starting at 50
# starting at 50.
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
@ -345,37 +345,37 @@ PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
define BOARD_PWM_COUNT_DEFAULT 4
# relays default to use GPIO pins 54 and 55
# Relays default to use GPIO pins 54 and 55.
define RELAY1_PIN_DEFAULT 54
define RELAY2_PIN_DEFAULT 55
# this is the invensense data-ready pin. We don't use it in the
# default driver
# This is the invensense data-ready pin. We don't use it in the
# default driver.
PD15 MPU_DRDY INPUT
# now the 2nd GPS UART
# the 2nd GPS UART
# UART8 serial4 GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# now setup SPI bus4
# Now setup SPI bus4.
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# this is the pin to enable the sensors rail. It can be used to power
# This is the pin to enable the sensors rail. It can be used to power
# cycle sensors to recover them in case there are problems with power on
# timing affecting sensor stability. We pull it high by default
# timing affecting sensor stability. We pull it high by default.
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters)
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters).
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# define a LED, mapping it to GPIO(0)
# Define a LED, mapping it to GPIO(0).
PE12 FMU_LED_AMBER OUTPUT GPIO(0)
# power flag pins. These tell the MCU the status of the various power
# Power flag pins: these tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
@ -383,21 +383,21 @@ PB7 VDD_SERVO_VALID INPUT PULLUP
PE10 VDD_5V_HIPOWER_OC INPUT PULLUP
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
# now the SPI device table. This table creates all accessible SPI
# Now the SPI device table. This table creates all accessible SPI
# devices, giving the name of the device (which is used by device
# drivers to open the device), plus which SPI bus it it on, what
# device ID will be used (which controls the IDs used in parameters
# such as COMPASS_DEV_ID, so we can detect when the list of devices
# changes between reboots for calibration purposes), the SPI mode to
# use, and the low and high speed settings for the device
# use, and the low and high speed settings for the device.
# You can define more SPI devices than you actually have, to allow for
# flexibility in board setup, and the driver code can probe to see
# which are responding
# which are responding.
# The DEVID values and device names are chosen to match the PX4 port
# of ArduPilot so users don't need to re-do their accel and compass
# calibrations when moving to ChibiOS
# calibrations when moving to ChibiOS.
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ
SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
@ -419,7 +419,7 @@ SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ
# Now some commented out SPI device names which can be used by
# developers to test that the clock calculations are right for a
# bus. This is used in conjunction with the mavproxy devop module
# bus. This is used in conjunction with the mavproxy devop module.
# for SPI clock testing
#SPIDEV clock500 SPI4 DEVID5 MPU_EXT_CS MODE0 500*KHZ 500*KHZ # gives 329KHz
@ -429,68 +429,71 @@ SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ
#SPIDEV clock8 SPI4 DEVID5 MPU_EXT_CS MODE0 8*MHZ 8*MHZ # gives 5.5MHz
#SPIDEV clock16 SPI4 DEVID5 MPU_EXT_CS MODE0 16*MHZ 16*MHZ # gives 10.6MHz
# this adds a C define which sets up the ArduPilot architecture
# This adds a C define which sets up the ArduPilot architecture
# define. Any line starting with 'define' is copied literally as
# a #define in the hwdef.h header
# a #define in the hwdef.h header.
define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files
# Nnow some defines for logging and terrain data files.
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
# We need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes).
define HAL_STORAGE_SIZE 16384
# now define fallback storage location is flash if no FRAM
# Now define fallback storage location is flash if no FRAM
# fitted. This needs to be carefully chosen to align with your
# bootloader. The flash storage system needs two sectors, and the
# sectors must be at least 20% larger than HAL_STORAGE_SIZE
# sectors must be at least 20% larger than HAL_STORAGE_SIZE.
define STORAGE_FLASH_PAGE 22
# this enables the use of a ramtron device for storage, if one is
# found on SPI. You must have a ramtron entry in the SPI device table
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
# enable RAMTROM parameter storage
# This enables the use of a ramtron device for storage, if one is
# found on SPI. You must have a ramtron entry in the SPI device table.
# Enable RAMTROM parameter storage.
define HAL_WITH_RAMTRON 1
# setup for the possibility of an IMU heater as the pixhawk2 cube has
# an IMU header
# Setup for the possibility of an IMU heater since the pixhawk2 cube has
# an IMU heater.
define HAL_HAVE_IMU_HEATER 1
# enable FAT filesystem support (needs a microSD defined via SDIO)
# Enable FAT filesystem support (needs a microSD defined via SDIO).
define HAL_OS_FATFS_IO 1
# enable RTSCTS support. You should define this if you have any UARTs
with RTS/CTS pins
# Enable RTSCTS support. You should define this if you have any UARTs
with RTS/CTS pins.
define AP_FEATURE_RTSCTS 1
# enable SBUS_OUT on IOMCU (if you have an IOMCU)
# Enable SBUS_OUT on IOMCU (if you have an IOMCU).
define AP_FEATURE_SBUS_OUT 1
# now setup the default battery pins driver analog pins and default
# scaling for the power brick
# Now setup the default battery pins driver analog pins and default
# scaling for the power brick.
define HAL_BATT_VOLT_PIN 2
define HAL_BATT_CURR_PIN 3
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
# this defines the default maximum clock on I2C devices.
# This defines the default maximum clock on I2C devices.
define HAL_I2C_MAX_CLOCK 100000
# uncomment the lines below to enable strict API
# checking in ChibiOS
# Uncomment the lines below to enable strict API
# checking in ChibiOS.
# define CH_DBG_ENABLE_ASSERTS TRUE
# define CH_DBG_ENABLE_CHECKS TRUE
# define CH_DBG_SYSTEM_STATE_CHECK TRUE
# define CH_DBG_ENABLE_STACK_CHECK TRUE
# we can't share IO UART (USART6)
# We can't share the IO UART (USART6).
DMA_NOSHARE USART6_TX USART6_RX ADC1
DMA_PRIORITY USART6*
# list of files to put in ROMFS. For fmuv3 we need an IO firmware so
# List of files to put in ROMFS. For fmuv3 we need an IO firmware so
# we can automatically update the IOMCU firmware on boot. The format
# is "ROMFS ROMFS-filename source-filename". Paths are relative to the
# ardupilot root
# ardupilot root.
ROMFS io_firmware.bin Tools/IO_Firmware/fmuv2_IO.bin

View File

@ -245,6 +245,9 @@ PD2 SDMMC_CMD SDMMC1
define HAL_STORAGE_SIZE 16384
define HAL_WITH_RAMTRON 1
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
define HAL_BARO_DEFAULT HAL_BARO_MS5611_SPI
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE

View File

@ -0,0 +1,77 @@
# hwdef for bootloader for mRoX21-777
# The X2.1-777 is a member of the X2.1 flight controller from Mayan Robotics (mRo) www.mrobotics.io
# Introduced in October 2018
# Designed by Nikolay Arsov, Phillip Kocmoud, and Jordi Munoz
# with a STM32F777VIT6 MCU
# and STM32F103C8T6 IO MCU
# MCU class and specific type
MCU STM32F7xx STM32F777xx
# crystal frequency
OSCILLATOR_HZ 24000000
define STM32_LSECLK 32768U
define STM32_LSEDRV (3U << 3U)
define STM32_PLLSRC STM32_PLLSRC_HSE
define STM32_PLLM_VALUE 24
define STM32_PLLN_VALUE 432
define STM32_PLLP_VALUE 2
define STM32_PLLQ_VALUE 9
# board ID for firmware load
APJ_BOARD_ID 136
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# USB setup
USB_VENDOR 0x0483 # ST
USB_PRODUCT 0x5740
USB_STRING_MANUFACTURER "mRo"
USB_STRING_PRODUCT "X2.1-777"
USB_STRING_SERIAL "%SERIAL%"
# order of UARTs (and USB)
UART_ORDER OTG1 USART2 USART3 UART7
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
# the telem2 USART, also with RTS/CTS available
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# define a LED
PE12 LED_BOOTLOADER OUTPUT
define HAL_LED_ON 1
# 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
# no reserved flash for bootloader
FLASH_RESERVE_START_KB 0
# start on 4th sector (1st sector for bootloader, 2 for extra storage)
define FLASH_BOOTLOADER_LOAD_KB 96
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -0,0 +1,463 @@
# The X2.1-777 is a member of the X2.1 flight controller from Mayan Robotics (mRo)
# Introduced in October 2018
# Designed by Nick Arsov, Phillip Kocmoud, and Jordi Munoz
# with a STM32F777VIT6 MCU
# and STM32F103C8T6 IO MCU
# MCU class and specific type
MCU STM32F7xx STM32F777xx
# we set a specific HAL_BOARD_SUBTYPE, allowing for custom config in
# drivers. For this to be used the subtype needs to be added to
# AP_HAL/AP_HAL_Boards.h as well
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
# Set Proper Sensor Orientation
define BOARD_TYPE_DEFAULT 20
# now we need to specify the APJ_BOARD_ID. This is the ID that the
# bootloader presents to GCS software so it knows if this firmware is
# suitable for the board. Please see
# https://github.com/ArduPilot/Bootloader/blob/master/hw_config.h for
# a list of current board IDs. If you add a new board type then please
# get it added to that repository so we don't get conflicts.
# Note that APJ is "ArduPilot JSON Firmware Format"
# crystal frequency
OSCILLATOR_HZ 24000000
define STM32_LSECLK 32768U
define STM32_LSEDRV (3U << 3U)
define STM32_PLLSRC STM32_PLLSRC_HSE
define STM32_PLLM_VALUE 24
define STM32_PLLN_VALUE 432
define STM32_PLLP_VALUE 2
define STM32_PLLQ_VALUE 9
# board ID for firmware load
APJ_BOARD_ID 136
# on some boards you will need to also set the various PLL values. See
# the defaults in common/mcuconf.h, and use the define mechanism
# explained later in this file to override values suitable for your
# board. Refer to your MCU datasheet or examples from supported boards
# in ChibiOS for the right values.
# now define the voltage the MCU runs at. This is needed for ChibiOS
# to set various internal driver limits. It is in 0.01 volt units
# board voltage
STM32_VDD 330U
# this is the STM32 timer that ChibiOS will use for the low level
# driver. This must be a 32 bit timer. We currently only support
# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# now the size of flash in kilobytes, for creating the ld.script
# flash size
FLASH_SIZE_KB 2048
# now define which UART is used for printf(). We rarely use printf()
# in ChibiOS, so this is really only for debugging very early startup
# in drivers.
# serial port for stdout. This is optional. If you leave it out then
# output from printf() lines will be thrown away (you can stil use
# hal.console->printf() for the ArduPilot console, which is the first
# UART in the UART_ORDER list). The value for STDOUT_SERIAL is a
# serial device name, and must be for a serial device for which pins
# are defined in this file. For example, SD7 is for UART7 (SD7 ==
# "serial device 7" in ChibiOS).
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600
# now the USB setup, if you have USB. All of these settings are
# option, and the ones below are the defaults. It ends up creating a
# USB ID on Linux like this:
# /dev/serial/by-id/usb-ArduPilot_fmuv3_3E0031000B51353233343932-if00
# if creating a board for a RTF vehicle you may wish to customise these
# USB setup
USB_VENDOR 0x0483 # ST
USB_PRODUCT 0x5740
USB_STRING_MANUFACTURER "mRo"
USB_STRING_PRODUCT "X2.1-777"
USB_STRING_SERIAL "%SERIAL%"
# now define the order that I2C buses are presented in the hal.i2c API
# in ArduPilot. For historical reasons inherited from HAL_PX4 the
# 'external' I2C bus should be bus 1 in hal.i2c, and internal I2C bus
# should be bus 0. On fmuv3 the STM32 I2C1 is our external bus and
# I2C2 is our internal bus, so we need to setup the order as I2C2
# followed by I2C1 in order to achieve the conventional order that
# drivers expect
# order of I2C buses
I2C_ORDER I2C1
# now the UART order. These map to the hal.uartA to hal.uartF
# objects. If you use a shorter list then HAL_Empty::UARTDriver
# objects are substituted for later UARTs, or you can leave a gap by
# listing one or more of the uarts as EMPTY
# the normal usage of this ordering is:
# 1) SERIAL0: console (primary mavlink, usually USB)
# 2) SERIAL3: primary GPS
# 3) SERIAL1: telem1
# 4) SERIAL2: telem2
# 5) SERIAL4: GPS2
# 6) SERIAL5: extra UART (usually RTOS debug console)
# order of UARTs (and USB)
UART_ORDER OTG1 UART4 USART2 USART3 UART8 UART7
# if the board has an IOMCU connected via a UART then this defines the
# UART to talk to that MCU. Leave it out for boards with no IOMCU
# UART for IOMCU
IOMCU_UART USART6
# now we start on the pin definitions. Every pin used by ArduPilot
# needs to be in this file. The format is P+port+pin. So PC4 is portC
# pin4. For every pin the 2nd colum is the label. If this is a
# peripheral that has an alternate function defined in the STM32
# datasheet then the label must be the name of that alternative
# function. The names are looked up in the python database for this
# MCU. Please see STM32F427xx.py for the F427 database. That database
# is used to automatically fill in the alternative function (and later
# for the DMA channels).
# The third column is the peripheral type. This must be one of the
# following: UARTn, USARTn, OTGn, SPIn, I2Cn, ADCn, TIMn, SWD, SDIO,
# INPUT, OUTPUT, CS
# the fourth and later columns are for modifiers on the pin. The
# possible modifiers are
# pin speed: SPEED_VERYLOW, SPEED_LOW, SPEED_MEDIUM, SPEED_HIGH
# pullup: PULLUP, PULLDOWN, FLOATING
# out type: OPENDRAIN, PUSHPULL
# default value: LOW, HIGH
# Additionally, each class of pin peripheral can have extra modifiers
# suitable for that pin type. For example, for an OUTPUT you can map
# it to a GPIO number in hal.gpio using the GPIO(n) modifier. For ADC
# inputs you can apply a scaling factor (to bring it to unit volts)
# using the SCALE(x) modifier. See the examples below for more
# modifiers, or read the python code in chibios_hwdef.py
# now we define UART4 which is for the GPS, which is a GPS. Be careful
# of the difference between USART and UART. Check the STM32F427xx.py
# if unsure which it is. For a UART we need to specify at least TX and
# RX pins.
# this pins in this file can be defined in any order.
# UART4 serial GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
# now define the primary battery connectors. The labels we choose hear
# are used to create defines for pins in the various drivers, so
# choose names that match existing board setups where possible. Here
# we define two pins PA2 and PA3 for voltage and current sensing, with
# a scale factor of 1.0 and connected on ADC1. The pin number this
# maps to in hal.adc is automatically determined using the datasheet
# tables in STM32F427xx.py
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PA3 BATT_CURRENT_SENS ADC1 SCALE(1)
# now the VDD sense pin. This is used to sense primary board voltags
PA4 VDD_5V_SENS ADC1 SCALE(2)
# now the first SPI bus. At minimum you need SCK, MISO and MOSI pin
definitions. You can add speed modifiers if you want them, otherwise
the defaults for the peripheral class are used.
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# this defines an output pin which will default to output LOW. It is a
# pin that enables peripheral power on this board
PA8 VDD_5V_PERIPH_EN OUTPUT LOW
# this is the pin that senses USB being connected. It is an input pin
# setup as OPENDRAIN
PA9 VBUS INPUT OPENDRAIN
# this is a commented out pin for talking to the debug uart on the
# IOMCU, not used yet, but left as a comment (with a '#' in front) for
# future reference
# PA10 IO-debug-console
# 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
# this defines the PWM pin for the buzzer (if there is one). It is
# also mapped to a GPIO output so you can play with the buzzer via
# MAVLink relay commands if you want to
# PWM output for buzzer
PA15 TIM2_CH1 TIM2 GPIO(77) ALARM
# this defines a couple of general purpose outputs, mapped to GPIO
# numbers 1 and 2 for users
PB10 EXTERN_GPIO1 OUTPUT GPIO(1) #Kill
# PB1 EXTERN_GPIO2 OUTPUT GPIO(2) #Not Connected
# this defines some input pins, currently unused
# PB2 BOOT1 INPUT
# PB3 FMU_SW0 INPUT
# this defines the pins for the 2nd CAN interface, if available
# PB6 CAN2_TX CAN2 #Not Connected
# PB12 CAN2_RX CAN2 #Not Connected
# now the first I2C bus. The pin speeds are automatically setup
# correctly, but can be overridden here if needed.
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# now the 2nd I2C bus
# PB10 I2C2_SCL I2C2
# PB11 I2C2_SDA I2C2
# the 2nd SPI bus
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# this input pin is used to detect that power is valid on USB
PC0 VBUS_VALID INPUT
# this defines the CS pin for the magnetometer and first IMU. Note
# that CS pins are software controlled, and are not tied to a particular
# SPI bus
PC1 MAG_CS CS #Not Connected
PC2 MPU_CS CS #MPU9250
# this defines more ADC inputs
PC3 AUX_POWER ADC1 SCALE(1)
PC4 AUX_ADC2 ADC1 SCALE(1)
# and the analog input for airspeed (rarely used these days)
PC5 PRESSURE_SENS ADC1 SCALE(2)
# this sets up the UART for talking to the IOMCU. Note that it is
# vital that this UART has DMA available. See the DMA settings below
# for more information
# USART6 to IO
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# now setup the pins for the microSD card, if available
PC8 SDMMC_D0 SDMMC1
PC9 SDMMC_D1 SDMMC1
PC10 SDMMC_D2 SDMMC1
PC11 SDMMC_D3 SDMMC1
PC12 SDMMC_CK SDMMC1
PD2 SDMMC_CMD SDMMC1
# more CS pins for more sensors. The labels for all CS pins need to
# match the SPI device table later in this file
# PC13 GYRO_EXT_CS CS #Not Connected
# PC14 BARO_EXT_CS CS
PC15 ACCEL_CS CS #MPU20602
PD7 BARO_CS CS #MS5611
# PC15 MPU_EXT_CS CS #MPU20602
# the first CAN bus
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
# Another USART, this one for telem1. This one has RTS and CTS lines
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# the telem2 USART, also with RTS/CTS available
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD11 USART3_CTS USART3
PD12 USART3_RTS USART3
# the CS pin for FRAM (ramtron). This one is marked as using
# SPEED_VERYLOW, which matches the HAL_PX4 setup
PD10 FRAM_CS CS SPEED_VERYLOW
# now we start defining some PWM pins. We also map these pins to GPIO
# values, so users can set BRD_PWM_COUNT to choose how many of the PWM
# outputs on the primary MCU are setup as PWM and how many as
# GPIOs. To match HAL_PX4 we number the GPIOs for the PWM outputs
# starting at 50
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51)
PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52)
PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53)
PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54)
PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55)
# this is the invensense data-ready pin. We don't use it in the
# default driver
PD15 MPU_DRDY INPUT
# now the 2nd GPS UART
# UART8 serial4 GPS2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# now setup SPI bus4
# PE2 SPI4_SCK SPI4 #Not Connected
# PE5 SPI4_MISO SPI4 #Not Connected
# PE6 SPI4_MOSI SPI4 #Not Connected
# this is the pin to enable the sensors rail. It can be used to power
# cycle sensors to recover them in case there are problems with power on
# timing affecting sensor stability. We pull it high by default
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters)
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# define a LED, mapping it to GPIO(0)
PE12 FMU_LED_AMBER OUTPUT GPIO(0)
# power flag pins. These tell the MCU the status of the various power
# supplies that are available. The pin names need to exactly match the
# names used in AnalogIn.cpp.
PB5 VDD_BRICK_VALID INPUT PULLUP
# PB7 VDD_SERVO_VALID INPUT PULLUP #Not Connected
# PE10 VDD_5V_HIPOWER_OC INPUT PULLUP #Not Connected
PE15 VDD_5V_PERIPH_OC INPUT PULLUP
# now the SPI device table. This table creates all accessible SPI
# devices, giving the name of the device (which is used by device
# drivers to open the device), plus which SPI bus it it on, what
# device ID will be used (which controls the IDs used in parameters
# such as COMPASS_DEV_ID, so we can detect when the list of devices
# changes between reboots for calibration purposes), the SPI mode to
# use, and the low and high speed settings for the device
# You can define more SPI devices than you actually have, to allow for
# flexibility in board setup, and the driver code can probe to see
# which are responding
# The DEVID values and device names are chosen to match the PX4 port
# of ArduPilot so users don't need to re-do their accel and compass
# calibrations when moving to ChibiOS
SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE0 20*MHZ 20*MHZ
# SPIDEV ms5611_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ
# SPIDEV mpu6000 SPI1 DEVID4 MPU_CS MODE0 2*MHZ 8*MHZ
SPIDEV icm20608-am SPI1 DEVID2 ACCEL_CS MODE0 4*MHZ 8*MHZ
SPIDEV mpu9250 SPI1 DEVID4 MPU_CS MODE0 4*MHZ 8*MHZ
# SPIDEV mpu9250_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ
# SPIDEV hmc5843 SPI1 DEVID5 MAG_CS MODE3 11*MHZ 11*MHZ
# SPIDEV lsm9ds0_g SPI1 DEVID1 GYRO_EXT_CS MODE0 11*MHZ 11*MHZ
# SPIDEV lsm9ds0_am SPI1 DEVID2 ACCEL_EXT_CS MODE0 11*MHZ 11*MHZ
# SPIDEV lsm9ds0_ext_g SPI4 DEVID4 GYRO_EXT_CS MODE3 11*MHZ 11*MHZ
# SPIDEV lsm9ds0_ext_am SPI4 DEVID3 ACCEL_EXT_CS MODE3 11*MHZ 11*MHZ
SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ
# SPIDEV external0m0 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ
# SPIDEV external0m1 SPI4 DEVID5 MPU_EXT_CS MODE1 2*MHZ 2*MHZ
# SPIDEV external0m2 SPI4 DEVID5 MPU_EXT_CS MODE2 2*MHZ 2*MHZ
# SPIDEV external0m3 SPI4 DEVID5 MPU_EXT_CS MODE3 2*MHZ 2*MHZ
# SPIDEV pixartPC15 SPI4 DEVID13 ACCEL_EXT_CS MODE3 2*MHZ 2*MHZ
# Now some commented out SPI device names which can be used by
# developers to test that the clock calculations are right for a
# bus. This is used in conjunction with the mavproxy devop module
# for SPI clock testing
#SPIDEV clock500 SPI4 DEVID5 MPU_EXT_CS MODE0 500*KHZ 500*KHZ # gives 329KHz
#SPIDEV clock1 SPI4 DEVID5 MPU_EXT_CS MODE0 1*MHZ 1*MHZ # gives 657kHz
#SPIDEV clock2 SPI4 DEVID5 MPU_EXT_CS MODE0 2*MHZ 2*MHZ # gives 1.3MHz
#SPIDEV clock4 SPI4 DEVID5 MPU_EXT_CS MODE0 4*MHZ 4*MHZ # gives 2.6MHz
#SPIDEV clock8 SPI4 DEVID5 MPU_EXT_CS MODE0 8*MHZ 8*MHZ # gives 5.5MHz
#SPIDEV clock16 SPI4 DEVID5 MPU_EXT_CS MODE0 16*MHZ 16*MHZ # gives 10.6MHz
# this adds a C define which sets up the ArduPilot architecture
# define. Any line starting with 'define' is copied literally as
# a #define in the hwdef.h header
define HAL_CHIBIOS_ARCH_FMUV3 1
# now some defines for logging and terrain data files
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# we need to tell HAL_ChibiOS/Storage.cpp how much storage is
# available (in bytes)
define HAL_STORAGE_SIZE 16384
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
# this enables the use of a ramtron device for storage, if one is
# found on SPI. You must have a ramtron entry in the SPI device table
# enable RAMTROM parameter storage
define HAL_WITH_RAMTRON 1
# setup for the possibility of an IMU heater as the The CUBE has
# an IMU header
define HAL_HAVE_IMU_HEATER 1
# enable FAT filesystem support (needs a microSD defined via SDIO)
define HAL_OS_FATFS_IO 1
# enable RTSCTS support. You should define this if you have any UARTs
with RTS/CTS pins
define AP_FEATURE_RTSCTS 1
# enable SBUS_OUT on IOMCU (if you have an IOMCU)
define AP_FEATURE_SBUS_OUT 1
# now setup the default battery pins driver analog pins and default
# scaling for the power brick
define HAL_BATT_VOLT_PIN 2
define HAL_BATT_CURR_PIN 3
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
# this defines the default maximum clock on I2C devices.
define HAL_I2C_MAX_CLOCK 100000
# uncomment the lines below to enable strict API
# checking in ChibiOS
# define CH_DBG_ENABLE_ASSERTS TRUE
# define CH_DBG_ENABLE_CHECKS TRUE
# define CH_DBG_SYSTEM_STATE_CHECK TRUE
# define CH_DBG_ENABLE_STACK_CHECK TRUE
# we can't share IO UART (USART6)
DMA_NOSHARE USART6_TX USART6_RX ADC1
DMA_PRIORITY USART6*
# start on 4th sector (1st sector for bootloader, 2 for extra storage)
FLASH_RESERVE_START_KB 96
# fallback storage in case FRAM is not populated
define STORAGE_FLASH_PAGE 1
# list of files to put in ROMFS. For fmuv3 we need an IO firmware so
# we can automatically update the IOMCU firmware on boot. The format
# is "ROMFS ROMFS-filename source-filename". Paths are relative to the
# ardupilot root
ROMFS io_firmware.bin Tools/IO_Firmware/fmuv2_IO.bin

View File

@ -182,6 +182,9 @@ define HAL_WITH_RAMTRON 1
# fallback to flash storage
define STORAGE_FLASH_PAGE 22
# allow to have have a dedicated safety switch pin
define HAL_HAVE_SAFETY_SWITCH 1
# enable FAT filesystem
define HAL_OS_FATFS_IO 1

View File

@ -0,0 +1,41 @@
# hw definition file for processing by chibios_pins.py
# for bootloader for mini-pix hardware from RadioLink
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 3
# crystal frequency
OSCILLATOR_HZ 24000000
# flash size
FLASH_SIZE_KB 1024
# don't allow bootloader to use more than 16k
FLASH_USE_MAX_KB 16
# bootloader loads at start of flash
FLASH_RESERVE_START_KB 0
# LEDs
PB1 LED_BOOTLOADER OUTPUT LOW
PE12 LED_ACTIVITY OUTPUT LOW
define HAL_LED_ON 0
# the location where the bootloader will put the firmware
define FLASH_BOOTLOADER_LOAD_KB 16
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
UART_ORDER OTG1
# USB pins
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384

View File

@ -34,12 +34,12 @@ PC2 BAT_VOLT_SENS ADC1 SCALE(1)
PA0 RSSI_IN ADC1
#pwm output
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(26)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(27)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(17)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(16)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(15)
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(41)
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55)
PA4 MPU6000_CS CS
PA5 SPI1_SCK SPI1

View File

@ -0,0 +1,40 @@
# hw definition file for processing by chibios_pins.py
# for omnibusf4 V6 bootloader
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 137
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
FLASH_SIZE_KB 1024
# don't allow bootloader to use more than 16k
FLASH_USE_MAX_KB 16
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# LEDs
PA8 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 0
# the location where the bootloader will put the firmware
define FLASH_BOOTLOADER_LOAD_KB 64
# board voltage
STM32_VDD 330U
# order of UARTs
UART_ORDER OTG1
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 15360

View File

@ -0,0 +1,149 @@
# hw definition file for processing by chibios_pins.py
# Omnibus F4 V6
# with F405 mcu, mpu6000 imu, bmp280 barometer, 7456 series osd, no flash log storage
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID for firmware load
APJ_BOARD_ID 137
# crystal frequency
OSCILLATOR_HZ 8000000
STM32_PLLM_VALUE 8
# board voltage
STM32_VDD 330U
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# flash size
FLASH_SIZE_KB 1024
FLASH_RESERVE_START_KB 64
# order of I2C buses
I2C_ORDER I2C1
# order of UARTs
UART_ORDER OTG1 USART6 USART1 UART4 USART3
#PINS
PA10 USART1_RX USART1
PA9 USART1_TX USART1
PC6 USART6_TX USART6
PC7 USART6_RX USART6
PB10 USART3_TX USART3
PB11 USART3_RX USART3
# UART4 (only RX) #"TX" pin PA0 is used for RSSI_ADC_CHANNEL
PA1 UART4_RX UART4
#adc
PC1 BAT_CURR_SENS ADC1 SCALE(1)
PC2 BAT_VOLT_SENS ADC1 SCALE(1)
PA0 RSSI_IN ADC1
#pwm output # PWM out pins. Channel order (GPIOs) follows the ArduPilot motor
# order conventions
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PB5 TIM3_CH2 TIM3 PWM(4) GPIO(53)
PC9 TIM8_CH4 TIM8 PWM(5) GPIO(54)
PC8 TIM8_CH3 TIM8 PWM(6) GPIO(55)
# spi bus for IMU
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PC12 SPI3_MOSI SPI3
PC11 SPI3_MISO SPI3
PC10 SPI3_SCK SPI3
PA4 MPU6000_CS CS #SPI1_NSS
PA15 OSD_CS CS #SPI3_NSS
PB3 BMP280_CS CS #SPI3_NSS
# note that this board needs PULLUP on I2C pins
PB8 I2C1_SCL I2C1 PULLUP
PB9 I2C1_SDA I2C1 PULLUP
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA8 LED OUTPUT HIGH GPIO(41)
#PB4 TIM3_CH1 TIM3 GPIO(70) ALARM
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PC5 VBUS INPUT OPENDRAIN
# LED strip output pad used for RC input
# timer 4 is free (not used for pwm)
PB6 TIM4_CH1 TIM4 RCININT PULLDOWN LOW
#Omnibus F4 V3 and later had hw inverter on UART6
#Overide it to use as GPS UART port
#PC8 SBUS_INVERT_RX OUTPUT LOW
#PC9 SBUS_INVERT_TX OUTPUT LOW
########### SPI Devices
SPIDEV mpu6000 SPI1 DEVID1 MPU6000_CS MODE3 1*MHZ 8*MHZ
SPIDEV bmp280 SPI3 DEVID3 BMP280_CS MODE3 1*MHZ 8*MHZ
SPIDEV osd SPI3 DEVID4 OSD_CS MODE0 10*MHZ 10*MHZ
define HAL_INS_DEFAULT HAL_INS_MPU60XX_SPI
# V6 needs 90 degree gyro alignment
define HAL_INS_DEFAULT_ROTATION ROTATION_YAW_90
# Baro
define HAL_BARO_DEFAULT HAL_BARO_BMP280_SPI
define HAL_BARO_BMP280_NAME "bmp280"
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define STORAGE_FLASH_PAGE 1
define HAL_STORAGE_SIZE 15360
# define default battery setup
define HAL_BATT_VOLT_PIN 12
define HAL_BATT_CURR_PIN 11
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 18.2
#analog rssi pin (also could be used as analog airspeed input)
#PA0 - ADC123_CH0
define BOARD_RSSI_ANA_PIN 0
define HAL_GPIO_A_LED_PIN 41
#To have complementary channels work we define this
define STM32_PWM_USE_ADVANCED TRUE
define BOARD_PWM_COUNT_DEFAULT 6
define OSD_ENABLED ENABLED
#font for the osd
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

View File

@ -129,6 +129,9 @@ define HAL_BARO_DEFAULT HAL_BARO_MS5611_I2C
define HAL_BARO_MS5611_I2C_BUS 0
define HAL_BARO_MS5611_I2C_ADDR 0x77
# also allow for probing of external barometers
define HAL_PROBE_EXTERNAL_I2C_BAROS
# SPI devices
SPIDEV mpu6000 SPI1 DEVID1 MPU_CS MODE3 1*MHZ 8*MHZ
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 1*MHZ 8*MHZ