mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
Merge remote-tracking branch 'origin/development' into dzikuvx-yaw-handling-cleanup
This commit is contained in:
commit
ecd3cdce07
21 changed files with 216 additions and 184 deletions
|
@ -8,6 +8,7 @@ env:
|
|||
- GOAL=targets-group-5
|
||||
- GOAL=targets-group-6
|
||||
- GOAL=targets-group-7
|
||||
- GOAL=targets-group-8
|
||||
- GOAL=targets-group-rest
|
||||
|
||||
# use new docker environment
|
||||
|
|
7
Makefile
7
Makefile
|
@ -133,7 +133,8 @@ GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 ALIENFLIGHTNGF7 P
|
|||
GROUP_5_TARGETS := ASGARD32F7 CHEBUZZF3 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
|
||||
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
|
||||
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
|
||||
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS), $(VALID_TARGETS))
|
||||
GROUP_8_TARGETS := MATEKF765
|
||||
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS))
|
||||
|
||||
REVISION = $(shell git rev-parse --short HEAD)
|
||||
|
||||
|
@ -415,6 +416,9 @@ targets-group-6: $(GROUP_6_TARGETS)
|
|||
## targets-group-7 : build some targets
|
||||
targets-group-7: $(GROUP_7_TARGETS)
|
||||
|
||||
## targets-group-8 : build some targets
|
||||
targets-group-8: $(GROUP_8_TARGETS)
|
||||
|
||||
## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3)
|
||||
targets-group-rest: $(GROUP_OTHER_TARGETS)
|
||||
|
||||
|
@ -510,6 +514,7 @@ targets:
|
|||
$(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)"
|
||||
$(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)"
|
||||
$(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)"
|
||||
$(V0) @echo "targets-group-7: $(GROUP_8_TARGETS)"
|
||||
$(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)"
|
||||
$(V0) @echo "Release targets: $(RELEASE_TARGETS)"
|
||||
|
||||
|
|
|
@ -23,7 +23,7 @@
|
|||
* `MATEKF411` if you want to control LEDs and have SS1 TX on ST1 pad.
|
||||
* `MATEKF411_FD_SFTSRL` if you need the softserial to be full-duplex (TX = ST1 pad, RX = LED pad), at the cost of losing the LED output.
|
||||
* `MATEKF411_RSSI` if you want to have analog RSSI input on ST1 pad. SS1 TX will be available on the LED pad.
|
||||
* `MATEKF411_SFTSRL2`if you want to use two softserials (TX only) at the same time. Eg. Smart Audio + S. Port, Smart Audio + LTM
|
||||
* `MATEKF411_SFTSRL2`if you want to use two softserials (TX only) at the same time. Eg. Smart Audio + S. Port, Smart Audio + LTM. (SS1 TX will be on ST1 pad and SS2 TX will be on LED pad).
|
||||
|
||||
## Where to buy:
|
||||
|
||||
|
|
|
@ -75,8 +75,22 @@ I2C requires that the WS2812 led strip is moved to S5, thus WS2812 is not usable
|
|||
Soft serial is available as an alternative to a hardware UART on RX4/TX4 and TX2. By default this is NOT inverted. In order to use this feature:
|
||||
|
||||
* Enable soft serial
|
||||
* Do not assign any function to hardware UART4 or UART2-TX
|
||||
* Assign the desired function to the soft-serial port
|
||||
* Do not assign any function to hardware UART4
|
||||
* Assign the desired function to the soft-serial ports
|
||||
* UART4 TX/RX pads will be used as SoftSerial 1 TX/RX pads
|
||||
* UART2 TX pad will be used as SoftSerial 2 TX pad
|
||||
|
||||
RX2 and SBUS pads can be used as normal for receiver-only UART. If you need a full duplex UART (IE: TBS Crossfire) and SoftSerial, then use UART 1, 3 or 5 for Full Duplex.
|
||||
|
||||
#### Common scenarios for SoftSerial on this boards:
|
||||
You need to wire a FrSky receiver (SBUS and SmartPort) to the Flight controller
|
||||
* Connect SBUS from Receiver to SBUS pin on the Flight Controller
|
||||
* Connect SmartPort from Receiver to TX2 pad on the Flight Controller
|
||||
* Enable SoftSerial and set UART2 for Serial RX and SoftSerial 2 for SmartPort Telemetry
|
||||
|
||||
You need to wire a SmartAudio or Trump VTX to the Flight controller
|
||||
* Connect SmartAudio/Tramp from VTX to the TX4 pad on the Flight Controller
|
||||
* Enable SoftSerial and set SoftSerial 1 for SmartAudio or Tramp
|
||||
|
||||
### USB
|
||||
|
||||
|
|
28
docs/Board - MatekF765-Wing.md
Normal file
28
docs/Board - MatekF765-Wing.md
Normal file
|
@ -0,0 +1,28 @@
|
|||
# Board - [MATEKSYS F765-Wing](https://inavflight.com/shop/s/bg/1557661)
|
||||
|
||||

|
||||
|
||||
## Specification:
|
||||
|
||||
* STM32F765 216MHz CPU
|
||||
* 2-8S LiPo support
|
||||
* 132A current sensor
|
||||
* OSD
|
||||
* BMP280 barometer
|
||||
* SD slot
|
||||
* 7 UART serial ports
|
||||
* 2 I2C
|
||||
* PDB for 2 motors
|
||||
* 12 outputs (10 DSHOT)
|
||||
* 8A BEC for the servos
|
||||
* 9V supply for FPV gear
|
||||
* Dual camera switcher
|
||||
|
||||
## Details
|
||||
|
||||
* For Matek F765-WING use `MATEKF765` firmware.
|
||||
* No need for SBUS inversion
|
||||
|
||||
## Where to buy:
|
||||
|
||||
* [Banggood](https://inavflight.com/shop/s/bg/1557661)
|
|
@ -1,20 +1,17 @@
|
|||
# Flight controller hardware
|
||||
|
||||
The current focus is geared towards flight controller hardware that use the STM32F3, STM32F4, STM32F7 series processors. The core logic is separated from the hardware drivers, porting to other processors is possible.
|
||||
### Sponsored and recommended boards
|
||||
|
||||
Current list of supported boards can be obtained using [INAV release page](https://github.com/iNavFlight/inav/releases)
|
||||
These boards come from companies that support INAV development. Buying one of these boards you make your small contribution for improving INAV as well.
|
||||
|
||||
### Boards based on F1 CPUs
|
||||
Also these boards are tested by INAV development team and usually flown on daily basis.
|
||||
|
||||
These boards are no longer supported including Naze32, CC3D and all derivatives.
|
||||
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|
||||
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
|
||||
| [Airbot OMNIBUS F4 PRO](https://inavflight.com/shop/p/OMNIBUSF4PRO)| F4 | OMNIBUSF4PRO | All | All | All | All | All | SERIAL, SD |
|
||||
| [Airbot OMNIBUS F4](https://inavflight.com/shop/s/bg/1319176)| F4 | OMNIBUSF4 | All | All | All | All | All | SERIAL, SD |
|
||||
|
||||
### Boards based on F3 CPUs
|
||||
|
||||
These boards are supported, but not recommeneded for modern setups.
|
||||
|
||||
### Boards based on F4/F7 CPUs
|
||||
|
||||
These boards are powerfull and in general support everything INAV is capable of. Limitations are quite rare and are usually caused by hardware design issues.
|
||||
Note: In the above and following tables, the sensor columns indicates firmware support for the sensor category; it does not necessarily mean there is an on-board sensor.
|
||||
|
||||
### Recommended boards
|
||||
|
||||
|
@ -22,7 +19,31 @@ These boards are well tested with INAV and are known to be of good quality and r
|
|||
|
||||
| Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox |
|
||||
|---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:|
|
||||
| [PARIS Sirius™ AIR3](http://www.multiwiicopter.com/products/inav-air3-fixed-wing) | F3 | AIRHEROF3, AIRHEROF3_QUAD | All | All | All | All | All | SERIAL |
|
||||
| [Airbot OMNIBUS AIO F3](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusv11.html) | F3 | OMNIBUS | All | All | All | All | All | SERIAL, SD |
|
||||
| [Airbot OMNIBUS AIO F4](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusf4v2.html)| F4 | OMNIBUSF4, OMNIBUSF4PRO | All | All | All | All | All | SERIAL, SD, SPIFLASH |
|
||||
| [Airbot F4 / Flip F4](http://shop.myairbot.com/index.php/flight-control/apm/airbotf4v1.html) | F4 | AIRBOTF4 | All | All | All | All | All | SERIAL, SPIFLASH |
|
||||
| [Matek F405-CTR](https://inavflight.com/shop/p/MATEKF405CTR) | F4 | MATEKF405 | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F405-STD](https://inavflight.com/shop/p/MATEKF405STD) | F4 | MATEKF405 | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F405-WING](https://inavflight.com/shop/p/MATEKF405WING) | F4 | MATEKF405SE | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F722 WING](https://inavflight.com/shop/p/MATEKF722WING) | F7 | MATEKF722SE | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F722-SE](https://inavflight.com/shop/p/MATEKF722SE) | F7 | MATEKF722SE | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F722-STD](https://inavflight.com/shop/p/MATEKF722STD) | F7 | MATEKF722 | All | All | All | All | All | SERIAL, SD |
|
||||
| [Matek F722-MINI](https://inavflight.com/shop/p/MATEKF722MINI) | F7 | MATEKF722SE | All | All | All | All | All | SPIFLASH |
|
||||
|
||||
It's possible to find more supported and tested boards [here](https://github.com/iNavFlight/inav/wiki/Welcome-to-INAV,-useful-links-and-products)
|
||||
### Boards documentation
|
||||
|
||||
See the [docs](https://github.com/iNavFlight/inav/tree/master/docs) folder for additional information regards to many targets in INAV, to example help in finding pinout and features. _Feel free to help improve the docs._
|
||||
|
||||
### Boards based on F4/F7 CPUs
|
||||
|
||||
These boards are powerful and in general support everything INAV is capable of. Limitations are quite rare and are usually caused by hardware design issues.
|
||||
|
||||
### Boards based on F3 CPUs
|
||||
|
||||
Boards based on F3 boards will be supported for as long as practical, sometimes with reduced features due to lack of resources. No new features will be added so F3 boards are not recommended for new builds.
|
||||
|
||||
### Boards based on F1 CPUs
|
||||
|
||||
Boards based on STM32F1 CPUs are no longer supported by latest INAV version. Last release is 1.7.3
|
||||
|
||||
### Not recommended for new setups
|
||||
|
||||
F1 and F3 boards are no longer recommended. Users should choose a board from the supported F4 or F7 devices available in the latest release.
|
|
@ -1,103 +0,0 @@
|
|||
# Building in windows
|
||||
|
||||
|
||||
##Setup Cygwin
|
||||
|
||||
download the Setup*.exe from https://www.cygwin.com/
|
||||
|
||||

|
||||
|
||||
Execute the download Setup and step through the installation wizard (no need to customize the settings here). Stop at the "Select Packages" Screen and select the following Packages
|
||||
for Installation:
|
||||
|
||||
- Devel/binutils
|
||||
- Devel/git
|
||||
- Devel/git-completion (Optional)
|
||||
- Devel/make
|
||||
- Editors/vim
|
||||
- Editors/vim-common (Optional)
|
||||
- Shells/mintty (should be already selected)
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||

|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
|
||||
Continue with the Installation and accept all autodetected dependencies.
|
||||
|
||||

|
||||
|
||||
|
||||
##Setup GNU ARM Toolchain
|
||||
|
||||
----------
|
||||
|
||||
use the latest version available. Download this version from https://gcc.gnu.org/mirrors.html - preferably as a ZIP-File.
|
||||
|
||||
|
||||
Extract the contents of this archive to any folder of your choice, for instance ```C:\dev\gcc-arm-none-eabi-*version number*```.
|
||||
|
||||

|
||||
|
||||
add the "bin" subdirectory to the PATH Windows environment variable: ```%PATH%;C:\dev\gcc-arm-none-eabi-*version number*\bin```
|
||||
|
||||

|
||||
|
||||

|
||||
|
||||
##Setup Ruby
|
||||
|
||||
Install the latest Ruby version using [Ruby Installer](https://rubyinstaller.org).
|
||||
|
||||
## Checkout and compile INAV
|
||||
|
||||
Head over to the INAV Github page and grab the URL of the GIT Repository: "https://github.com/iNavFlight/inav.git"
|
||||
|
||||
Open the Cygwin-Terminal, navigate to your development folder and use the git commandline to checkout the repository:
|
||||
|
||||
```bash
|
||||
cd /cygdrive/c/dev
|
||||
git clone https://github.com/iNavFlight/inav.git
|
||||
```
|
||||

|
||||
|
||||

|
||||
|
||||
To compile your INAV binaries, enter the inav directory and build the project using the make command. You can append TARGET=[HARDWARE] if you want to build anything other than the default SPRACINGF3 target:
|
||||
|
||||
```bash
|
||||
cd inav
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
||||
|
||||

|
||||
|
||||
within few moments you should have your binary ready:
|
||||
|
||||
```bash
|
||||
(...)
|
||||
arm-none-eabi-size ./obj/main/inav_SPRACINGF3.elf
|
||||
text data bss dec hex filename
|
||||
95388 308 10980 106676 1a0b4 ./obj/main/inav_SPRACINGF3.elf
|
||||
arm-none-eabi-objcopy -O ihex --set-start 0x8000000 obj/main/inav_SPRACINGF3.elf obj/inav_SPRACINGF3.hex
|
||||
```
|
||||
|
||||
You can use the INAV-Configurator to flash the ```obj/inav_SPRACINGF3.hex``` file.
|
||||
|
||||
## Updating and rebuilding
|
||||
|
||||
Navigate to the local INAV repository and use the following steps to pull the latest changes and rebuild your version of INAV:
|
||||
|
||||
```bash
|
||||
cd /cygdrive/c/dev/inav
|
||||
git reset --hard
|
||||
git pull
|
||||
make clean
|
||||
make TARGET=SPRACINGF3
|
||||
```
|
|
@ -15,7 +15,7 @@ RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4
|
|||
RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
|
||||
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
|
||||
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765
|
||||
|
||||
RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL
|
||||
|
||||
|
@ -29,4 +29,6 @@ RELEASE_TARGETS += MAMBAF405
|
|||
|
||||
RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING
|
||||
|
||||
RELEASE_TARGETS += AIKONF4
|
||||
RELEASE_TARGETS += AIKONF4
|
||||
|
||||
RELEASE_TARGETS += MATEKF765
|
|
@ -28,6 +28,9 @@
|
|||
#define CONCAT_HELPER(x,y) x ## y
|
||||
#define CONCAT(x,y) CONCAT_HELPER(x, y)
|
||||
|
||||
#define CONCAT3_HELPER(x, y, z) x ## y ## z
|
||||
#define CONCAT3(x, y, z) CONCAT3_HELPER(x, y, z)
|
||||
|
||||
#define CONCAT4_HELPER(x, y, z, w) x ## y ## z ## w
|
||||
#define CONCAT4(x, y, z, w) CONCAT4_HELPER(x, y, z, w)
|
||||
|
||||
|
@ -106,4 +109,4 @@ void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("me
|
|||
#define FALLTHROUGH do {} while(0)
|
||||
#endif
|
||||
|
||||
#define ALIGNED(x) __attribute__ ((aligned(x)))
|
||||
#define ALIGNED(x) __attribute__ ((aligned(x)))
|
||||
|
|
|
@ -116,7 +116,7 @@
|
|||
#define SYM_3D_KMH 0x89 // 137 KM/H 3D
|
||||
#define SYM_3D_MPH 0x8A // 138 MPH 3D
|
||||
|
||||
// 0x8B // 139 -
|
||||
#define SYM_RPM 0x8B // 139 RPM
|
||||
// 0x8C // 140 -
|
||||
// 0x8D // 141 -
|
||||
// 0x8E // 142 -
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define UART_AF(uart, af) CONCAT3(GPIO_AF, af, _ ## uart)
|
||||
|
||||
// Since serial ports can be used for any function these buffer sizes should be equal
|
||||
// The two largest things that need to be sent are: 1, MSP responses, 2, UBLOX SVINFO packet.
|
||||
|
||||
|
|
|
@ -54,7 +54,11 @@ static uartDevice_t uart1 =
|
|||
.dev = USART1,
|
||||
.rx = IO_TAG(UART1_RX_PIN),
|
||||
.tx = IO_TAG(UART1_TX_PIN),
|
||||
#ifdef UART1_AF
|
||||
.af = UART_AF(USART1, UART1_AF),
|
||||
#else
|
||||
.af = GPIO_AF7_USART1,
|
||||
#endif
|
||||
#ifdef UART1_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -70,7 +74,11 @@ static uartDevice_t uart2 =
|
|||
.dev = USART2,
|
||||
.rx = IO_TAG(UART2_RX_PIN),
|
||||
.tx = IO_TAG(UART2_TX_PIN),
|
||||
#ifdef UART2_AF
|
||||
.af = UART_AF(USART2, UART2_AF),
|
||||
#else
|
||||
.af = GPIO_AF7_USART2,
|
||||
#endif
|
||||
#ifdef UART2_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -86,7 +94,11 @@ static uartDevice_t uart3 =
|
|||
.dev = USART3,
|
||||
.rx = IO_TAG(UART3_RX_PIN),
|
||||
.tx = IO_TAG(UART3_TX_PIN),
|
||||
#ifdef UART3_AF
|
||||
.af = UART_AF(USART3, UART3_AF),
|
||||
#else
|
||||
.af = GPIO_AF7_USART3,
|
||||
#endif
|
||||
#ifdef UART3_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -102,7 +114,11 @@ static uartDevice_t uart4 =
|
|||
.dev = UART4,
|
||||
.rx = IO_TAG(UART4_RX_PIN),
|
||||
.tx = IO_TAG(UART4_TX_PIN),
|
||||
#ifdef UART4_AF
|
||||
.af = UART_AF(UART4, UART4_AF),
|
||||
#else
|
||||
.af = GPIO_AF8_UART4,
|
||||
#endif
|
||||
#ifdef UART4_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -118,7 +134,11 @@ static uartDevice_t uart5 =
|
|||
.dev = UART5,
|
||||
.rx = IO_TAG(UART5_RX_PIN),
|
||||
.tx = IO_TAG(UART5_TX_PIN),
|
||||
#ifdef UART5_AF
|
||||
.af = UART_AF(UART5, UART5_AF),
|
||||
#else
|
||||
.af = GPIO_AF8_UART5,
|
||||
#endif
|
||||
#ifdef UART5_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -134,7 +154,11 @@ static uartDevice_t uart6 =
|
|||
.dev = USART6,
|
||||
.rx = IO_TAG(UART6_RX_PIN),
|
||||
.tx = IO_TAG(UART6_TX_PIN),
|
||||
#ifdef UART6_AF
|
||||
.af = UART_AF(USART6, UART6_AF),
|
||||
#else
|
||||
.af = GPIO_AF8_USART6,
|
||||
#endif
|
||||
#ifdef UART6_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -150,7 +174,11 @@ static uartDevice_t uart7 =
|
|||
.dev = UART7,
|
||||
.rx = IO_TAG(UART7_RX_PIN),
|
||||
.tx = IO_TAG(UART7_TX_PIN),
|
||||
#ifdef UART7_AF
|
||||
.af = UART_AF(UART7, UART7_AF),
|
||||
#else
|
||||
.af = GPIO_AF8_UART7,
|
||||
#endif
|
||||
#ifdef UART7_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART7_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
@ -165,7 +193,11 @@ static uartDevice_t uart8 =
|
|||
.dev = UART8,
|
||||
.rx = IO_TAG(UART8_RX_PIN),
|
||||
.tx = IO_TAG(UART8_TX_PIN),
|
||||
#ifdef UART8_AF
|
||||
.af = UART_AF(UART8, UART8_AF),
|
||||
#else
|
||||
.af = GPIO_AF8_UART8,
|
||||
#endif
|
||||
#ifdef UART8_AHB1_PERIPHERALS
|
||||
.rcc_ahb1 = UART8_AHB1_PERIPHERALS,
|
||||
#endif
|
||||
|
|
|
@ -131,6 +131,8 @@
|
|||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "uav_interconnect/uav_interconnect.h"
|
||||
|
@ -640,5 +642,11 @@ void init(void)
|
|||
motorControlEnable = true;
|
||||
fcTasksInit();
|
||||
|
||||
#ifdef USE_OSD
|
||||
if (feature(FEATURE_OSD) && (osdDisplayPort != NULL)) {
|
||||
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||
}
|
||||
#endif
|
||||
|
||||
systemState |= SYSTEM_STATE_READY;
|
||||
}
|
||||
|
|
|
@ -313,9 +313,6 @@ void fcTasksInit(void)
|
|||
#ifdef USE_PWM_SERVO_DRIVER
|
||||
setTaskEnabled(TASK_PWMDRIVER, feature(FEATURE_PWM_SERVO_DRIVER));
|
||||
#endif
|
||||
#ifdef USE_OSD
|
||||
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
|
||||
#endif
|
||||
#ifdef USE_CMS
|
||||
#ifdef USE_MSP_DISPLAYPORT
|
||||
setTaskEnabled(TASK_CMS, true);
|
||||
|
|
|
@ -888,21 +888,19 @@ static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t
|
|||
#if defined(USE_ESC_SENSOR)
|
||||
static void osdFormatRpm(char *buff, uint32_t rpm)
|
||||
{
|
||||
// FIXME: We need a new symbol for RPM
|
||||
buff[0] = SYM_BLANK;
|
||||
buff[1] = SYM_THR;
|
||||
buff[0] = SYM_RPM;
|
||||
if (rpm) {
|
||||
if (rpm >= 1000) {
|
||||
osdFormatCentiNumber(buff + 2, rpm / 10, 0, 1, 1, 2);
|
||||
buff[4] = 'K';
|
||||
buff[5] = '\0';
|
||||
osdFormatCentiNumber(buff + 1, rpm / 10, 0, 1, 1, 2);
|
||||
buff[3] = 'K';
|
||||
buff[4] = '\0';
|
||||
}
|
||||
else {
|
||||
tfp_sprintf(buff + 2, "%3lu", rpm);
|
||||
tfp_sprintf(buff + 1, "%3lu", rpm);
|
||||
}
|
||||
}
|
||||
else {
|
||||
strcpy(buff + 2, "---");
|
||||
strcpy(buff + 1, "---");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -375,6 +375,10 @@ rx_spi_received_e eleresDataReceived(uint8_t *payload, uint16_t *linkQuality)
|
|||
statusRegisters[0] = 0;
|
||||
statusRegisters[1] = 0;
|
||||
|
||||
if (linkQuality) {
|
||||
*linkQuality = eleresRssi();
|
||||
}
|
||||
|
||||
if (rxSpiCheckIrq())
|
||||
{
|
||||
statusRegisters[0] = rfmSpiRead(0x03);
|
||||
|
@ -385,10 +389,6 @@ rx_spi_received_e eleresDataReceived(uint8_t *payload, uint16_t *linkQuality)
|
|||
}
|
||||
}
|
||||
|
||||
if (linkQuality) {
|
||||
*linkQuality = eleresRssi();
|
||||
}
|
||||
|
||||
eleresSetRcDataFromPayload(NULL,NULL);
|
||||
|
||||
return RX_SPI_RECEIVED_NONE;
|
||||
|
|
|
@ -510,7 +510,6 @@ void FAST_CODE NOINLINE gyroUpdate()
|
|||
#ifdef USE_GYRO_NOTCH_2
|
||||
gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf);
|
||||
#endif
|
||||
gyro.gyroADCf[axis] = gyroADCf;
|
||||
|
||||
#ifdef USE_DYNAMIC_FILTERS
|
||||
if (isDynamicFilterActive()) {
|
||||
|
@ -523,6 +522,7 @@ void FAST_CODE NOINLINE gyroUpdate()
|
|||
gyroADCf = notchFilterDynApplyFn2((filter_t *)¬chFilterDyn2[axis], gyroADCf);
|
||||
}
|
||||
#endif
|
||||
gyro.gyroADCf[axis] = gyroADCf;
|
||||
}
|
||||
|
||||
#ifdef USE_DYNAMIC_FILTERS
|
||||
|
|
|
@ -33,6 +33,9 @@
|
|||
#define BEEPER PD15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_DSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_GYRO
|
||||
|
||||
|
@ -49,6 +52,15 @@
|
|||
#define ICM20689_CS_PIN SPI4_NSS_PIN
|
||||
#define ICM20689_SPI_BUS BUS_SPI4
|
||||
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_INT_EXTI PE1
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
#define MPU6000_CS_PIN SPI4_NSS_PIN
|
||||
#define MPU6000_SPI_BUS BUS_SPI4
|
||||
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
#define USB_IO
|
||||
#define USE_VCP
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
|
|
@ -7,6 +7,7 @@ endif
|
|||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_icm20689.c \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/compass/compass_ak8963.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
DEF_TIM(TIM10, CH1, PB8, TIM_USE_PPM, 0, 0), // PPM
|
||||
DEF_TIM(TIM4, CH4, PB9, TIM_USE_ANY, 0, 0), // S2_IN
|
||||
#else
|
||||
|
@ -42,14 +42,25 @@ const timerHardware_t timerHardware[] = {
|
|||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4_OUT D1_ST1
|
||||
|
||||
// { TIM9, IO_TAG(PA3), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // MOTOR_3
|
||||
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
|
||||
#elif defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_ANY, 0, 0), // S5_OUT SOFTSERIAL
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
|
||||
#elif defined(OMNIBUSF4V3_S6_SS)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // S6_OUT SOFTSERIAL
|
||||
#elif defined(OMNIBUSF4PRO_LEDSTRIPM5)
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_LED, 0, 0), // S5_OUT LED strip
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
|
||||
#else
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S5_OUT
|
||||
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO | TIM_USE_LED, 0, 0), // S5_OUT MOTOR, SERVO or LED
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
|
||||
#endif
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S6_OUT
|
||||
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5)
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
|
||||
|
||||
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS))
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, 0, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
|
||||
#endif
|
||||
};
|
||||
|
||||
|
|
|
@ -69,22 +69,23 @@
|
|||
#define MPU6000_CS_PIN PA4
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
#if defined(DYSF4PRO) || defined(DYSF4PROV2)
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#else
|
||||
// Long sentence, OMNIBUSF4 always defined
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW270_DEG
|
||||
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW270_DEG
|
||||
#else
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG
|
||||
#endif
|
||||
|
||||
// Support for OMNIBUS F4 PRO CORNER - it has ICM20608 instead of MPU6000
|
||||
#if !defined(DYSF4PRO) && !defined(DYSF4PROV2)
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define MPU6500_CS_PIN MPU6000_CS_PIN
|
||||
#define MPU6500_SPI_BUS MPU6000_SPI_BUS
|
||||
|
||||
|
@ -110,20 +111,19 @@
|
|||
|
||||
#define USE_BARO
|
||||
|
||||
#if defined(DYSF4PRO) || defined(DYSF4PROV2) || defined(OMNIBUSF4)
|
||||
#define BARO_I2C_BUS I2C_EXT_BUS
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#else
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define USE_BARO_BMP280
|
||||
#define BMP280_SPI_BUS BUS_SPI3
|
||||
#define BMP280_CS_PIN PB3 // v1
|
||||
|
||||
// Support external barometers
|
||||
#define BARO_I2C_BUS I2C_EXT_BUS
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_MS5611
|
||||
#else
|
||||
#define BARO_I2C_BUS I2C_EXT_BUS
|
||||
#define USE_BARO_BMP085
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
#endif
|
||||
|
||||
#define PITOT_I2C_BUS I2C_EXT_BUS
|
||||
|
@ -166,26 +166,26 @@
|
|||
|
||||
#elif defined(OMNIBUSF4V3_S6_SS) // one softserial on S6
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN PA8 // shared with S6 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA8 // shared with S6 output
|
||||
#define SOFTSERIAL_1_RX_PIN PA8 // S6 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
|
||||
|
||||
#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
|
||||
|
||||
#elif defined(OMNIBUSF4V3_S5S6_SS) // one softserial on S5/RX S6/TX
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN PA1 // shared with S5 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA8 // shared with S6 output
|
||||
#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA8 // S6 output
|
||||
|
||||
#define SERIAL_PORT_COUNT 5 // VCP, USART1, USART3, USART6, SOFTSERIAL1
|
||||
|
||||
#elif defined(OMNIBUSF4V3_S5_S6_2SS) // two softserials, one on S5 and one on S6
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_RX_PIN PA1 // shared with S5 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA1 // shared with S5 output
|
||||
#define SOFTSERIAL_1_RX_PIN PA1 // S5 output
|
||||
#define SOFTSERIAL_1_TX_PIN PA1 // S5 output
|
||||
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SOFTSERIAL_2_RX_PIN PA8 // shared with S6 output
|
||||
#define SOFTSERIAL_2_TX_PIN PA8 // shared with S6 output
|
||||
#define SOFTSERIAL_2_RX_PIN PA8 // S6 output
|
||||
#define SOFTSERIAL_2_TX_PIN PA8 // S6 output
|
||||
|
||||
#define SERIAL_PORT_COUNT 6 // VCP, USART1, USART3, USART6, SOFTSERIAL1, SOFTSERIAL2
|
||||
|
||||
|
@ -201,7 +201,7 @@
|
|||
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#if !defined(DYSF4PRO) && !defined(DYSF4PROV2) && !defined(OMNIBUSF4)
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
|
@ -210,7 +210,7 @@
|
|||
#endif
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#if !defined(DYSF4PRO) && !defined(DYSF4PROV2) && !defined(OMNIBUSF4)
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#else
|
||||
#define SPI3_NSS_PIN PB3
|
||||
|
@ -224,13 +224,7 @@
|
|||
#define MAX7456_SPI_BUS BUS_SPI3
|
||||
#define MAX7456_CS_PIN PA15
|
||||
|
||||
#if defined(DYSF4PRO) || defined(DYSF4PROV2) || defined(OMNIBUSF4)
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#else
|
||||
#if defined(OMNIBUSF4PRO) || defined(OMNIBUSF4PRO_LEDSTRIPM5) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS)
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
|
@ -240,6 +234,12 @@
|
|||
|
||||
#define SDCARD_DETECT_PIN PB7
|
||||
#define SDCARD_DETECT_INVERTED
|
||||
#else
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#endif
|
||||
|
||||
#define USE_ADC
|
||||
|
@ -259,10 +259,10 @@
|
|||
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)
|
||||
|
||||
#define USE_LED_STRIP
|
||||
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3)) && !defined(OMNIBUSF4PRO_LEDSTRIPM5)
|
||||
# define WS2811_PIN PB6
|
||||
#if (defined(OMNIBUSF4PRO) || defined(OMNIBUSF4V3) || defined(OMNIBUSF4V3_S6_SS) || defined(OMNIBUSF4V3_S5S6_SS) || defined(OMNIBUSF4V3_S5_S6_2SS))
|
||||
#define WS2811_PIN PB6
|
||||
#else
|
||||
# define WS2811_PIN PA1
|
||||
#define WS2811_PIN PA1
|
||||
#endif
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_PPM
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue