hwdef: add Lumenier LUX F765 - NDAA

This commit is contained in:
D.J. Morvay 2025-02-25 14:42:21 -05:00 committed by Andrew Tridgell
parent 17299a7bb4
commit 940613901f
6 changed files with 635 additions and 0 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 238 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 83 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 296 KiB

View File

@ -0,0 +1,403 @@
# Lumenier LUX F765 Flight Controller - NDAA
The Lumenier LUX F765 NDAA flight controller is sold by
[GetFPV](https://www.getfpv.com/lumenier-lux-f765-flight-controller-ndaa.html).
![LUX F765 NDAA Slim](LUXF765_NDAA_Slim_Graphic.png "LUX F765 NDAA Slim")
## Features
- Processor: MCU STM32F765, 216MHz, 512KB RAM, 2MB Flash
- ICM42688 IMU
- BMP280 Barometer
- microSD Card Slot
- 12 PWM Outputs
- I2C Ports for External Sensors
- CANbus Support
- 8 UART Ports
- Buzzer Control
- LED Strip Control
- Analog Current Sensor Input
- Analog Battery Sensor Input
- USB Type-C (2.0)
- Blackbox Storage - SD Card and Flash (128Mbit/16Mbyte)
- Camera Control Output
- AT7456E OSD
- 10V Regulator for VTX Power
- 5V Regulator for Accessories
- Supported Firmware - Betaflight, Ardupilot, and PX4
- NDAA compliant
- Power Supply: 3S to 6S Battery Voltage
## Pinout
![LUX F765 NDAA Top](LUXF765_NDAA_TOP.png "LUX F765 NDAA Top")
![LUX F765 NDAA Bottom](LUXF765_NDAA_BOTTOM.png "LUX F765 NDAA Bottom")
## UART Mapping
- SERIAL0 -> USB
- SERIAL1 -> USART1 (RCinput, DMA enabled)
- SERIAL2 -> UART5 (Telem2, DMA enabled)
- SERIAL3 -> USART3 (GPS1, TX DMA enabled)
- SERIAL4 -> UART8 (GPS2)
- SERIAL5 -> USART2 (ESC Telemetry)
- SERIAL6 -> UART4 (DisplayPort)
- SERIAL7 -> UART7 (Spare)
- SERIAL8 -> USART6 (Spare)
## SPI Mapping
<table border="1" class="docutils">
<tbody>
<tr>
<th>SPI</th>
<th>Device</th>
</tr>
<tr>
<td>1</td>
<td>ICM42688</td>
</tr>
<tr>
<td>2</td>
<td>W25Q128JV Flash</td>
</tr>
<tr>
<td>3</td>
<td>AT7456E</td>
</tr>
<tr>
<td>4</td>
<td>SD Card</td>
</tr>
</tbody>
</table>
## Connectors
All connectors are JST SH 1.0mm pitch EXCEPT for the CANbus port, which is JST GH 1.25mm pitch.
### ESC #1 Port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin </th>
<th>Signal </th>
<th>Volt </th>
</tr>
<tr>
<td>1</td>
<td>VCC</td>
<td>VBAT</td>
</tr>
<tr>
<td>2 </td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>3</td>
<td>CURRENT</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>TELEMETRY</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>MOTOR 1 (TIM2_CH1)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6</td>
<td>MOTOR 2 (TIM2_CH2)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>7</td>
<td>MOTOR 3 (TIM2_CH3)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>8</td>
<td>MOTOR 4 (TIM2_CH4)</td>
<td>+3.3V</td>
</tr>
</tbody>
</table>
### ESC #2 Port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin </th>
<th>Signal </th>
<th>Volt </th>
</tr>
<tr>
<td>1</td>
<td>NOT CONNECTED</td>
<td>NOT CONNECTED</td>
</tr>
<tr>
<td>2 </td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>3</td>
<td>NOT CONNECTED</td>
<td>NOT CONNECTED</td>
</tr>
<tr>
<td>4</td>
<td>TELEMETRY</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>MOTOR 5 (TIM4_CH1)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6</td>
<td>MOTOR 6 (TIM4_CH2)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>7</td>
<td>MOTOR 7 (TIM4_CH3)</td>
<td>+3.3V</td>
</tr>
<tr>
<td>8</td>
<td>MOTOR 8 (TIM4_CH4)</td>
<td>+3.3V</td>
</tr>
</tbody>
</table>
### GPS port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>+5V</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>TX3</td>
<td>+3.3V</td>
</tr>
<tr>
<td>3</td>
<td>RX3</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>I2C3 SCL</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>I2C3 SDA</td>
<td>+3.3V</td>
</tr>
<tr>
<td>6</td>
<td>GND</td>
<td>GND</td>
</tr>
</tbody>
</table>
### HD VTX port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>+10V</td>
<td>+10V</td>
</tr>
<tr>
<td>2</td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>3</td>
<td>TX4</td>
<td>+3.3V</td>
</tr>
<tr>
<td>4</td>
<td>RX4</td>
<td>+3.3V</td>
</tr>
<tr>
<td>5</td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>6</td>
<td>RX7</td>
<td>+3V3</td>
</tr>
</tbody>
</table>
### Receiver Port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>+5V</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>3</td>
<td>RX7</td>
<td>+3.3</td>
</tr>
<tr>
<td>4</td>
<td>TX7</td>
<td>+3.3V</td>
</tr>
</tbody>
</table>
### CANbus Port
<table border="1" class="docutils">
<tbody>
<tr>
<th>Pin</th>
<th>Signal</th>
<th>Volt</th>
</tr>
<tr>
<td>1</td>
<td>+5V</td>
<td>+5V</td>
</tr>
<tr>
<td>2</td>
<td>GND</td>
<td>GND</td>
</tr>
<tr>
<td>3</td>
<td>CAN_H</td>
<td>+5V</td>
</tr>
<tr>
<td>4</td>
<td>CAN_L</td>
<td>+5V</td>
</tr>
</tbody>
</table>
## PWM Output
The Lumenier LUX F765 NDAA supports 12 PWM outputs and a serial LED PWM output.
All outputs are DShot capable. Outputs 1-4 are bi-directional DShot capable.
The 8 main PWM outputs are labeled M1 through M8.
The 4 auxiliary outputs are labeled S1 through S4.
The 8 main PWM outputs are in 2 groups:
- PWM 1 through 4 (M1 - M4) are in TIM2
- PWM 5 through 8 (M5 - M8) are in TIM4
The auxiliary PWM outputs are grouped as follows:
- PWM 9/10 (S1/S2) are in a group
- PWM 11/12 (S3/S4) are in a group
- PWM 13 (LED) is in a group
## RC Input
Bi-directional RC inputs like CRSF/ELRS are supported on USART1 (telem1).
USART1 (telem1) will also support all unidirectional RC protocols.
## OSD Support
The LUX F765 - NDAA is equipped with an onboard AT7456E OSD.
The AT7456E communicates with the flight controller on SPI3.
## Camera Control
The LUX F765 - NDAA has a camera control output on PE10, which corresponds to GPIO 82. Additionally, RELAY3 is pre-configured to control GPIO 82.
## Analog inputs
The LUX F765 NDAA has 2 analog inputs:
- PC2 -> Battery Current
- PC3 -> Battery Voltage
# Battery Monitor
The LUX F765 - NDAA has an internal voltage sensor and connections on the ESC connector
for an external current sensor input. The voltage sensor can handle up to an 8S battery.
The default parameters are as follows:
* :ref:`BATT_MONITOR<BATT_MONITOR>` = 4
* :ref:`BATT_VOLT_PIN<BATT_VOLT_PIN__AP_BattMonitor_Analog>` = 12
* :ref:`BATT_CURR_PIN<BATT_CURR_PIN__AP_BattMonitor_Analog>` = 13
* :ref:`BATT_VOLT_MULT<BATT_VOLT_MULT__AP_BattMonitor_Analog>` = 10.1
* :ref:`BATT_AMP_PERVLT<BATT_AMP_PERVLT__AP_BattMonitor_Analog>` = 17.0 (will need to be adjusted for whichever current sensor is attached)
## Compass
The LUX F765 - NDAA does not have a built-in compass, but you can attach an external compass using I2C on the SDA and SCL pads.
## Firmware
Firmware for the LUX F765 - NDAA can be found [here](https://firmware.ardupilot.org) in sub-folders labeled “LumenierLUXF765-NDAA".
## Loading Firmware
The LUX F765 - NDAA does not come with ArduPilot firmware pre-installed. Use instructions here to load ArduPilot the first time :ref:`common-loading-firmware-onto-chibios-only-boards`.
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 favorite 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.

View File

@ -0,0 +1,45 @@
# Lumenier LUX F765 Flight Controller - NDAA
# hw definition file for processing by chibios_hwdef.py
# for F765 bootloader
# MCU class and specific type
MCU STM32F7xx STM32F767xx
# crystal frequency
OSCILLATOR_HZ 8000000
# board ID for firmware load
APJ_BOARD_ID AP_HW_LUMENIER_LUX_F765_NDAA
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 96
PE4 LED_BOOTLOADER OUTPUT HIGH
define HAL_LED_ON 0
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# VTX_POWER not included on NDAAF7
# PB2 VTX_PWR OUTPUT HIGH
PE10 CAM_CTRL OUTPUT HIGH
# Add CS pins to ensure they are high in bootloader
PB12 FLASH_CS CS
PA15 AT7456E_CS CS
PE12 SDCARD_CS CS
PA4 ICM42688_CS CS

View File

@ -0,0 +1,187 @@
# Lumenier LUX F765 Flight Controller - NDAA
# hw definition file for processing by chibios_hwdef.py
# 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 8000000
# ChibiOS system timer
STM32_ST_USE_TIMER 5
# board ID for firmware load
APJ_BOARD_ID AP_HW_LUMENIER_LUX_F765_NDAA
FLASH_RESERVE_START_KB 96
# flash size
FLASH_SIZE_KB 2048
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 UART5 USART3 UART8 USART2 UART4 UART7 USART6
# 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 - GYRO
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
PA4 ICM42688_CS CS
PE14 DRDY1_ICM42688 INPUT
# SPI2 - FLASH
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PB12 FLASH_CS CS
# SPI3 - OSD
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PC12 SPI3_MOSI SPI3
PA15 AT7456E_CS CS
# SPI4 - SD CARD
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PE12 SDCARD_CS CS
PE3 SD_DETECT INPUT
# I2C buses
# I2C2 not present on NDAAF7
# PB10 I2C2_SCL I2C2
# PB11 I2C2_SDA I2C2
PA8 I2C3_SCL I2C3
PC9 I2C3_SDA I2C3
# order of I2C buses
I2C_ORDER I2C3
# UARTs
# USART1 for telem1 (RX)
PA10 USART1_RX USART1
PA9 USART1_TX USART1
define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_RCIN
# USART2 for ESC telemetry
PD6 USART2_RX USART2 NODMA
PD5 USART2_TX USART2 NODMA
define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry
# USART3 for GPS1
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART4 spare uart
PD0 UART4_RX UART4 NODMA
PD1 UART4_TX UART4 NODMA
define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_MSP_DisplayPort
# UART5 for telem2
PD2 UART5_RX UART5
PB6 UART5_TX UART5
# USART6 spare uart
PC7 USART6_RX USART6 NODMA
PC6 USART6_TX USART6 NODMA
# UART7 spare uart
PE7 UART7_RX UART7 NODMA
PE8 UART7_TX UART7 NODMA
# UART8 GPS2
PE0 UART8_RX UART8 NODMA
PE1 UART8_TX UART8 NODMA
# PWM AUX channels
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51)
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53)
PD12 TIM4_CH1 TIM4 PWM(5) GPIO(54)
PD13 TIM4_CH2 TIM4 PWM(6) GPIO(55)
PD14 TIM4_CH3 TIM4 PWM(7) GPIO(56)
PD15 TIM4_CH4 TIM4 PWM(8) GPIO(57)
PB0 TIM3_CH3 TIM3 PWM(9) GPIO(58)
PB1 TIM3_CH4 TIM3 PWM(10) GPIO(59)
PE9 TIM1_CH1 TIM1 PWM(11) GPIO(60)
PE11 TIM1_CH2 TIM1 PWM(12) GPIO(61)
PB5 TIM3_CH2 TIM3 PWM(13) GPIO(62) # for WS2812 LED
# PWM output for buzzer
PC8 TIM8_CH3 TIM8 GPIO(77) ALARM
# RC input (PPM)
# Not included on NDAAF7 - placeholder
# PE13 TIM1_CH3 TIM1 RCININT PULLDOWN LOW
# VTX Power control - should be high at startup to ensure power
# Not included on NDAAF7 - placeholder
# PB2 VTX_PWR OUTPUT HIGH GPIO(81)
# define RELAY2_PIN_DEFAULT 81
# Camera switch control - should be high at startup to ensure Camera 1 selected
PE10 CAM_CTRL OUTPUT HIGH GPIO(82)
define RELAY3_PIN_DEFAULT 82
define AP_HAL_SHARED_DMA_ENABLED 1
DMA_PRIORITY TIM2* TIM4* SPI1* USART1* USART3* UART5* ADC* TIM1* TIM3*
# analog in
# Airspeed ADC and RSSI not present on NDAAF7
# PC0 SPARE1_ADC1 ADC1 SCALE(1)
# PC1 RSSI_IN ADC1 SCALE(1)
PC2 BATT_CURRENT_SENS ADC1 SCALE(1)
PC3 BATT_VOLTAGE_SENS ADC1 SCALE(1)
define HAL_BATT_VOLT_PIN 12
define HAL_BATT_CURR_PIN 13
define HAL_BATT_VOLT_SCALE 10.1
define HAL_BATT_CURR_SCALE 17.0
# CAN bus
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
# SPI devices
SPIDEV icm42688 SPI1 DEVID1 ICM42688_CS MODE3 2*MHZ 16*MHZ
SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
SPIDEV osd SPI3 DEVID1 AT7456E_CS MODE0 10*MHZ 10*MHZ
SPIDEV sdcard SPI4 DEVID2 SDCARD_CS MODE0 400*KHZ 25*MHZ
# ICM-42688P
IMU Invensensev3 SPI:icm42688 ROTATION_YAW_180
# 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 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# one baro
BARO BMP280 I2C:0:0x76
# LED
define AP_NOTIFY_GPIO_LED_1_ENABLED 1
PE4 LED0 OUTPUT LOW GPIO(90) # blue
define AP_NOTIFY_GPIO_LED_1_PIN 90
# filesystem setup on sdcard
define HAL_OS_FATFS_IO 1
define HAL_STORAGE_SIZE 16384
# setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 5
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin