mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: add JFB100 board definition
This commit is contained in:
parent
4637156e6c
commit
e9bda3a311
|
@ -0,0 +1,123 @@
|
|||
# JFB-100 Flight Controller
|
||||
|
||||
The JFB-100 flight controller is sold by [JAE](https://www.jae.com/files/user/motion-sense-control/catalog/jfb-100-ja.pdf)
|
||||
|
||||
## Features
|
||||
|
||||
- STM32F765 microcontroller
|
||||
- Two IMUs: ICM20602 and SCHA63T
|
||||
- MS5611 SPI barometer
|
||||
- builtin I2C IST8310 magnetometer
|
||||
- microSD card slot
|
||||
- 6 UARTs plus USB
|
||||
- 8 PWM outputs
|
||||
- Four I2C and two CAN ports
|
||||
- External Buzzer
|
||||
- external safety Switch
|
||||
- voltage monitoring for servo rail and Vcc
|
||||
- two dedicated power input ports for external power bricks
|
||||
|
||||
## UART Mapping
|
||||
|
||||
- SERIAL0 -> USB
|
||||
- SERIAL1 -> UART2 (Telem1)
|
||||
- SERIAL2 -> UART3 (Telem2)
|
||||
- SERIAL3 -> UART1 (GPS)
|
||||
- SERIAL4 -> UART4 (GPS2, marked UART/I2CB)
|
||||
- SERIAL5 -> UART6 (RC)
|
||||
- SERIAL6 -> UART7 (spare, debug)
|
||||
|
||||
The Telem1 and Telem2 ports have RTS/CTS pins, the other UARTs do not
|
||||
have RTS/CTS.
|
||||
|
||||
The UART7 connector is labelled debug, but is available as a general
|
||||
purpose UART with ArduPilot.
|
||||
|
||||
## RC Input
|
||||
|
||||
RC input is configured on the port marked DSM/SBUS RC. This connector
|
||||
supports all RC protocols. Two cables are available for this port. To
|
||||
use software binding of Spektrum satellite receivers you need to use
|
||||
the Spektrum satellite cable.
|
||||
|
||||
## PWM Output
|
||||
|
||||
The JFB-100 supports up to 8 PWM outputs.
|
||||
These are directly attached to the STM32F765 and support all
|
||||
PWM protocols. The first 4 of the PWM outputs support DShot.
|
||||
|
||||
The 8 PWM outputs are in 3 groups:
|
||||
|
||||
- PWM 1, 2, 3 and 4 in group1
|
||||
- PWM 5 and 6 in group2
|
||||
- PWM 7 and 8 in group3
|
||||
|
||||
Channels within the same group need to use the same output rate. If
|
||||
any channel in a group uses DShot then all channels in the group need
|
||||
to use DShot.
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has two dedicated power monitor ports on 8 pin
|
||||
connectors. The correct battery setting parameters are dependent on
|
||||
the type of power brick which is connected.
|
||||
|
||||
## Compass
|
||||
|
||||
The JFB-100 has a builtin IST8310 compass. Due to potential
|
||||
interference the board is usually used with an external I2C compass as
|
||||
part of a GPS/Compass combination.
|
||||
|
||||
## GPIOs
|
||||
|
||||
The 6 PWM ports can be used as GPIOs (relays, buttons, RPM etc). To
|
||||
use them you need to limit the number of these pins that is used for
|
||||
PWM by setting the BRD_PWM_COUNT to a number less than 6. For example
|
||||
if you set BRD_PWM_COUNT to 4 then PWM5 and PWM6 will be available for
|
||||
use as GPIOs.
|
||||
|
||||
The numbering of the GPIOs for PIN variables in ArduPilot is:
|
||||
|
||||
- AUX1 50
|
||||
- AUX2 51
|
||||
- AUX3 52
|
||||
- AUX4 53
|
||||
- AUX5 54
|
||||
- AUX6 55
|
||||
|
||||
## Analog inputs
|
||||
|
||||
The JFB-100 has 7 analog inputs
|
||||
|
||||
- ADC Pin0 -> Battery Voltage
|
||||
- ADC Pin1 -> Battery Current Sensor
|
||||
- ADC Pin2 -> Battery Voltage 2
|
||||
- ADC Pin3 -> Battery Current Sensor 2
|
||||
- ADC Pin4 -> ADC port pin 2
|
||||
- ADC Pin14 -> ADC port pin 3
|
||||
- ADC Pin10 -> ADC 5V Sense
|
||||
- ADC Pin11 -> ADC 3.3V Sense
|
||||
- ADC Pin103 -> RSSI voltage monitoring
|
||||
|
||||
## I2C Buses
|
||||
|
||||
- the internal I2C port is bus 0 in ArduPilot (I2C3 in hardware)
|
||||
- the port labelled I2CA is bus 3 in ArduPilot (I2C4 in hardware)
|
||||
- the port labelled I2CB is bus 2 in ArduPilot (I2c2 in hardware)
|
||||
- the port labelled GPS is bus 1 in ArduPilot (I2c1 in hardware)
|
||||
|
||||
|
||||
## CAN
|
||||
|
||||
The JFB-100 has two independent CAN buses, with the following pinouts.
|
||||
|
||||
## Debug
|
||||
|
||||
The JFB-100 supports SWD debugging on the debug port
|
||||
|
||||
|
||||
## Loading Firmware
|
||||
|
||||
The board comes pre-installed with an ArduPilot compatible bootloader,
|
||||
allowing the loading of *.apj firmware files with any ArduPilot
|
||||
compatible ground station.
|
|
@ -0,0 +1,3 @@
|
|||
# JFB-100 board default definition
|
||||
SERIAL5_OPTIONS,8
|
||||
SERIAL5_PROTOCOL,23
|
|
@ -0,0 +1,57 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for F765 bootloader
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1084
|
||||
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
# bootloader is installed at zero offset
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 32
|
||||
|
||||
PC6 LED_BOOTLOADER OUTPUT HIGH
|
||||
PC7 LED_ACTIVITY OUTPUT HIGH
|
||||
define HAL_LED_ON 0
|
||||
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 UART7
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PF10 MS5611_CS CS
|
||||
PF2 SCHA63T_G_CS CS
|
||||
PF3 ICM20602_CS CS SPEED_VERYLOW
|
||||
PF4 SCHA63T_A_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
# PF11 SPARE_CS CS (using for WA6)
|
||||
PH5 AUXMEM_CS CS
|
||||
PI4 EXTERNAL1_CS1 CS
|
||||
PI10 EXTERNAL1_CS2 CS
|
||||
PI11 EXTERNAL1_CS3 CS
|
||||
PI6 EXTERNAL2_CS1 CS
|
||||
PI7 EXTERNAL2_CS2 CS
|
||||
PI8 EXTERNAL2_CS3 CS
|
|
@ -0,0 +1,354 @@
|
|||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for JAE JFB-100 hardware.(modifid based fmuv5)
|
||||
define AP_CUSTOM_FIRMWARE_STRING "(JFB100 V1.0.0)"
|
||||
|
||||
# MCU class and specific type. It is a F765, which is the same as F767
|
||||
# but without the TFT interface
|
||||
MCU STM32F7xx STM32F767xx
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 16000000
|
||||
|
||||
define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_CHIBIOS_FMUV5
|
||||
define HAL_CHIBIOS_ARCH_FMUV5 1
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1084
|
||||
|
||||
FLASH_RESERVE_START_KB 32
|
||||
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 2048
|
||||
|
||||
env OPTIMIZE -O2
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART2 USART3 USART1 UART4 USART6 UART7 OTG2
|
||||
|
||||
# default the 2nd interface to MAVLink2 until MissionPlanner updates drivers
|
||||
define HAL_OTG2_PROTOCOL SerialProtocol_MAVLink2
|
||||
|
||||
# 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
|
||||
|
||||
# SPI1 - internal sensors
|
||||
PG11 SPI1_SCK SPI1
|
||||
PA6 SPI1_MISO SPI1
|
||||
PD7 SPI1_MOSI SPI1
|
||||
|
||||
# SPI2 - FRAM
|
||||
PI1 SPI2_SCK SPI2
|
||||
PI2 SPI2_MISO SPI2
|
||||
PI3 SPI2_MOSI SPI2
|
||||
|
||||
# SPI4 - sensors2
|
||||
PE2 SPI4_SCK SPI4
|
||||
PE13 SPI4_MISO SPI4
|
||||
PE6 SPI4_MOSI SPI4
|
||||
|
||||
# SPI5 - external1 (disabled to save DMA channels)
|
||||
# PF7 SPI5_SCK SPI5
|
||||
# PF8 SPI5_MISO SPI5
|
||||
# PF9 SPI5_MOSI SPI5
|
||||
|
||||
# SPI6 - external2 (disabled to save DMA channels)
|
||||
# PG13 SPI6_SCK SPI6
|
||||
# PG12 SPI6_MISO SPI6
|
||||
# PB5 SPI6_MOSI SPI6
|
||||
|
||||
# sensor CS
|
||||
PF10 MS5611_CS CS
|
||||
PF2 SCHA63T_G_CS CS
|
||||
PF3 ICM20602_CS CS SPEED_VERYLOW
|
||||
PF4 SCHA63T_A_CS CS
|
||||
PF5 FRAM_CS CS SPEED_VERYLOW
|
||||
|
||||
# unusued CS pins
|
||||
# PF11 SPARE_CS CS (using for WA6)
|
||||
PH5 AUXMEM_CS CS
|
||||
PI4 EXTERNAL1_CS1 CS
|
||||
PI10 EXTERNAL1_CS2 CS
|
||||
PI11 EXTERNAL1_CS3 CS
|
||||
PI6 EXTERNAL2_CS1 CS
|
||||
PI7 EXTERNAL2_CS2 CS
|
||||
PI8 EXTERNAL2_CS3 CS
|
||||
|
||||
# I2C buses
|
||||
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
|
||||
PF1 I2C2_SCL I2C2
|
||||
PF0 I2C2_SDA I2C2
|
||||
|
||||
PH7 I2C3_SCL I2C3
|
||||
PH8 I2C3_SDA I2C3
|
||||
|
||||
PF14 I2C4_SCL I2C4
|
||||
PF15 I2C4_SDA I2C4
|
||||
|
||||
# order of I2C buses
|
||||
I2C_ORDER I2C3 I2C1 I2C2 I2C4
|
||||
|
||||
|
||||
# enable pins
|
||||
PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH
|
||||
|
||||
# start peripheral power off, then enable after init
|
||||
# this prevents a problem with radios that use RTS for
|
||||
# bootloader hold
|
||||
PF12 nVDD_5V_HIPOWER_EN OUTPUT HIGH
|
||||
PG4 nVDD_5V_PERIPH_EN OUTPUT HIGH
|
||||
|
||||
PG5 VDD_5V_RC_EN OUTPUT HIGH
|
||||
PG6 VDD_5V_WIFI_EN OUTPUT HIGH
|
||||
PG7 VDD_3V3_SD_CARD_EN OUTPUT HIGH
|
||||
|
||||
# drdy pins
|
||||
# PE7 DRDY8_NC INPUT (using for WA5)
|
||||
PB4 DRDY1_ICM20689 INPUT
|
||||
PB14 DRDY2_SCHA63T_GYRO INPUT
|
||||
PB15 DRDY3_SCHA63T_ACC INPUT
|
||||
PC5 DRDY4_ICM20602 INPUT
|
||||
PC13 DRDY5_SCHA63T_GYRO INPUT
|
||||
PD10 DRDY6_SCHA63T_ACC INPUT
|
||||
PD15 DRDY7_EXTERNAL1 INPUT
|
||||
|
||||
# Control of Spektrum power pin
|
||||
PE4 SPEKTRUM_PWR OUTPUT HIGH GPIO(73)
|
||||
define HAL_GPIO_SPEKTRUM_PWR 73
|
||||
|
||||
# Spektrum Power is Active High
|
||||
define HAL_SPEKTRUM_PWR_ENABLED 1
|
||||
|
||||
# UARTs
|
||||
|
||||
# USART2 is telem1
|
||||
PD6 USART2_RX USART2
|
||||
PD5 USART2_TX USART2
|
||||
PD3 USART2_CTS USART2
|
||||
PD4 USART2_RTS USART2
|
||||
|
||||
# USART1 is GPS1
|
||||
PB7 USART1_RX USART1 NODMA
|
||||
PB6 USART1_TX USART1 NODMA
|
||||
|
||||
# USART3 is telem2
|
||||
PD9 USART3_RX USART3
|
||||
PD8 USART3_TX USART3
|
||||
PD11 USART3_CTS USART3
|
||||
PD12 USART3_RTS USART3
|
||||
|
||||
# UART4 GPS2
|
||||
PD0 UART4_RX UART4 NODMA
|
||||
PD1 UART4_TX UART4 NODMA
|
||||
|
||||
# USART6 is telem3
|
||||
PG9 USART6_RX USART6 NODMA
|
||||
# we leave PG14 as an input to prevent it acting as a pullup
|
||||
# on the IOMCU SBUS input
|
||||
PG14 USART6_TX USART6 NODMA
|
||||
# PG15 USART6_CTS USART6 (using for WA8)
|
||||
# PG8 USART6_RTS USART6 (using for WA7)
|
||||
|
||||
# UART7 is debug
|
||||
PF6 UART7_RX UART7 NODMA
|
||||
PE8 UART7_TX UART7 NODMA
|
||||
|
||||
# UART8 is for IOMCU
|
||||
# PE0 UART8_RX UART8 (using for PP3)
|
||||
# PE1 UART8_TX UART8 (using for PP5)
|
||||
|
||||
# UART for IOMCU
|
||||
# IOMCU_UART UART8
|
||||
|
||||
# RCInput on the PPM pin, for all protocols
|
||||
PI5 TIM8_CH1 TIM8 RCININT PULLUP LOW
|
||||
|
||||
# PWM AUX channels
|
||||
PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50)
|
||||
PA10 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)
|
||||
# we need to disable DMA on the last 2 FMU channels
|
||||
# as timer 12 doesn't have a TIMn_UP DMA option
|
||||
PH6 TIM12_CH1 TIM12 PWM(7) GPIO(56) NODMA
|
||||
PH9 TIM12_CH2 TIM12 PWM(8) GPIO(57) NODMA
|
||||
|
||||
define BOARD_PWM_COUNT_DEFAULT 8
|
||||
|
||||
# PWM output for buzzer
|
||||
PE5 TIM9_CH1 TIM9 GPIO(77) ALARM
|
||||
|
||||
# analog in
|
||||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PA2 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
|
||||
PA3 BATT2_CURRENT_SENS ADC1 SCALE(1)
|
||||
|
||||
PC4 SPARE1_ADC1 ADC1 SCALE(1)
|
||||
PA4 SPARE2_ADC1 ADC1 SCALE(1)
|
||||
|
||||
PB0 RSSI_IN ADC1 SCALE(1)
|
||||
|
||||
PC3 HW_REV_SENS ADC1 SCALE(1)
|
||||
PC2 HW_VER_SENS ADC1 SCALE(1)
|
||||
|
||||
PC0 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC1 SCALED_V3V3 ADC1 SCALE(2)
|
||||
|
||||
# setup scaling defaults for PixHackV5 power brick
|
||||
# define HAL_BATT_VOLT_SCALE 18.0
|
||||
# define HAL_BATT_CURR_SCALE 24.0
|
||||
# setup for supplied power brick
|
||||
define HAL_BATT_VOLT_SCALE 18.182
|
||||
define HAL_BATT_CURR_SCALE 36.364
|
||||
define HAL_BATT_VOLT_PIN 0
|
||||
define HAL_BATT_CURR_PIN 1
|
||||
define HAL_BATT2_VOLT_PIN 2
|
||||
define HAL_BATT2_CURR_PIN 3
|
||||
|
||||
# CAN bus
|
||||
PI9 CAN1_RX CAN1
|
||||
PH13 CAN1_TX CAN1
|
||||
|
||||
PB12 CAN2_RX CAN2
|
||||
PB13 CAN2_TX CAN2
|
||||
|
||||
PH2 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||
PH3 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71)
|
||||
PH4 GPIO_CAN3_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(72)
|
||||
|
||||
# GPIOs
|
||||
PA7 HEATER_EN OUTPUT LOW GPIO(80)
|
||||
define HAL_HEATER_GPIO_PIN 80
|
||||
|
||||
PG1 VDD_BRICK_nVALID INPUT PULLUP
|
||||
PG2 VDD_BRICK2_nVALID INPUT PULLUP
|
||||
PG3 VBUS_nVALID INPUT PULLUP
|
||||
PF13 VDD_5V_HIPOWER_nOC INPUT PULLUP
|
||||
PE15 VDD_5V_PERIPH_nOC INPUT PULLUP
|
||||
# PB10 nSPI5_RESET_EXTERNAL1 OUTPUT HIGH (using for WA4)
|
||||
|
||||
# capture pins
|
||||
PA5 FMU_CAP1 INPUT GPIO(58)
|
||||
PB3 FMU_CAP2 INPUT GPIO(59)
|
||||
PB11 FMU_CAP3 INPUT GPIO(60)
|
||||
PI0 FMU_SPARE_4 INPUT GPIO(61)
|
||||
|
||||
# SPI devices
|
||||
SPIDEV ms5611 SPI4 DEVID1 MS5611_CS MODE3 20*MHZ 20*MHZ
|
||||
SPIDEV scha63t_g SPI1 DEVID1 SCHA63T_G_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV scha63t_a SPI1 DEVID2 SCHA63T_A_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV icm20602 SPI1 DEVID3 ICM20602_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ
|
||||
|
||||
# up to 3 IMUs
|
||||
IMU SCHA63T SPI:scha63t_a SPI:scha63t_g ROTATION_NONE
|
||||
IMU Invensense SPI:icm20602 ROTATION_PITCH_180_YAW_270
|
||||
|
||||
# 3rd could be BMMI055 or BMI088
|
||||
# IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
|
||||
# IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_ROLL_180_YAW_90
|
||||
|
||||
define HAL_DEFAULT_INS_FAST_SAMPLE 1
|
||||
|
||||
# probe external I2C compasses plus some internal IST8310
|
||||
# we also probe some external IST8310 with a non-standard orientation
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90
|
||||
COMPASS IST8310 I2C:ALL_INTERNAL:0x0E false ROTATION_YAW_270
|
||||
|
||||
# one baro
|
||||
BARO MS56XX SPI:ms5611
|
||||
|
||||
# microSD support
|
||||
PC8 SDMMC_D0 SDMMC1
|
||||
PC9 SDMMC_D1 SDMMC1
|
||||
PC10 SDMMC_D2 SDMMC1
|
||||
PC11 SDMMC_D3 SDMMC1
|
||||
PC12 SDMMC_CK SDMMC1
|
||||
PD2 SDMMC_CMD SDMMC1
|
||||
|
||||
# red LED marked as B/E
|
||||
# PB1 LED_RED OUTPUT OPENDRAIN GPIO(90) (swap)
|
||||
|
||||
# green LED marked as PWR. We leave this solid on, but allow
|
||||
# for it to be controlled as a relay if needed
|
||||
PC6 LED_GREEN OUTPUT GPIO(91) LOW
|
||||
|
||||
# blue LED marked as ACT
|
||||
# PC7 LED_BLUE OUTPUT GPIO(92) HIGH (swap)
|
||||
|
||||
# setup for BoardLED2
|
||||
define HAL_GPIO_A_LED_PIN 90
|
||||
define HAL_GPIO_B_LED_PIN 92
|
||||
define HAL_GPIO_LED_ON 0
|
||||
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_STORAGE_SIZE 32768
|
||||
define HAL_WITH_RAMTRON 1
|
||||
|
||||
# allow to have have a dedicated safety switch pin
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
|
||||
define HAL_COMPASS_DEFAULT HAL_COMPASS_NONE
|
||||
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||
|
||||
DMA_PRIORITY SDMMC* UART8* ADC* SPI* TIM*
|
||||
|
||||
# define HAL_SPI_CHECK_CLOCK_FREQ 1
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# uncomment block below to enable a 2nd MS5611 baro on SPI5
|
||||
#PF7 SPI5_SCK SPI5
|
||||
#PF8 SPI5_MISO SPI5
|
||||
#PF9 SPI5_MOSI SPI5
|
||||
#SPIDEV ms5611_spi5 SPI5 DEVID1 EXTERNAL1_CS1 MODE3 20*MHZ 20*MHZ
|
||||
#undef PI10
|
||||
#PI10 EXTERNAL1_CS2 OUTPUT LOW
|
||||
#BARO MS56XX SPI:ms5611_spi5
|
||||
|
||||
# imu sensor SCHA63T reset
|
||||
PH12 SCHA63T_RESET OUTPUT LOW
|
||||
|
||||
# PWM wraparound 1-8
|
||||
PA8 WA1 INPUT PULLUP
|
||||
PA15 WA2 INPUT PULLUP
|
||||
PB2 WA3 INPUT PULLUP
|
||||
PB10 WA4 INPUT PULLUP
|
||||
PE7 WA5 INPUT PULLUP
|
||||
PF11 WA6 INPUT PULLUP
|
||||
PG8 WA7 INPUT PULLUP
|
||||
PG15 WA8 INPUT PULLUP
|
||||
|
||||
# now we define the pins that USB is connected on
|
||||
PA9 VBAS INPUT PULLDOWN
|
||||
|
||||
# External watchdog timer clear
|
||||
PH11 WDI_OUT OUTPUT SPEED_VERYLOW
|
||||
define WDI_OUT_INTERVAL_TIME_MS 100
|
||||
|
||||
# safety switch
|
||||
PE10 SAFETY_IN INPUT PULLUP
|
||||
|
||||
# red and blue LEDs swapped vs fmuv5
|
||||
# red LED marked as B/E
|
||||
PB1 LED_RED OUTPUT OPENDRAIN GPIO(92)
|
||||
# blue LED marked as ACT
|
||||
PC7 LED_BLUE OUTPUT GPIO(90) HIGH
|
Loading…
Reference in New Issue