mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
hwdef: added QiotekAdeptF407
This commit is contained in:
parent
74102c6380
commit
2850740bd8
226
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/README.md
Normal file
226
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/README.md
Normal file
@ -0,0 +1,226 @@
|
||||
# QioTek AdeptF407 Flight Controller
|
||||
|
||||
The Qiotek AdeptF407 an autopilot produced by [QioTek](https://www.qiotek.io).
|
||||
|
||||
It is an autopilot used CKS MCU.
|
||||
|
||||
## Features
|
||||
- MCU: CKS32F407VGT6
|
||||
- Accelerometer/Gyro: ICM4 series/ICM2 series or ICM4 series/ICM4 series
|
||||
- BEC output: 5V 3A for autopilot and peripheral hardware
|
||||
- BEC output: 9V/12V 3A for camera and analog video transmission
|
||||
- Barometer: DPS310
|
||||
- OSD: AT7456E
|
||||
- builtin IST8310 magnetometer(internal I2C)
|
||||
- builtin RAMTRON(SPI)
|
||||
- 12 dedicated PWM/Capture inputs on FMU
|
||||
- 5 UARTS: (USART1, USART2, USART3, UART4, USART7)
|
||||
- 2 I2C ports
|
||||
- 1 CAN port
|
||||
- 2 Analog inputs of voltage / current for battery monitoring
|
||||
- 2 analog video input channels
|
||||
- 1 analog video output source switcher switching by relay5
|
||||
- 4 relays output control
|
||||
- 1 Status LED
|
||||
- 1 nARMED
|
||||
|
||||
## Pinout
|
||||
![QioTek AdpetF407 Board](../QioTekAdeptF407/adept_f407.jpg "QioTek AdpetF407")
|
||||
|
||||
## Connectors
|
||||
|
||||
**External USB**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | D+ | D_P |
|
||||
| 3 | D- | D_N |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**Telme1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX | +3.3V |
|
||||
| 3 | RX | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**Telme2**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX | +3.3V |
|
||||
| 3 | RX | +3.3V |
|
||||
| 4 | NC | - - |
|
||||
| 5 | NC | - - |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**GPS1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX | +3.3V |
|
||||
| 3 | RX | +3.3V |
|
||||
| 4 | scl2 | +3.3V |
|
||||
| 5 | sda2 | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**GPS1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX | +3.3V |
|
||||
| 3 | RX | +3.3V |
|
||||
| 4 | scl2 | +3.3V |
|
||||
| 5 | sda2 | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**UART4 and UART5**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | TX | +3.3V |
|
||||
| 3 | RX | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**CAN1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | CAN1_H | CAN_P |
|
||||
| 3 | CAN1_L | CAN_N |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**IIC1**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC | +5V |
|
||||
| 2 | SDA1 | +3.3V |
|
||||
| 3 | SCL1 | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**Safety and buzzer**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | VCC/3.3| +3.3V |
|
||||
| 2 | VCC5 | +5V |
|
||||
| 3 | Safety | +3.3V |
|
||||
| 4 | LED | +3.3V |
|
||||
| 5 | Buzzer | +3.3V |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**VT Port**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | AV_OUT | +5V |
|
||||
| 2 | S.AU ctrl. | +3.3V |
|
||||
| 3 | 9V/12V | 9V/12V|
|
||||
| 4 | GND | GND |
|
||||
|
||||
**PWM11 and PWM12**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :----: | :---: |
|
||||
| 1 | PWM11 | +3.3V |
|
||||
| 2 | GND | GND |
|
||||
| 3 | PWM12 | +3.3V |
|
||||
| 4 | GND | GND |
|
||||
|
||||
**POWER1 and Power2**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-------------: | :---: |
|
||||
| 1 | VCC_IN | +5V |
|
||||
| 2 | VCC_IN | +5V |
|
||||
| 3 | BAT_CRRENT_ADC | +6.6V |
|
||||
| 4 | BAT_VOLTAGE_ADC | +6.3V |
|
||||
| 5 | GND | GND |
|
||||
| 6 | GND | GND |
|
||||
|
||||
**Battery Input**
|
||||
|
||||
| Pin | Signal | Volt |
|
||||
| :--: | :-------------: | :---: |
|
||||
| 1 | Battery_VCC | MAX 30V |
|
||||
| 2 | Battery_GND | GND |
|
||||
|
||||
## 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.
|
||||
|Name|Pin|Function|
|
||||
|:-|:-|:-|
|
||||
|SERIAL0|OTG1|USB|
|
||||
|SERIAL1|TX6/RX6|UART1 (Telem1)|
|
||||
|SERIAL2|TX3/RX3|UART2 (Telem2 buadrate 921600)|
|
||||
|SERIAL3|TX1/RX1|UART3 (GNSS)|
|
||||
|SERIAL4|TX4/RX4|UART4 (Reserve for GNSS2)|
|
||||
|SERIAL5|TX2/RX2|UART5 (Debug)|
|
||||
|
||||
## RC Input
|
||||
RC input is configured on the RCIN pin by PA15 TIM2_CH1 TIM2 , at one end of the servo rail, marked RC in the above diagram. This pin supports PPM and S.Bus. protocols.
|
||||
|
||||
## OSD Support
|
||||
|
||||
QioTek AdpetF407 supports OSD using OSD_TYPE 1 (MAX7456 driver).
|
||||
|
||||
## PWM Output
|
||||
|
||||
The QioTek AdpetF407 AIO supports up to 12 PWM outputs. All 14 PWM outputs have GND on the top row, 5V on the middle row and signal on the bottom row.
|
||||
|
||||
The 12 PWM outputs are in 3 groups:
|
||||
|
||||
PWM 1 and 4 in group1
|
||||
PWM 4 and 8 in group2
|
||||
PWM 9 and 12 in group3
|
||||
|
||||
Channels within the same group need to use the same output rate. If any channel in a group uses DShot or then all channels in the group need to use DShot.
|
||||
|
||||
## CAN Port
|
||||
|
||||
The CAN port is disabled by default. Enable the CAN port setting the parameters CAN_P1_Driver to 1 (DroneCAN protocol).
|
||||
|
||||
## Battery Monitoring
|
||||
|
||||
The board has two dedicated power monitor ports on 6 pin connectors. The correct battery setting parameters are dependent on the type of power brick which is connected.
|
||||
|
||||
The correct battery setting parameters are:
|
||||
|
||||
BATT_VOLT_PIN 2
|
||||
BATT_CURR_PIN 3
|
||||
BATT_VOLT_MULT 20.000
|
||||
BATT_AMP_PERVLT 60.000
|
||||
BATT2_VOLT_PIN 14
|
||||
BATT2_CURR_PIN 15
|
||||
BATT2_VOLT_MULT 20.000
|
||||
BATT2_AMP_PERVLT 60.000
|
||||
|
||||
In addition, the builtin voltage divider circuit can be used by Solder pad to switching to share the battery voltage monitoring by power2 support to 6S.
|
||||
|
||||
If you want to use the built-in voltage monitor on power 1, you can manually invert the BATT_ VOLT_ PIN to 14, BATT_ CURR_ PIN to 15, BATT2_ VOLT_ PIN to 2, BATT2_ CURR_ PIN to 3.
|
||||
|
||||
**Built-in BEC**
|
||||
The built-in BEC 5V output has a starting voltage of 2S, and 9V/12V has a starting voltage of 3S/4S respectively.
|
||||
|
||||
## Compass
|
||||
|
||||
The QioTek AdpetF407 has a builtin QMC5883 compass. Due to potential interference the board is usually used with an external I2C compass as part of a GPS/Compass combination.
|
||||
|
||||
## 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.
|
||||
|
||||
The AdeptF407 auto pilot pre-installed with an ArduPilot compatible bootloader.
|
||||
Updates should be done with the *.apj firmware files.
|
23
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm
Normal file
23
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/defaults.parm
Normal file
@ -0,0 +1,23 @@
|
||||
# setup serial2 port defaults for ESP8266
|
||||
SERIAL2_BAUD 921
|
||||
|
||||
# setup the parameter for the ADC power module
|
||||
BATT_VOLT_PIN 2
|
||||
BATT_CURR_PIN 3
|
||||
BATT_VOLT_MULT 20.000
|
||||
BATT_AMP_PERVLT 60.000
|
||||
BATT2_VOLT_PIN 14
|
||||
BATT2_CURR_PIN 15
|
||||
BATT2_VOLT_MULT 20.000
|
||||
BATT2_AMP_PERVLT 60.000
|
||||
|
||||
# setup the parameter for the two Relays GPIO others for reserve
|
||||
RELAY_PIN 1
|
||||
RELAY_PIN2 2
|
||||
RELAY_PIN3 3
|
||||
RELAY_PIN4 4
|
||||
RELAY_PIN5 5
|
||||
RELAY_PIN6 6
|
||||
|
||||
# Disable the safety switch by default
|
||||
BRD_SAFETY_DEFLT 0
|
47
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef-bl.dat
Normal file
47
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef-bl.dat
Normal file
@ -0,0 +1,47 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for for QioTekAdeptF407 hardware bootloader from Qio-tek.com
|
||||
|
||||
MCU CKS32F4xx CKS32F407xx
|
||||
|
||||
APJ_BOARD_ID 1065
|
||||
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
# flash size
|
||||
FLASH_SIZE_KB 1024
|
||||
FLASH_RESERVE_START_KB 0
|
||||
|
||||
# the location where the bootloader will put the firmware
|
||||
FLASH_BOOTLOADER_LOAD_KB 16
|
||||
|
||||
# order of UARTs (and USB)
|
||||
SERIAL_ORDER OTG1 USART6
|
||||
|
||||
PE15 LED_BOOTLOADER OUTPUT
|
||||
PE12 LED_ACTIVITY OUTPUT
|
||||
define HAL_LED_ON 1
|
||||
|
||||
PA9 VBUS INPUT
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
|
||||
#define BOOTLOADER_DEBUG SD6
|
||||
|
||||
# Add CS pins to ensure they are high in bootloader
|
||||
PD3 IMU1_CS CS
|
||||
PD4 IMU2_CS CS
|
||||
PD7 IMU3_CS CS
|
||||
PB3 Baro1_CS CS
|
||||
PE4 Baro2_CS CS
|
||||
PE6 AT7453_CS CS
|
||||
PC13 FRAM_CS CS SPEED_VERYLOW
|
201
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat
Normal file
201
libraries/AP_HAL_ChibiOS/hwdef/QioTekAdeptF407/hwdef.dat
Normal file
@ -0,0 +1,201 @@
|
||||
# hw definition file for processing by chibios_hwdef.py
|
||||
# for QioTekZealotF407 hardware from Qio-tek.com
|
||||
|
||||
# MCU class and specific type
|
||||
MCU CKS32F4xx CKS32F407xx
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1065
|
||||
|
||||
FLASH_SIZE_KB 1024
|
||||
|
||||
# reserve 16k for bootloader
|
||||
FLASH_RESERVE_START_KB 16
|
||||
|
||||
# USB setup
|
||||
USB_STRING_MANUFACTURER "Qiotek"
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 8000000
|
||||
|
||||
# ChibiOS system timer
|
||||
STM32_ST_USE_TIMER 5
|
||||
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
# this is the pin that senses USB being connected. It is an input pin
|
||||
# setup as OPENDRAIN
|
||||
PA9 VBUS INPUT OPENDRAIN
|
||||
|
||||
# The normal usage of this ordering is:
|
||||
# 1) SERIAL0: console (primary mavlink, usually USB)
|
||||
# 2) SERIAL1: telem1
|
||||
# 3) SERIAL2: telem2 (recommend ESP8266)
|
||||
# 4) SERIAL3: primary GPS
|
||||
# 5) SERIAL4: telem3 or GPS2
|
||||
# 6) SERIAL5: extra UART or sbus output (usually RTOS debug console)
|
||||
|
||||
SERIAL_ORDER OTG1 USART6 USART3 USART1 UART4 USART2
|
||||
|
||||
# UART3
|
||||
PD8 USART3_TX USART3
|
||||
PD9 USART3_RX USART3
|
||||
|
||||
# USART2 for Mavlink2 wifi module set baudrate to 921600
|
||||
PD5 USART2_TX USART2 NODMA
|
||||
PD6 USART2_RX USART2
|
||||
|
||||
# USART1 for gps1
|
||||
PB6 USART1_TX USART1
|
||||
PB7 USART1_RX USART1
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4 NODMA
|
||||
PA1 UART4_RX UART4 NODMA
|
||||
|
||||
# USART6
|
||||
PC6 USART6_TX USART6 NODMA
|
||||
PC7 USART6_RX USART6 NODMA
|
||||
|
||||
# CAN bus
|
||||
PD0 CAN1_RX CAN1
|
||||
PD1 CAN1_TX CAN1
|
||||
|
||||
# SPI1 for IMU Baro OSD
|
||||
PA5 SPI1_SCK SPI1
|
||||
PB4 SPI1_MISO SPI1
|
||||
PB5 SPI1_MOSI SPI1
|
||||
PD3 IMU1_CS CS
|
||||
PD4 IMU2_CS CS
|
||||
PD7 IMU3_CS CS
|
||||
PB3 Baro1_CS CS
|
||||
PE4 Baro2_CS CS
|
||||
PE6 AT7456_CS CS
|
||||
|
||||
# SPI bus for dataflash
|
||||
PB13 SPI2_SCK SPI2
|
||||
PC2 SPI2_MISO SPI2
|
||||
PC3 SPI2_MOSI SPI2
|
||||
PC13 FRAM_CS CS SPEED_VERYLOW
|
||||
|
||||
# SPI devices
|
||||
SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV imu2 SPI1 DEVID2 IMU2_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV imu3 SPI1 DEVID3 IMU3_CS MODE3 2*MHZ 8*MHZ
|
||||
SPIDEV baro1 SPI1 DEVID2 Baro1_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV baro2 SPI1 DEVID1 Baro2_CS MODE3 5*MHZ 5*MHZ
|
||||
SPIDEV osd SPI1 DEVID2 AT7456_CS MODE0 10*MHZ 10*MHZ
|
||||
SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE0 8*MHZ 8*MHZ
|
||||
|
||||
# four IMUs, adi16740 is used, then imu3 will be removed
|
||||
IMU Invensensev3 SPI:imu1 ROTATION_NONE
|
||||
IMU Invensensev3 SPI:imu2 ROTATION_NONE
|
||||
IMU Invensense SPI:imu2 ROTATION_PITCH_180
|
||||
|
||||
# two Baro sensors
|
||||
BARO DPS280 SPI:baro1
|
||||
#BARO DPS280 SPI:baro2
|
||||
|
||||
# define the pins for the microSD card.
|
||||
PC8 SDIO_D0 SDIO
|
||||
PC9 SDIO_D1 SDIO
|
||||
PC10 SDIO_D2 SDIO
|
||||
PC11 SDIO_D3 SDIO
|
||||
PC12 SDIO_CK SDIO
|
||||
PD2 SDIO_CMD SDIO
|
||||
|
||||
# enable FAT filesystem support
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
# now some defines for logging and terrain data files
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
# define the order that I2C buses
|
||||
I2C_ORDER I2C1 I2C2
|
||||
PB8 I2C1_SCL I2C1
|
||||
PB9 I2C1_SDA I2C1
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
# look for I2C compass
|
||||
COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180
|
||||
COMPASS QMC5883L I2C:0:0x0D false ROTATION_ROLL_180
|
||||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
|
||||
define HAL_I2C_INTERNAL_MASK 1
|
||||
|
||||
# PWM out pins
|
||||
PA6 TIM3_CH1 TIM3 PWM(1) GPIO(50)
|
||||
PA7 TIM3_CH2 TIM3 PWM(2) GPIO(51)
|
||||
PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52)
|
||||
PB1 TIM3_CH4 TIM3 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)
|
||||
|
||||
PD12 TIM4_CH1 TIM4 PWM(9) GPIO(58)
|
||||
PD13 TIM4_CH2 TIM4 PWM(10) GPIO(59)
|
||||
PD14 TIM4_CH3 TIM4 PWM(11) GPIO(60)
|
||||
PD15 TIM4_CH4 TIM4 PWM(12) GPIO(61)
|
||||
|
||||
PE7 EXTERN_GPIO1 OUTPUT GPIO(1)
|
||||
PE8 EXTERN_GPIO2 OUTPUT GPIO(2)
|
||||
PE2 EXTERN_GPIO3 OUTPUT GPIO(3)
|
||||
PE3 EXTERN_GPIO4 OUTPUT GPIO(4)
|
||||
PE1 EXTERN_GPIO5 OUTPUT GPIO(5)
|
||||
PE0 EXTERN_GPIO6 OUTPUT GPIO(6)
|
||||
|
||||
# also USART6_RX for serial RC
|
||||
PA15 TIM2_CH1 TIM2 RCININT PULLDOWN LOW
|
||||
|
||||
# LED setup is similar to PixRacer
|
||||
define HAL_HAVE_PIXRACER_LED
|
||||
PE10 LED_RED OUTPUT GPIO(10)
|
||||
PE12 LED_GREEN OUTPUT GPIO(11)
|
||||
PE15 LED_BLUE OUTPUT GPIO(12)
|
||||
|
||||
define HAL_GPIO_A_LED_PIN 10
|
||||
define HAL_GPIO_B_LED_PIN 11
|
||||
define HAL_GPIO_C_LED_PIN 12
|
||||
|
||||
define HAL_GPIO_LED_ON 0
|
||||
define HAL_GPIO_LED_OFF 1
|
||||
|
||||
# analog in 6.6V
|
||||
PC1 ADC_1 ADC1 SCALE(2)
|
||||
|
||||
# define the primary battery connectors.
|
||||
PA3 BATT_CURRENT_SENS ADC1 SCALE(2)
|
||||
PA2 BATT_VOLTAGE_SENS ADC1 SCALE(2)
|
||||
PC5 BATT2_CURRENT_SENS ADC1 SCALE(2)
|
||||
PC4 BATT2_VOLTAGE_SENS ADC1 SCALE(2)
|
||||
PA4 VDD_5V_SENS ADC1 SCALE(2)
|
||||
PC0 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(12)
|
||||
|
||||
#PB2 HEATER_EN OUTPUT LOW GPIO(5)
|
||||
#define HAL_HEATER_GPIO_PIN 5
|
||||
#define HAL_IMU_TEMP_DEFAULT 45
|
||||
|
||||
define HAL_HAVE_SAFETY_SWITCH 1
|
||||
PB15 LED_SAFETY OUTPUT
|
||||
PB12 SAFETY_IN INPUT PULLDOWN
|
||||
PB14 TIM12_CH1 TIM12 ALARM
|
||||
|
||||
# enable RAMTROM parameter storage
|
||||
define HAL_WITH_RAMTRON 1
|
||||
define HAL_STORAGE_SIZE 16384
|
||||
|
||||
# --------------------- save flash ----------------------
|
||||
include ../include/minimize_features.inc
|
||||
include ../include/minimal.inc
|
||||
|
||||
# setup for OSD
|
||||
undef OSD_ENABLED
|
||||
define OSD_ENABLED 1
|
||||
define HAL_OSD_TYPE_DEFAULT 1
|
||||
ROMFS_WILDCARD libraries/AP_OSD/fonts/font1.bin
|
Loading…
Reference in New Issue
Block a user