mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: TBS LUCID H7
This commit is contained in:
parent
f0900bd119
commit
01fc0744dc
Binary file not shown.
After Width: | Height: | Size: 238 KiB |
|
@ -0,0 +1,133 @@
|
||||||
|
# TBS LUCID H7 Flight Controller
|
||||||
|
|
||||||
|
The TBS LUCID H7 is a flight controller produced by [TBS](https://www.team-blacksheep.com/).
|
||||||
|
|
||||||
|
## Features
|
||||||
|
|
||||||
|
- MCU - STM32H743 32-bit processor running at 480 MHz
|
||||||
|
- IMU - Dual ICM42688
|
||||||
|
- Barometer - DPS310
|
||||||
|
- OSD - AT7456E
|
||||||
|
- microSD card slot
|
||||||
|
- 7x UARTs
|
||||||
|
- CAN support
|
||||||
|
- 13x PWM Outputs (12 Motor Output, 1 LED)
|
||||||
|
- Battery input voltage: 2S-6S
|
||||||
|
- BEC 3.3V 0.5A
|
||||||
|
- BEC 5V 3A
|
||||||
|
- BEC 9V 3A for video, gpio controlled, pinned out on HD VTX connector
|
||||||
|
- Selectable 5V or VBAT pad, for analog VTX, gpio controlled on/off
|
||||||
|
- Dual switchable camera inputs
|
||||||
|
|
||||||
|
## Pinout
|
||||||
|
|
||||||
|
![TBS LUCID H7 Board Top](Top.png "TBS LUCID H7 Top")
|
||||||
|
![TBS LUCID H7 Board Bottom](Bottom.png "TBS LUCID H7 Bottom")
|
||||||
|
|
||||||
|
## UART Mapping
|
||||||
|
|
||||||
|
The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the
|
||||||
|
receive pin for UARTn. The Tn pin is the transmit pin for UARTn.
|
||||||
|
|
||||||
|
- SERIAL0 -> USB (MAVLink2)
|
||||||
|
- SERIAL1 -> UART1 (RX1 is SBUS in HD VTX connector)
|
||||||
|
- SERIAL2 -> UART2 (GPS, DMA-enabled)
|
||||||
|
- SERIAL3 -> UART3 (DisplayPort, DMA-enabled)
|
||||||
|
- SERIAL4 -> UART4 (MAVLink2, Telem1)
|
||||||
|
- SERIAL6 -> UART6 (RC Input, DMA-enabled)
|
||||||
|
- SERIAL7 -> UART7 (MAVLink2, Telem2, DMA and flow-control enabled)
|
||||||
|
- SERIAL8 -> UART8 (ESC Telemetry, RX8 on ESC connector for telem)
|
||||||
|
|
||||||
|
## RC Input
|
||||||
|
|
||||||
|
RC input is configured by default via the USART6 RX input. It supports all serial RC protocols except PPM.
|
||||||
|
|
||||||
|
Note: If the receiver is FPort the receiver must be tied to the USART6 TX pin , RSSI_TYPE set to 3,
|
||||||
|
and SERIAL6_OPTIONS must be set to 7 (invert TX/RX, half duplex). For full duplex like CRSF/ELRS use both
|
||||||
|
RX6 and TX6 and set RSSI_TYPE also to 3.
|
||||||
|
|
||||||
|
If SBUS is used on HD VTX connector (DJI TX), then SERIAL1_PROTOCOl should be set to "23" and SERIAL6_PROTOCOL changed to something else.
|
||||||
|
|
||||||
|
## FrSky Telemetry
|
||||||
|
|
||||||
|
FrSky Telemetry is supported using an unused UART, such as the T1 pin (UART1 transmit).
|
||||||
|
You need to set the following parameters to enable support for FrSky S.PORT:
|
||||||
|
|
||||||
|
- SERIAL1_PROTOCOL 10
|
||||||
|
- SERIAL1_OPTIONS 7
|
||||||
|
|
||||||
|
## OSD Support
|
||||||
|
|
||||||
|
The TBS LUCID H7 supports OSD using OSD_TYPE 1 (MAX7456 driver) and simultaneously DisplayPort using TX3/RX3 on the HD VTX connector.
|
||||||
|
|
||||||
|
## PWM Output
|
||||||
|
|
||||||
|
The TBS LUCID H7 supports up to 13 PWM or DShot outputs. The pads for motor output
|
||||||
|
M1 to M4 are provided on both the motor connectors and on separate pads, plus
|
||||||
|
M9-13 on a separate pads for LED strip and other PWM outputs.
|
||||||
|
|
||||||
|
The PWM is in 4 groups:
|
||||||
|
|
||||||
|
- PWM 1-2 in group1
|
||||||
|
- PWM 3-4 in group2
|
||||||
|
- PWM 5-6 in group3
|
||||||
|
- PWM 7-10 in group4
|
||||||
|
- PWM 11-12 in group5
|
||||||
|
- PWM 13 in group6
|
||||||
|
|
||||||
|
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. Channels 1-10 support bi-directional dshot.
|
||||||
|
|
||||||
|
## Battery Monitoring
|
||||||
|
|
||||||
|
The board has a built-in voltage sensor and external current sensor input. The current
|
||||||
|
sensor can read up to 130 Amps. The voltage sensor can handle up to 6S
|
||||||
|
LiPo batteries.
|
||||||
|
|
||||||
|
The correct battery setting parameters are:
|
||||||
|
|
||||||
|
- BATT_MONITOR 4
|
||||||
|
- BATT_VOLT_PIN 10
|
||||||
|
- BATT_CURR_PIN 11
|
||||||
|
- BATT_VOLT_MULT 11.0
|
||||||
|
- BATT_AMP_PERVLT 40
|
||||||
|
|
||||||
|
Pads for a second analog battery monitor are provided. To use:
|
||||||
|
|
||||||
|
- Set BATT2_MONIOTOR 4
|
||||||
|
- BATT2_VOLT_PIN 18
|
||||||
|
- BATT2_CURR_PIN 7
|
||||||
|
- BATT2_VOLT_MULT 11.0
|
||||||
|
- BATT2_AMP_PERVLT as required
|
||||||
|
|
||||||
|
## Analog RSSI and AIRSPEED inputs
|
||||||
|
|
||||||
|
Analog RSSI uses RSSI_PIN 8
|
||||||
|
Analog Airspeed sensor would use ARSPD_PIN 4
|
||||||
|
|
||||||
|
## Compass
|
||||||
|
|
||||||
|
The TBS LUCID H7 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads.
|
||||||
|
|
||||||
|
## VTX power control
|
||||||
|
|
||||||
|
GPIO 81 controls the VSW pins which can be set to output either VBAT or 5V via a board jumper. Setting this GPIO high removes voltage supply to pins. RELAY2 is configured by default to control this GPIO and is low by default.
|
||||||
|
|
||||||
|
GPIO 83 controls the VTX BEC output to pins marked "9V" and is included on the HD VTX connector. Setting this GPIO low removes voltage supply to this pin/pad.
|
||||||
|
|
||||||
|
By default RELAY4 is configured to control this pin and sets the GPIO high.
|
||||||
|
|
||||||
|
## Camera control
|
||||||
|
|
||||||
|
GPIO 82 controls the camera output to the connectors marked "CAM1" and "CAM2". Setting this GPIO low switches the video output from CAM1 to CAM2. By default RELAY3 is configured to control this pin and sets the GPIO high.
|
||||||
|
|
||||||
|
## Loading Firmware
|
||||||
|
|
||||||
|
Initial firmware load can be done with DFU by plugging in USB with the
|
||||||
|
bootloader button pressed. Then you should load the "with_bl.hex"
|
||||||
|
firmware, using your favourite DFU loading tool.
|
||||||
|
|
||||||
|
Once the initial firmware is loaded you can update the firmware using
|
||||||
|
any ArduPilot ground station software. Updates should be done with the
|
||||||
|
\*.apj firmware files.
|
Binary file not shown.
After Width: | Height: | Size: 240 KiB |
|
@ -0,0 +1,4 @@
|
||||||
|
# setup for LEDs on chan13
|
||||||
|
SERVO13_FUNCTION 120
|
||||||
|
# Default VTX power to on
|
||||||
|
RELAY4_DEFAULT 1
|
|
@ -0,0 +1,77 @@
|
||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
# for TBS FCAPv1 H743
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32H7xx STM32H743xx
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID AP_HW_TBS_LUCID_H7
|
||||||
|
|
||||||
|
# crystal frequency, setup to use external oscillator
|
||||||
|
OSCILLATOR_HZ 8000000
|
||||||
|
|
||||||
|
FLASH_SIZE_KB 2048
|
||||||
|
|
||||||
|
# bootloader starts at zero offset
|
||||||
|
FLASH_RESERVE_START_KB 0
|
||||||
|
|
||||||
|
# the location where the bootloader will put the firmware
|
||||||
|
# the H743 has 128k sectors
|
||||||
|
FLASH_BOOTLOADER_LOAD_KB 128
|
||||||
|
|
||||||
|
# order of UARTs (and USB). Allow bootloading on USB and telem1
|
||||||
|
SERIAL_ORDER OTG1 UART7
|
||||||
|
|
||||||
|
# UART7 (telem1)
|
||||||
|
PE7 UART7_RX UART7 NODMA
|
||||||
|
PE8 UART7_TX UART7 NODMA
|
||||||
|
|
||||||
|
# PA10 IO-debug-console
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
PE3 LED_BOOTLOADER OUTPUT LOW
|
||||||
|
define HAL_LED_ON 0
|
||||||
|
|
||||||
|
# Add CS pins to ensure they are high in bootloader
|
||||||
|
PC15 IMU1_CS CS
|
||||||
|
PB12 MAX7456_CS CS
|
||||||
|
PE11 IMU2_CS CS
|
||||||
|
PD4 EXT_CS1 CS
|
||||||
|
PE2 EXT_CS2 CS
|
||||||
|
|
||||||
|
# Ensure GPIOs are on during bootloader
|
||||||
|
# Vsw
|
||||||
|
PD10 VSW OUTPUT LOW
|
||||||
|
# CamSw
|
||||||
|
PD11 CAMSW OUTPUT LOW
|
||||||
|
# 9V_EN
|
||||||
|
PC13 VPWR OUTPUT LOW
|
||||||
|
|
||||||
|
# support flashing from SD card:
|
||||||
|
# enable DFU by default
|
||||||
|
ENABLE_DFU_BOOT 1
|
||||||
|
|
||||||
|
# FATFS support:
|
||||||
|
define CH_CFG_USE_MEMCORE 1
|
||||||
|
define CH_CFG_USE_HEAP 1
|
||||||
|
define CH_CFG_USE_SEMAPHORES 0
|
||||||
|
define CH_CFG_USE_MUTEXES 1
|
||||||
|
define CH_CFG_USE_DYNAMIC 1
|
||||||
|
define CH_CFG_USE_WAITEXIT 1
|
||||||
|
define CH_CFG_USE_REGISTRY 1
|
||||||
|
|
||||||
|
# microSD support
|
||||||
|
PC8 SDMMC1_D0 SDMMC1
|
||||||
|
PC9 SDMMC1_D1 SDMMC1
|
||||||
|
PC10 SDMMC1_D2 SDMMC1
|
||||||
|
PC11 SDMMC1_D3 SDMMC1
|
||||||
|
PC12 SDMMC1_CK SDMMC1
|
||||||
|
PD2 SDMMC1_CMD SDMMC1
|
||||||
|
|
||||||
|
define FATFS_HAL_DEVICE SDCD1
|
||||||
|
define HAL_OS_FATFS_IO 1
|
||||||
|
define AP_BOOTLOADER_FLASH_FROM_SD_ENABLED 1
|
|
@ -0,0 +1,219 @@
|
||||||
|
# hw definition file for processing by chibios_pins.py
|
||||||
|
# for TBS FCAPv1 H743
|
||||||
|
|
||||||
|
# MCU class and specific type
|
||||||
|
MCU STM32H7xx STM32H743xx
|
||||||
|
|
||||||
|
# board ID for firmware load
|
||||||
|
APJ_BOARD_ID AP_HW_TBS_LUCID_H7
|
||||||
|
|
||||||
|
# crystal frequency, setup to use external oscillator
|
||||||
|
OSCILLATOR_HZ 8000000
|
||||||
|
|
||||||
|
FLASH_SIZE_KB 2048
|
||||||
|
env OPTIMIZE -Os
|
||||||
|
MCU_CLOCKRATE_MHZ 480
|
||||||
|
|
||||||
|
# bootloader takes first sector
|
||||||
|
FLASH_RESERVE_START_KB 128
|
||||||
|
|
||||||
|
# ChibiOS system timer
|
||||||
|
STM32_ST_USE_TIMER 12
|
||||||
|
define CH_CFG_ST_RESOLUTION 16
|
||||||
|
|
||||||
|
# USB
|
||||||
|
PA11 OTG_FS_DM OTG1
|
||||||
|
PA12 OTG_FS_DP OTG1
|
||||||
|
|
||||||
|
PA13 JTMS-SWDIO SWD
|
||||||
|
PA14 JTCK-SWCLK SWD
|
||||||
|
|
||||||
|
# SPI1 for IMU1 (ICM42688)
|
||||||
|
PA5 SPI1_SCK SPI1
|
||||||
|
PA6 SPI1_MISO SPI1
|
||||||
|
PD7 SPI1_MOSI SPI1
|
||||||
|
PC15 IMU1_CS CS
|
||||||
|
|
||||||
|
# SPI2 for MAX7456 OSD
|
||||||
|
PB12 MAX7456_CS CS
|
||||||
|
PB13 SPI2_SCK SPI2
|
||||||
|
PB14 SPI2_MISO SPI2
|
||||||
|
PB15 SPI2_MOSI SPI2
|
||||||
|
|
||||||
|
# SPI3 - external
|
||||||
|
PB3 SPI3_SCK SPI3
|
||||||
|
PB4 SPI3_MISO SPI3
|
||||||
|
PB5 SPI3_MOSI SPI3
|
||||||
|
|
||||||
|
# external CS pins
|
||||||
|
PD4 EXT_CS1 CS
|
||||||
|
PE2 EXT_CS2 CS
|
||||||
|
|
||||||
|
# SPI4 for IMU2 (ICM42688)
|
||||||
|
PE11 IMU2_CS CS
|
||||||
|
PE12 SPI4_SCK SPI4
|
||||||
|
PE13 SPI4_MISO SPI4
|
||||||
|
PE14 SPI4_MOSI SPI4
|
||||||
|
|
||||||
|
# two I2C bus
|
||||||
|
I2C_ORDER I2C2 I2C1
|
||||||
|
|
||||||
|
# I2C1
|
||||||
|
PB6 I2C1_SCL I2C1
|
||||||
|
PB7 I2C1_SDA I2C1
|
||||||
|
|
||||||
|
# I2C2 - Internal Baro
|
||||||
|
PB10 I2C2_SCL I2C2
|
||||||
|
PB11 I2C2_SDA I2C2
|
||||||
|
|
||||||
|
# ADC
|
||||||
|
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
|
||||||
|
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
|
||||||
|
PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
|
||||||
|
PA7 BATT2_CURRENT_SENS ADC1 SCALE(1)
|
||||||
|
|
||||||
|
define HAL_BATT_MONITOR_DEFAULT 4
|
||||||
|
define HAL_BATT_VOLT_PIN 10
|
||||||
|
define HAL_BATT_CURR_PIN 11
|
||||||
|
define HAL_BATT2_VOLT_PIN 18
|
||||||
|
define HAL_BATT2_CURR_PIN 7
|
||||||
|
define HAL_BATT_VOLT_SCALE 11.0
|
||||||
|
define HAL_BATT_CURR_SCALE 40.0
|
||||||
|
define HAL_BATT2_VOLT_SCALE 11.0
|
||||||
|
|
||||||
|
PC4 PRESSURE_SENS ADC1 SCALE(2)
|
||||||
|
define HAL_DEFAULT_AIRSPEED_PIN 4
|
||||||
|
|
||||||
|
PC5 RSSI_ADC ADC1
|
||||||
|
define BOARD_RSSI_ANA_PIN 8
|
||||||
|
|
||||||
|
# LED
|
||||||
|
# green LED1 marked as B/E
|
||||||
|
# blue LED0 marked as ACT
|
||||||
|
define AP_NOTIFY_GPIO_LED_2_ENABLED 1
|
||||||
|
PE3 LED0 OUTPUT LOW GPIO(90) # blue
|
||||||
|
PE4 LED1 OUTPUT LOW GPIO(91) # green
|
||||||
|
define HAL_GPIO_A_LED_PIN 91
|
||||||
|
define HAL_GPIO_B_LED_PIN 90
|
||||||
|
|
||||||
|
# order of UARTs (and USB)
|
||||||
|
SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 EMPTY USART6 UART7 UART8 OTG2
|
||||||
|
|
||||||
|
# USART1 (DJI SBUS in connector)
|
||||||
|
PA10 USART1_RX USART1 NODMA
|
||||||
|
PA9 USART1_TX USART1 NODMA
|
||||||
|
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_None
|
||||||
|
|
||||||
|
# USART2 (GPS1)
|
||||||
|
PD5 USART2_TX USART2
|
||||||
|
PD6 USART2_RX USART2
|
||||||
|
define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_GPS
|
||||||
|
|
||||||
|
# USART3 (DJI O3 in connector)
|
||||||
|
PD9 USART3_RX USART3
|
||||||
|
PD8 USART3_TX USART3
|
||||||
|
define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_MSP_DisplayPort
|
||||||
|
|
||||||
|
# UART4 (Telem1)
|
||||||
|
PB9 UART4_TX UART4 NODMA
|
||||||
|
PB8 UART4_RX UART4 NODMA
|
||||||
|
define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_MAVLink2
|
||||||
|
|
||||||
|
# USART6 (RCIN)
|
||||||
|
PC6 USART6_TX USART6
|
||||||
|
PC7 USART6_RX USART6
|
||||||
|
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_RCIN
|
||||||
|
|
||||||
|
# UART7 (Telem2)
|
||||||
|
PE7 UART7_RX UART7
|
||||||
|
PE8 UART7_TX UART7
|
||||||
|
PE10 UART7_CTS UART7
|
||||||
|
PE9 UART7_RTS UART7
|
||||||
|
define DEFAULT_SERIAL7_PROTOCOL SerialProtocol_MAVLink2
|
||||||
|
|
||||||
|
# UART8 (ESC Telemetry)
|
||||||
|
PE0 UART8_RX UART8 NODMA
|
||||||
|
PE1 UART8_TX UART8 NODMA
|
||||||
|
define DEFAULT_SERIAL8_PROTOCOL SerialProtocol_ESCTelemetry
|
||||||
|
|
||||||
|
# CAN bus
|
||||||
|
PD0 CAN1_RX CAN1
|
||||||
|
PD1 CAN1_TX CAN1
|
||||||
|
PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
|
||||||
|
|
||||||
|
# Motors
|
||||||
|
PB0 TIM3_CH3 TIM3 PWM(1) GPIO(50) BIDIR
|
||||||
|
PB1 TIM3_CH4 TIM3 PWM(2) GPIO(51)
|
||||||
|
PA0 TIM2_CH1 TIM2 PWM(3) GPIO(52) BIDIR
|
||||||
|
PA1 TIM2_CH2 TIM2 PWM(4) GPIO(53)
|
||||||
|
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54) BIDIR
|
||||||
|
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
|
||||||
|
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56) BIDIR
|
||||||
|
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57)
|
||||||
|
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) BIDIR
|
||||||
|
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59)
|
||||||
|
# Disable DMA on PWM11-12 so that the LEDs get a channel
|
||||||
|
PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA
|
||||||
|
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA
|
||||||
|
# Motors
|
||||||
|
PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED
|
||||||
|
|
||||||
|
# Beeper
|
||||||
|
PA15 BUZZER OUTPUT GPIO(32) LOW
|
||||||
|
define HAL_BUZZER_PIN 32
|
||||||
|
define AP_NOTIFY_TONEALARM_ENABLED 1
|
||||||
|
|
||||||
|
# microSD support
|
||||||
|
PC8 SDMMC1_D0 SDMMC1
|
||||||
|
PC9 SDMMC1_D1 SDMMC1
|
||||||
|
PC10 SDMMC1_D2 SDMMC1
|
||||||
|
PC11 SDMMC1_D3 SDMMC1
|
||||||
|
PC12 SDMMC1_CK SDMMC1
|
||||||
|
PD2 SDMMC1_CMD SDMMC1
|
||||||
|
|
||||||
|
# GPIOs
|
||||||
|
# Vsw
|
||||||
|
PD10 VSW OUTPUT GPIO(81) LOW
|
||||||
|
# CamSw
|
||||||
|
PD11 CAMSW OUTPUT GPIO(82) LOW
|
||||||
|
# 9V_EN
|
||||||
|
PC13 VPWR OUTPUT GPIO(83) LOW
|
||||||
|
|
||||||
|
define RELAY2_PIN_DEFAULT 81
|
||||||
|
define RELAY3_PIN_DEFAULT 82
|
||||||
|
define RELAY4_PIN_DEFAULT 83
|
||||||
|
|
||||||
|
DMA_PRIORITY SPI1* SPI4*
|
||||||
|
DMA_NOSHARE SPI1* SPI4* TIM3* TIM2* TIM5* TIM4*
|
||||||
|
|
||||||
|
define HAL_STORAGE_SIZE 32768
|
||||||
|
|
||||||
|
# use last 2 pages for flash storage
|
||||||
|
# H743 has 16 pages of 128k each
|
||||||
|
STORAGE_FLASH_PAGE 14
|
||||||
|
|
||||||
|
# spi devices
|
||||||
|
SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8
|
||||||
|
SPIDEV imu2 SPI4 DEVID1 IMU2_CS MODE3 2*MHZ 16*MHZ # Clock is 100Mhz so highest clock <= 24Mhz is 100Mhz/8
|
||||||
|
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
|
||||||
|
|
||||||
|
# no built-in compass, but probe the i2c bus for all possible
|
||||||
|
# external compass types
|
||||||
|
define ALLOW_ARM_NO_COMPASS
|
||||||
|
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||||
|
define HAL_I2C_INTERNAL_MASK 2
|
||||||
|
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
|
||||||
|
|
||||||
|
IMU Invensensev3 SPI:imu1 ROTATION_YAW_270
|
||||||
|
IMU Invensensev3 SPI:imu2 ROTATION_YAW_180
|
||||||
|
define HAL_DEFAULT_INS_FAST_SAMPLE 3
|
||||||
|
|
||||||
|
# DPS310 integrated on I2C2 bus
|
||||||
|
BARO DPS310 I2C:0:0x76
|
||||||
|
|
||||||
|
define HAL_OS_FATFS_IO 1
|
||||||
|
|
||||||
|
# setup for OSD
|
||||||
|
define OSD_ENABLED 1
|
||||||
|
define HAL_OSD_TYPE_DEFAULT 1
|
||||||
|
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
|
Loading…
Reference in New Issue