diff --git a/docs/Boards.md b/docs/Boards.md index 28e54bbdb..944005875 100644 --- a/docs/Boards.md +++ b/docs/Boards.md @@ -1,31 +1,15 @@ # Flight controller hardware -### Sponsored and recommended boards - -These boards come from companies that support INAV development. Buying one of these boards you make your small contribution for improving INAV as well. - -Also these boards are tested by INAV development team and usually flown on daily basis. - -| 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 | - -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 These boards are well tested with INAV and are known to be of good quality and reliability. | Board name | CPU Family | Target name(s) | GPS | Compass | Barometer | Telemetry | RX | Blackbox | |---------------------------|:----------:|:-------------------------:|:----:|:-------:|:--------------:|:---------:|:------------------------------:|:--------------------:| -| [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 | +| [Diatone Mamba H743](https://inavflight.com/shop/s/bg/1929033) | H7 | MAMBAH743 | All | All | All | All | All | SERIAL, SD | +| [Matek F765-WSE](https://inavflight.com/shop/s/bg/1890404) | F7 | MATEKF765SE | 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 | +| [Holybro Kakute H7](https://inavflight.com/shop/s/bg/1914066) | H7 | KAKUTEH7 | All | All | All | All | All | SERIAL, SD | 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 diff --git a/docs/ESC and servo outputs.md b/docs/ESC and servo outputs.md index 09f9f835b..78a505659 100644 --- a/docs/ESC and servo outputs.md +++ b/docs/ESC and servo outputs.md @@ -2,13 +2,14 @@ ## ESC protocols -INAV support following ESC protocols: +INAV support the following ESC protocols: * "standard" PWM with 50-400Hz update rate * OneShot125 * OneShot42 * Multishot * Brushed motors +* DSHOT150, DSHOT300, DSHOT600 ESC protocol can be selected in Configurator. No special configuration is required. @@ -23,4 +24,12 @@ higher update rates. Only high end digital servos are capable of handling 200Hz Not all outputs on a flight controller can be used for servo outputs. It is a hardware thing. Always check flight controller documentation. -While motors are usually ordered sequentially, here is no standard output layout for servos! Some boards might not be supporting servos in _Multirotor_ configuration at all! \ No newline at end of file +While motors are usually ordered sequentially, here is no standard output layout for servos! Some boards might not be supporting servos in _Multirotor_ configuration at all! + +## Modifying output mapping + +INAV 5 allows the limited output type mapping by allowing to change the function of *ALL* outputs at the same time. It can be done with the `output_mode` CLI setting. Allowed values: + +* `AUTO` assigns outputs according to the default mapping +* `SERVOS` assigns all outputs to servos +* `MOTORS` assigns all outputs to motors \ No newline at end of file diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index dadc722fb..e5082ef3d 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -226,13 +226,13 @@ Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Movin `logic 0 1 0 29 0 1000 0 0 0` -Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true` +Sets throttle output to `0%` when Logic Condition `0` evaluates as `true` ### Set throttle to 50% and keep other throttle bindings active `logic 0 1 0 29 0 1500 0 0 0` -Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true` +Sets throttle output to about `50%` when Logic Condition `0` evaluates as `true` ### Set throttle control to different RC channel diff --git a/docs/Settings.md b/docs/Settings.md index 61abf4d18..874337ad2 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -4452,6 +4452,16 @@ LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50 --- +### osd_mah_used_precision + +Number of digits used to display mAh used. + +| Default | Min | Max | +| --- | --- | --- | +| 4 | 4 | 6 | + +--- + ### osd_main_voltage_decimals Number of decimals for the battery voltages displayed in the OSD [1-2]. @@ -5848,7 +5858,7 @@ Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, | Default | Min | Max | | --- | --- | --- | -| 4 | VTX_SETTINGS_NO_BAND | VTX_SETTINGS_MAX_BAND | +| 1 | VTX_SETTINGS_NO_BAND | VTX_SETTINGS_MAX_BAND | --- @@ -5862,6 +5872,16 @@ Channel to use within the configured `vtx_band`. Valid values are [1, 8]. --- +### vtx_frequency_group + +VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz. + +| Default | Min | Max | +| --- | --- | --- | +| FREQUENCYGROUP_5G8 | 0 | 2 | + +--- + ### vtx_halfduplex Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. @@ -5932,6 +5952,16 @@ Enable workaround for early AKK SAudio-enabled VTX bug. --- +### vtx_softserial_shortstop + +Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | OFF | ON | + +--- + ### yaw_deadband These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. diff --git a/docs/VTx.md b/docs/VTx.md new file mode 100644 index 000000000..84bbc9f5f --- /dev/null +++ b/docs/VTx.md @@ -0,0 +1,17 @@ +## VTx Setup + +### IRC Tramp + +#### Matek 1G3SE Setup + +To use the Matek 1G3SE with IRC Tramp. You will need to enter the CLI command `set vtx_frequency_group = FREQUENCYGROUP_1G3`. You must also make sure that the initial VTx settings in the configuration tab are in a valid range. They are: +- `vtx_band` 1 or 2 +- `vtx_channel` between 1 and 9 + +### Team BlackSheep SmartAudio + +If you have problems getting SmartAudio working. There are a couple of CLI parameters you can try changing to see if they help. + +There is a workaround for early AKK VTx modules. This is enabled by default. You could try disabling this setting [`vtx_smartaudio_early_akk_workaround`](https://github.com/iNavFlight/inav/blob/master/docs/Settings.md#vtx_smartaudio_early_akk_workaround) to OFF. + +If you are using softserial, you can try using the alternate method by setting [`vtx_smartaudio_alternate_softserial_method`](https://github.com/iNavFlight/inav/blob/master/docs/Settings.md#vtx_smartaudio_alternate_softserial_method) to OFF. diff --git a/docs/development/Development.md b/docs/development/Development.md index 9be10a3da..03dbc5b09 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -46,21 +46,45 @@ Note: Tests are written in C++ and linked with with firmware's C code. ### Running the tests. -The tests and test build system is very simple and based off the googletest example files, it will be improved in due course. From the root folder of the project simply do: +The tests and test build system is very simple and based off the googletest example files, it may be improved in due course. From the root folder of the project simply do: + +Test are configured from the top level directory. It is recommended to use a separate test directory, here named `testing`. ``` -make test +mkdir testing +cd testing +# define NULL toolchain ... +cmake -DTOOLCHAIN= .. +# Run the tests +make check ``` -This will build a set of executable files in the `obj/test` folder, one for each `*_unittest.cc` file. +This will build a set of executable files in the `src/test/unit` folder (below `testing`), one for each `*_unittest.cc` file. + +After they have been executed by the make invocation, you can still run them on the command line to execute the tests and to see the test report, for example: -After they have been executed by the make invocation, you can still run them on the command line to execute the tests and to see the test report. +``` +src/test/unit/time_unittest +Running main() from /home/jrh/Projects/fc/inav/testing/src/test/googletest-src/googletest/src/gtest_main.cc +[==========] Running 2 tests from 1 test suite. +[----------] Global test environment set-up. +[----------] 2 tests from TimeUnittest +[ RUN ] TimeUnittest.TestMillis +[ OK ] TimeUnittest.TestMillis (0 ms) +[ RUN ] TimeUnittest.TestMicros +[ OK ] TimeUnittest.TestMicros (0 ms) +[----------] 2 tests from TimeUnittest (0 ms total) + +[----------] Global test environment tear-down +[==========] 2 tests from 1 test suite ran. (0 ms total) +[ PASSED ] 2 tests. +``` -You can also step-debug the tests in eclipse and you can use the GoogleTest test runner to make building and re-running the tests simple. +You can also step-debug the tests in `gdb` (or IDE debugger). The tests are currently always compiled with debugging information enabled, there may be additional warnings, if you see any warnings please attempt to fix them and submit pull requests with the fixes. -Tests are verified and working with GCC 4.9.2. +Tests are verified and working with (native) GCC 11.20. ## Using git and github diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 2f5f8e0be..ad78f1ff5 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -69,7 +69,13 @@ typedef struct SPIDevice_s { ioTag_t mosi; ioTag_t miso; rccPeriphTag_t rcc; +#if defined(STM32F7) || defined(STM32H7) + uint8_t sckAF; + uint8_t misoAF; + uint8_t mosiAF; +#else uint8_t af; +#endif const uint32_t * divisorMap; volatile uint16_t errorCount; bool initDone; diff --git a/src/main/drivers/bus_spi_hal_ll.c b/src/main/drivers/bus_spi_hal_ll.c index 25662f2f2..fac8a8276 100644 --- a/src/main/drivers/bus_spi_hal_ll.c +++ b/src/main/drivers/bus_spi_hal_ll.c @@ -91,22 +91,53 @@ static const uint32_t spiDivisorMapSlow[] = { #if defined(STM32H7) static spiDevice_t spiHardwareMap[SPIDEV_COUNT] = { #ifdef USE_SPI_DEVICE_1 - { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast }, +#if defined(SPI1_SCK_AF) || defined(SPI1_MISO_AF) || defined(SPI1_MOSI_AF) +#if !defined(SPI1_SCK_AF) || !defined(SPI1_MISO_AF) || !defined(SPI1_MOSI_AF) +#error SPI1: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast }, +#else + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = GPIO_AF5_SPI1, .misoAF = GPIO_AF5_SPI1, .mosiAF = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast }, +#endif #else { .dev = NULL }, // No SPI1 #endif + #ifdef USE_SPI_DEVICE_2 - { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .af = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow }, +#if defined(SPI2_SCK_AF) || defined(SPI2_MISO_AF) || defined(SPI2_MOSI_AF) +#if !defined(SPI2_SCK_AF) || !defined(SPI2_MISO_AF) || !defined(SPI2_MOSI_AF) +#error SPI2: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow }, +#else + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1L(SPI2), .sckAF = GPIO_AF5_SPI2, .misoAF = GPIO_AF5_SPI2, .mosiAF = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow }, +#endif #else { .dev = NULL }, // No SPI2 #endif + #ifdef USE_SPI_DEVICE_3 - { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1L(SPI3), .af = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow }, +#if defined(SPI3_SCK_AF) || defined(SPI3_MISO_AF) || defined(SPI3_MOSI_AF) +#if !defined(SPI3_SCK_AF) || !defined(SPI3_MISO_AF) || !defined(SPI3_MOSI_AF) +#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1L(SPI3), .sckAF = SPI3_SCK_AF, .misoAF = SPI3_MISO_AF, .mosiAF = SPI3_MOSI_AF, .divisorMap = spiDivisorMapSlow }, +#else + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1L(SPI3), .sckAF = GPIO_AF6_SPI3, .misoAF = GPIO_AF6_SPI3, .mosiAF = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow }, +#endif #else { .dev = NULL }, // No SPI3 #endif + #ifdef USE_SPI_DEVICE_4 - { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .af = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow } +#if defined(SPI4_SCK_AF) || defined(SPI4_MISO_AF) || defined(SPI4_MOSI_AF) +#if !defined(SPI4_SCK_AF) || !defined(SPI4_MISO_AF) || !defined(SPI4_MOSI_AF) +#error SPI4: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = SPI4_SCK_AF, .misoAF = SPI4_MISO_AF, .mosiAF = SPI4_MOSI_AF, .divisorMap = spiDivisorMapSlow } +#else + { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = GPIO_AF5_SPI4, .misoAF = GPIO_AF5_SPI4, .mosiAF = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow } +#endif #else { .dev = NULL } // No SPI4 #endif @@ -114,22 +145,53 @@ static spiDevice_t spiHardwareMap[SPIDEV_COUNT] = { #else static spiDevice_t spiHardwareMap[] = { #ifdef USE_SPI_DEVICE_1 - { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast }, +#if defined(SPI1_SCK_AF) || defined(SPI1_MISO_AF) || defined(SPI1_MOSI_AF) +#if !defined(SPI1_SCK_AF) || !defined(SPI1_MISO_AF) || !defined(SPI1_MOSI_AF) +#error SPI1: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = SPI1_SCK_AF, .misoAF = SPI1_MISO_AF, .mosiAF = SPI1_MOSI_AF, .divisorMap = spiDivisorMapFast }, +#else + { .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .sckAF = GPIO_AF5_SPI1, .misoAF = GPIO_AF5_SPI1, .mosiAF = GPIO_AF5_SPI1, .divisorMap = spiDivisorMapFast }, +#endif #else { .dev = NULL }, // No SPI1 #endif + #ifdef USE_SPI_DEVICE_2 - { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow }, +#if defined(SPI2_SCK_AF) || defined(SPI2_MISO_AF) || defined(SPI2_MOSI_AF) +#if !defined(SPI2_SCK_AF) || !defined(SPI2_MISO_AF) || !defined(SPI2_MOSI_AF) +#error SPI2: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .sckAF = SPI2_SCK_AF, .misoAF = SPI2_MISO_AF, .mosiAF = SPI2_MOSI_AF, .divisorMap = spiDivisorMapSlow }, +#else + { .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .sckAF = GPIO_AF5_SPI2, .misoAF = GPIO_AF5_SPI2, .mosiAF = GPIO_AF5_SPI2, .divisorMap = spiDivisorMapSlow }, +#endif #else { .dev = NULL }, // No SPI2 #endif + #ifdef USE_SPI_DEVICE_3 - { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow }, +#if defined(SPI3_SCK_AF) || defined(SPI3_MISO_AF) || defined(SPI3_MOSI_AF) +#if !defined(SPI3_SCK_AF) || !defined(SPI3_MISO_AF) || !defined(SPI3_MOSI_AF) +#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .sckAF = SPI3_SCK_AF, .misoAF = SPI3_MISO_AF, .mosiAF = SPI3_MOSI_AF, .divisorMap = spiDivisorMapSlow }, +#else + { .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .sckAF = GPIO_AF6_SPI3, .misoAF = GPIO_AF6_SPI3, .mosiAF = GPIO_AF6_SPI3, .divisorMap = spiDivisorMapSlow }, +#endif #else { .dev = NULL }, // No SPI3 #endif + #ifdef USE_SPI_DEVICE_4 - { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .af = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow } +#if defined(SPI4_SCK_AF) || defined(SPI4_MISO_AF) || defined(SPI4_MOSI_AF) +#if !defined(SPI4_SCK_AF) || !defined(SPI4_MISO_AF) || !defined(SPI4_MOSI_AF) +#error SPI3: SCK, MISO and MOSI AFs should be defined together in target.h! +#endif + { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = SPI4_SCK_AF, .misoAF = SPI4_MISO_AF, .mosiAF = SPI4_MOSI_AF, .divisorMap = spiDivisorMapSlow } +#else + { .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .sckAF = GPIO_AF5_SPI4, .misoAF = GPIO_AF5_SPI4, .mosiAF = GPIO_AF5_SPI4, .divisorMap = spiDivisorMapSlow } +#endif #else { .dev = NULL } // No SPI4 #endif @@ -184,12 +246,13 @@ bool spiInitDevice(SPIDevice device, bool leadingEdge) IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); if (leadingEdge) { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->sckAF); } else { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF); } - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); + IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->misoAF); + + IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->mosiAF); if (spi->nss) { IOInit(IOGetByTag(spi->nss), OWNER_SPI, RESOURCE_SPI_CS, device + 1); diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index c76b49fd1..841404dbc 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -164,7 +164,7 @@ #define SYM_SWITCH_INDICATOR_LOW 0xD0 // 208 Switch High #define SYM_SWITCH_INDICATOR_MID 0xD1 // 209 Switch Mid #define SYM_SWITCH_INDICATOR_HIGH 0xD2 // 210 Switch Low - +#define SYM_AH 0xD3 // 211 Amphours symbol #define SYM_LOGO_START 0x101 // 257 to 280, INAV logo #define SYM_LOGO_WIDTH 6 diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index f9a5b263f..05d31fb02 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -38,6 +38,8 @@ typedef enum portOptions_t { SERIAL_PARITY_EVEN = 1 << 2, SERIAL_UNIDIR = 0 << 3, SERIAL_BIDIR = 1 << 3, + SERIAL_LONGSTOP = 0 << 4, + SERIAL_SHORTSTOP = 1 << 4, /* * Note on SERIAL_BIDIR_PP diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 255087f00..92d89c4c1 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -381,7 +381,9 @@ void processTxState(softSerial_t *softSerial) serialOutputPortActivate(softSerial); } - return; + if ((softSerial->port.options & SERIAL_SHORTSTOP) == 0) { + return; + } } if (softSerial->bitsLeftToTransmit) { @@ -390,7 +392,10 @@ void processTxState(softSerial_t *softSerial) setTxSignal(softSerial, mask); softSerial->bitsLeftToTransmit--; - return; + + if (((softSerial->port.options & SERIAL_SHORTSTOP) == 0) || softSerial->bitsLeftToTransmit) { + return; + } } softSerial->isTransmittingData = false; diff --git a/src/main/drivers/vtx_common.h b/src/main/drivers/vtx_common.h index c83b0aeab..1910075a8 100644 --- a/src/main/drivers/vtx_common.h +++ b/src/main/drivers/vtx_common.h @@ -66,6 +66,12 @@ typedef enum { VTXDEV_UNKNOWN = 0xFF, } vtxDevType_e; +typedef enum { + FREQUENCYGROUP_5G8 = 0, + FREQUENCYGROUP_2G4 = 1, + FREQUENCYGROUP_1G3 = 2, +} vtxFrequencyGroups_e; + struct vtxVTable_s; typedef struct vtxDeviceCapability_s { diff --git a/src/main/fc/config.c b/src/main/fc/config.c index efd1a3129..c916434d0 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -239,7 +239,7 @@ void validateAndFixConfig(void) // Limitations of different protocols #if !defined(USE_DSHOT) if (motorConfig()->motorPwmProtocol > PWM_TYPE_BRUSHED) { - motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD; + motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; } #endif diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index fa56997f7..f1717aa6b 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -131,6 +131,9 @@ tables: - name: vtx_low_power_disarm values: ["OFF", "ON", "UNTIL_FIRST_ARM"] enum: vtxLowerPowerDisarm_e + - name: vtx_frequency_groups + values: ["FREQUENCYGROUP_5G8", "FREQUENCYGROUP_2G4", "FREQUENCYGROUP_1G3"] + enum: vtxFrequencyGroups_e - name: filter_type values: ["PT1", "BIQUAD"] - name: filter_type_full @@ -3516,6 +3519,13 @@ groups: max: 6 default_value: 3 + - name: osd_mah_used_precision + description: Number of digits used to display mAh used. + field: mAh_used_precision + min: 4 + max: 6 + default_value: 4 + - name: osd_switch_indicator_zero_name description: "Character to use for OSD switch incicator 0." field: osd_switch_indicator0_name @@ -3704,6 +3714,11 @@ groups: default_value: ON field: smartAudioAltSoftSerialMethod type: bool + - name: vtx_softserial_shortstop + description: "Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes." + default_value: OFF + field: softSerialShortStop + type: bool - name: PG_VTX_SETTINGS_CONFIG type: vtxSettingsConfig_t @@ -3712,7 +3727,7 @@ groups: members: - name: vtx_band description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." - default_value: 4 + default_value: 1 field: band min: VTX_SETTINGS_NO_BAND max: VTX_SETTINGS_MAX_BAND @@ -3745,6 +3760,13 @@ groups: field: maxPowerOverride min: 0 max: 10000 + - name: vtx_frequency_group + field: frequencyGroup + description: "VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz." + table: vtx_frequency_groups + min: 0 + max: 2 + default_value: FREQUENCYGROUP_5G8 - name: PG_PINIOBOX_CONFIG type: pinioBoxConfig_t diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 3e99afa46..ee4cf4ef5 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -93,16 +93,6 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, .outputMode = SETTING_OUTPUT_MODE_DEFAULT, ); -#ifdef BRUSHED_MOTORS -#define DEFAULT_PWM_PROTOCOL PWM_TYPE_BRUSHED -#define DEFAULT_PWM_RATE 16000 -#else -#define DEFAULT_PWM_PROTOCOL PWM_TYPE_ONESHOT125 -#define DEFAULT_PWM_RATE 400 -#endif - -#define DEFAULT_MAX_THROTTLE 1850 - PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 7575d417a..1ea6d7ef0 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1580,13 +1580,18 @@ static bool osdDrawSingleElement(uint8_t item) } break; - case OSD_MAH_DRAWN: - tfp_sprintf(buff, "%4d", (int)getMAhDrawn()); - buff[4] = SYM_MAH; - buff[5] = '\0'; + case OSD_MAH_DRAWN: { + if (osdFormatCentiNumber(buff, getMAhDrawn() * 100, 1000, 0, (osdConfig()->mAh_used_precision - 2), osdConfig()->mAh_used_precision)) { + // Shown in mAh + buff[osdConfig()->mAh_used_precision] = SYM_AH; + } else { + // Shown in Ah + buff[osdConfig()->mAh_used_precision] = SYM_MAH; + } + buff[(osdConfig()->mAh_used_precision + 1)] = '\0'; osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); break; - + } case OSD_WH_DRAWN: osdFormatCentiNumber(buff, getMWhDrawn() / 10, 0, 2, 0, 3); osdUpdateBatteryCapacityOrVoltageTextAttributes(&elemAttr); @@ -3266,6 +3271,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT, .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT, .esc_rpm_precision = SETTING_OSD_ESC_RPM_PRECISION_DEFAULT, + .mAh_used_precision = SETTING_OSD_MAH_USED_PRECISION_DEFAULT, .osd_switch_indicator0_name = SETTING_OSD_SWITCH_INDICATOR_ZERO_NAME_DEFAULT, .osd_switch_indicator0_channnel = SETTING_OSD_SWITCH_INDICATOR_ZERO_CHANNNEL_DEFAULT, .osd_switch_indicator1_name = SETTING_OSD_SWITCH_INDICATOR_ONE_NAME_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 933b16c1e..56668fb28 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -415,6 +415,7 @@ typedef struct osdConfig_s { uint8_t telemetry; // use telemetry on displayed pixel line 0 uint8_t esc_rpm_precision; // Number of characters used for the RPM numbers. uint16_t system_msg_display_time; // system message display time for multiple messages (ms) + uint8_t mAh_used_precision; // Number of numbers used for mAh drawn. Plently of packs now are > 9999 mAh char osd_switch_indicator0_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 0. uint8_t osd_switch_indicator0_channnel; // RC Channel to use for switch indicator 0. char osd_switch_indicator1_name[OSD_SWITCH_INDICATOR_NAME_LENGTH + 1]; // Name to use for switch indicator 1. diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index c2dce6194..4e986f260 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -202,17 +202,46 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu // Distance - if (((millis() / 1000) % 6 == 0) && poiType > 0) { // For Radar and WPs, display the difference in altitude - altc = ((osd_unit_e)osdConfig()->units == OSD_UNIT_IMPERIAL) ? constrain(CENTIMETERS_TO_FEET(poiAltitude * 100), -99, 99) : constrain(poiAltitude, -99 , 99); + if (((millis() / 1000) % 7 == 0 || (millis() / 1000) % 7 == 1) && poiType > 0) { // For Radar and WPs, display the difference in altitude for 2 seconds, then distance for 5 seconds + altc = constrain(poiAltitude, -99 , 99); + + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_GA: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + // Convert to feet + altc = constrain(CENTIMETERS_TO_FEET(poiAltitude * 100), -99, 99); + break; + default: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + // Already in metres + break; + } + tfp_sprintf(buff, "%3d", altc); buff[0] = (poiAltitude >= 0) ? SYM_DIRECTION : SYM_DIRECTION+4; - } - else { // Display the distance by default - if ((osd_unit_e)osdConfig()->units == OSD_UNIT_IMPERIAL) { - osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3); - } - else { - osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3); + } else { // Display the distance by default + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_MILE, 0, 3, 3); + break; + case OSD_UNIT_GA: + osdFormatCentiNumber(buff, CENTIMETERS_TO_CENTIFEET(poiDistance * 100), FEET_PER_NAUTICALMILE, 0, 3, 3); + break; + default: + FALLTHROUGH; + case OSD_UNIT_METRIC_MPH: + FALLTHROUGH; + case OSD_UNIT_METRIC: + osdFormatCentiNumber(buff, poiDistance * 100, METERS_PER_KILOMETER, 0, 3, 3); + break; } } diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index eabe0d1f0..c7891ce6b 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -53,6 +53,7 @@ PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, .pitModeChan = SETTING_VTX_PIT_MODE_CHAN_DEFAULT, .lowPowerDisarm = SETTING_VTX_LOW_POWER_DISARM_DEFAULT, .maxPowerOverride = SETTING_VTX_MAX_POWER_OVERRIDE_DEFAULT, + .frequencyGroup = SETTING_VTX_FREQUENCY_GROUP_DEFAULT, ); typedef enum { diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index 4bff70af5..1a0fcaac4 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -41,6 +41,7 @@ typedef struct vtxSettingsConfig_s { uint16_t pitModeChan; // sets out-of-range pitmode frequency uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e uint16_t maxPowerOverride; // for VTX drivers that are polling VTX capabilities - override what VTX is reporting + uint8_t frequencyGroup; // Frequencies being used, i.e. 5.8, 2.4, or 1.3 GHz } vtxSettingsConfig_t; PG_DECLARE(vtxSettingsConfig_t, vtxSettingsConfig); diff --git a/src/main/io/vtx_control.c b/src/main/io/vtx_control.c index 516b78ab0..54c550cdc 100644 --- a/src/main/io/vtx_control.c +++ b/src/main/io/vtx_control.c @@ -46,6 +46,7 @@ PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig, .halfDuplex = SETTING_VTX_HALFDUPLEX_DEFAULT, .smartAudioEarlyAkkWorkaroundEnable = SETTING_VTX_SMARTAUDIO_EARLY_AKK_WORKAROUND_DEFAULT, .smartAudioAltSoftSerialMethod = SETTING_VTX_SMARTAUDIO_ALTERNATE_SOFTSERIAL_METHOD_DEFAULT, + .softSerialShortStop = SETTING_VTX_SOFTSERIAL_SHORTSTOP_DEFAULT, ); static uint8_t locked = 0; diff --git a/src/main/io/vtx_control.h b/src/main/io/vtx_control.h index b474a4bc0..639764e4f 100644 --- a/src/main/io/vtx_control.h +++ b/src/main/io/vtx_control.h @@ -33,6 +33,7 @@ typedef struct vtxConfig_s { uint8_t halfDuplex; uint8_t smartAudioEarlyAkkWorkaroundEnable; bool smartAudioAltSoftSerialMethod; + bool softSerialShortStop; } vtxConfig_t; PG_DECLARE(vtxConfig_t, vtxConfig); diff --git a/src/main/io/vtx_string.c b/src/main/io/vtx_string.c index ed75c981b..b86a7ba02 100644 --- a/src/main/io/vtx_string.c +++ b/src/main/io/vtx_string.c @@ -25,11 +25,15 @@ #include "platform.h" #include "build/debug.h" -#define VTX_STRING_BAND_COUNT 5 -#define VTX_STRING_CHAN_COUNT 8 -#define VTX_STRING_POWER_COUNT 5 +#define VTX_STRING_5G8_BAND_COUNT 5 +#define VTX_STRING_5G8_CHAN_COUNT 8 +#define VTX_STRING_5G8_POWER_COUNT 5 -const uint16_t vtx58frequencyTable[VTX_STRING_BAND_COUNT][VTX_STRING_CHAN_COUNT] = +#define VTX_STRING_1G3_BAND_COUNT 2 +#define VTX_STRING_1G3_CHAN_COUNT 8 +#define VTX_STRING_1G3_POWER_COUNT 3 + +const uint16_t vtx58frequencyTable[VTX_STRING_5G8_BAND_COUNT][VTX_STRING_5G8_CHAN_COUNT] = { { 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 }, // A { 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 }, // B @@ -38,7 +42,7 @@ const uint16_t vtx58frequencyTable[VTX_STRING_BAND_COUNT][VTX_STRING_CHAN_COUNT] { 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 }, // R }; -const char * const vtx58BandNames[VTX_STRING_BAND_COUNT + 1] = { +const char * const vtx58BandNames[VTX_STRING_5G8_BAND_COUNT + 1] = { "-", "A", "B", @@ -47,16 +51,38 @@ const char * const vtx58BandNames[VTX_STRING_BAND_COUNT + 1] = { "R", }; -const char vtx58BandLetter[VTX_STRING_BAND_COUNT + 1] = "-ABEFR"; +const char vtx58BandLetter[VTX_STRING_5G8_BAND_COUNT + 1] = "-ABEFR"; -const char * const vtx58ChannelNames[VTX_STRING_CHAN_COUNT + 1] = { +const char * const vtx58ChannelNames[VTX_STRING_5G8_CHAN_COUNT + 1] = { "-", "1", "2", "3", "4", "5", "6", "7", "8", }; -const char * const vtx58DefaultPowerNames[VTX_STRING_POWER_COUNT + 1] = { +const char * const vtx58DefaultPowerNames[VTX_STRING_5G8_POWER_COUNT + 1] = { "---", "PL1", "PL2", "PL3", "PL4", "PL5" }; +const uint16_t vtx1G3frequencyTable[VTX_STRING_1G3_BAND_COUNT][VTX_STRING_1G3_CHAN_COUNT] = +{ + { 1080, 1120, 1160, 1200, 1240, 1280, 1320, 1360 }, // A + { 1080, 1120, 1160, 1200, 1258, 1280, 1320, 1360 }, // B +}; + +const char * const vtx1G3BandNames[VTX_STRING_1G3_BAND_COUNT + 1] = { + "-", + "A", + "B", +}; + +const char vtx1G3BandLetter[VTX_STRING_1G3_BAND_COUNT + 1] = "-AB"; + +const char * const vtx1G3ChannelNames[VTX_STRING_1G3_CHAN_COUNT + 1] = { + "-", "1", "2", "3", "4", "5", "6", "7", "8", +}; + +const char * const vtx1G3DefaultPowerNames[VTX_STRING_1G3_POWER_COUNT + 1] = { + "---", "PL1", "PL2", "PL3" +}; + bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel) { int8_t band; @@ -80,15 +106,28 @@ bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel) return false; } -//Converts band and channel values to a frequency (in MHz) value. +// Converts band and channel values to a frequency (in MHz) value. // band: Band value (1 to 5). // channel: Channel value (1 to 8). // Returns frequency value (in MHz), or 0 if band/channel out of range. uint16_t vtx58_Bandchan2Freq(uint8_t band, uint8_t channel) { - if (band > 0 && band <= VTX_STRING_BAND_COUNT && - channel > 0 && channel <= VTX_STRING_CHAN_COUNT) { + if (band > 0 && band <= VTX_STRING_5G8_BAND_COUNT && + channel > 0 && channel <= VTX_STRING_5G8_CHAN_COUNT) { return vtx58frequencyTable[band - 1][channel - 1]; } return 0; } + +// Converts band and channel values to a frequency (in MHz) value. +// band: Band value (1 to 2). +// channel: Channel value (1 to 8). +// Returns frequency value (in MHz), or 0 if band/channel out of range. +uint16_t vtx1G3_Bandchan2Freq(uint8_t band, uint8_t channel) +{ + if (band > 0 && band <= VTX_STRING_1G3_BAND_COUNT && + channel > 0 && channel <= VTX_STRING_1G3_CHAN_COUNT) { + return vtx1G3frequencyTable[band - 1][channel - 1]; + } + return 0; +} diff --git a/src/main/io/vtx_string.h b/src/main/io/vtx_string.h index cb63cbe7a..e23990ec7 100644 --- a/src/main/io/vtx_string.h +++ b/src/main/io/vtx_string.h @@ -8,5 +8,12 @@ extern const char * const vtx58ChannelNames[]; extern const char * const vtx58DefaultPowerNames[]; extern const char vtx58BandLetter[]; +extern const uint16_t vtx1G3frequencyTable[2][8]; +extern const char * const vtx1G3BandNames[]; +extern const char * const vtx1G3ChannelNames[]; +extern const char * const vtx1G3DefaultPowerNames[]; +extern const char vtx51G3BandLetter[]; + bool vtx58_Freq2Bandchan(uint16_t freq, uint8_t *pBand, uint8_t *pChannel); uint16_t vtx58_Bandchan2Freq(uint8_t band, uint8_t channel); +uint16_t vtx1G3_Bandchan2Freq(uint8_t band, uint8_t channel); diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 7e5012211..2791ada29 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -407,8 +407,12 @@ static void impl_SetBandAndChannel(vtxDevice_t * vtxDevice, uint8_t band, uint8_ return; } - // TRAMP is 5.8 GHz only - uint16_t newFreqMhz = vtx58_Bandchan2Freq(band, channel); + // Default to 5.8 GHz + uint16_t newFreqMhz = vtx58_Bandchan2Freq(band, channel); + + if (vtxSettingsConfig()->frequencyGroup == FREQUENCYGROUP_1G3) { + newFreqMhz = vtx1G3_Bandchan2Freq(band, channel); + } if (newFreqMhz < vtxState.capabilities.freqMin || newFreqMhz > vtxState.capabilities.freqMax) { return; @@ -512,9 +516,20 @@ static bool impl_GetOsdInfo(const vtxDevice_t *vtxDevice, vtxDeviceOsdInfo_t * pOsdInfo->frequency = vtxState.request.freq; pOsdInfo->powerIndex = vtxState.request.powerIndex; pOsdInfo->powerMilliwatt = vtxState.request.power; - pOsdInfo->bandLetter = vtx58BandNames[vtxState.request.band][0]; - pOsdInfo->bandName = vtx58BandNames[vtxState.request.band]; - pOsdInfo->channelName = vtx58ChannelNames[vtxState.request.channel]; + + switch (vtxSettingsConfig()->frequencyGroup) { + case FREQUENCYGROUP_1G3: + pOsdInfo->bandLetter = vtx1G3BandNames[vtxState.request.band][0]; + pOsdInfo->bandName = vtx1G3BandNames[vtxState.request.band]; + pOsdInfo->channelName = vtx1G3ChannelNames[vtxState.request.channel]; + break; + default: // Currently all except 1.3GHz + pOsdInfo->bandLetter = vtx58BandNames[vtxState.request.band][0]; + pOsdInfo->bandName = vtx58BandNames[vtxState.request.band]; + pOsdInfo->channelName = vtx58ChannelNames[vtxState.request.channel]; + break; + } + pOsdInfo->powerIndexLetter = '0' + vtxState.request.powerIndex; return true; } @@ -539,67 +554,85 @@ static vtxDevice_t impl_vtxDevice = { .vTable = &impl_vtxVTable, .capability.bandCount = VTX_TRAMP_5G8_BAND_COUNT, .capability.channelCount = VTX_TRAMP_5G8_CHANNEL_COUNT, - .capability.powerCount = VTX_TRAMP_MAX_POWER_COUNT, + .capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT, .capability.bandNames = (char **)vtx58BandNames, .capability.channelNames = (char **)vtx58ChannelNames, .capability.powerNames = NULL, }; -const uint16_t trampPowerTable_200[VTX_TRAMP_MAX_POWER_COUNT] = { 25, 100, 200, 200, 200 }; -const char * const trampPowerNames_200[VTX_TRAMP_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "200", "200" }; +const uint16_t trampPowerTable_5G8_200[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 200, 200 }; +const char * const trampPowerNames_5G8_200[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "200", "200" }; + +const uint16_t trampPowerTable_5G8_400[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 400, 400 }; +const char * const trampPowerNames_5G8_400[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "400" }; -const uint16_t trampPowerTable_400[VTX_TRAMP_MAX_POWER_COUNT] = { 25, 100, 200, 400, 400 }; -const char * const trampPowerNames_400[VTX_TRAMP_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "400" }; +const uint16_t trampPowerTable_5G8_600[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 400, 600 }; +const char * const trampPowerNames_5G8_600[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "600" }; -const uint16_t trampPowerTable_600[VTX_TRAMP_MAX_POWER_COUNT] = { 25, 100, 200, 400, 600 }; -const char * const trampPowerNames_600[VTX_TRAMP_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "400", "600" }; +const uint16_t trampPowerTable_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT] = { 25, 100, 200, 500, 800 }; +const char * const trampPowerNames_5G8_800[VTX_TRAMP_5G8_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "500", "800" }; -const uint16_t trampPowerTable_800[VTX_TRAMP_MAX_POWER_COUNT] = { 25, 100, 200, 500, 800 }; -const char * const trampPowerNames_800[VTX_TRAMP_MAX_POWER_COUNT + 1] = { "---", "25 ", "100", "200", "500", "800" }; +const uint16_t trampPowerTable_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT] = { 25, 200, 800 }; +const char * const trampPowerNames_1G3_800[VTX_TRAMP_1G3_MAX_POWER_COUNT + 1] = { "---", "25 ", "200", "800" }; static void vtxProtoUpdatePowerMetadata(uint16_t maxPower) { - if (maxPower >= 800) { - // Max power 800mW: Use 25, 100, 200, 500, 800 table - vtxState.metadata.powerTablePtr = trampPowerTable_800; - vtxState.metadata.powerTableCount = VTX_TRAMP_MAX_POWER_COUNT; - - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_800; - impl_vtxDevice.capability.powerCount = VTX_TRAMP_MAX_POWER_COUNT; - } - else if (maxPower >= 600) { - // Max power 600mW: Use 25, 100, 200, 400, 600 table - vtxState.metadata.powerTablePtr = trampPowerTable_600; - vtxState.metadata.powerTableCount = VTX_TRAMP_MAX_POWER_COUNT; + switch (vtxSettingsConfig()->frequencyGroup) { + case FREQUENCYGROUP_1G3: + vtxState.metadata.powerTablePtr = trampPowerTable_1G3_800; + vtxState.metadata.powerTableCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_1G3_800; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_1G3_MAX_POWER_COUNT; + + impl_vtxDevice.capability.bandCount = VTX_TRAMP_1G3_BAND_COUNT; + impl_vtxDevice.capability.channelCount = VTX_TRAMP_1G3_CHANNEL_COUNT; + impl_vtxDevice.capability.bandNames = (char **)vtx1G3BandNames; + impl_vtxDevice.capability.channelNames = (char **)vtx1G3ChannelNames; + break; + default: + if (maxPower >= 800) { + // Max power 800mW: Use 25, 100, 200, 500, 800 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_800; + vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_800; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + } + else if (maxPower >= 600) { + // Max power 600mW: Use 25, 100, 200, 400, 600 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_600; + vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_600; - impl_vtxDevice.capability.powerCount = VTX_TRAMP_MAX_POWER_COUNT; - } - else if (maxPower >= 400) { - // Max power 400mW: Use 25, 100, 200, 400 table - vtxState.metadata.powerTablePtr = trampPowerTable_400; - vtxState.metadata.powerTableCount = 4; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_600; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + } + else if (maxPower >= 400) { + // Max power 400mW: Use 25, 100, 200, 400 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_400; + vtxState.metadata.powerTableCount = 4; - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_400; - impl_vtxDevice.capability.powerCount = 4; - } - else if (maxPower >= 200) { - // Max power 200mW: Use 25, 100, 200 table - vtxState.metadata.powerTablePtr = trampPowerTable_200; - vtxState.metadata.powerTableCount = 3; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_400; + impl_vtxDevice.capability.powerCount = 4; + } + else if (maxPower >= 200) { + // Max power 200mW: Use 25, 100, 200 table + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_200; + vtxState.metadata.powerTableCount = 3; - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_200; - impl_vtxDevice.capability.powerCount = 3; - } - else { - // Default to standard TRAMP 600mW VTX - vtxState.metadata.powerTablePtr = trampPowerTable_600; - vtxState.metadata.powerTableCount = VTX_TRAMP_MAX_POWER_COUNT; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_200; + impl_vtxDevice.capability.powerCount = 3; + } + else { + // Default to standard TRAMP 600mW VTX + vtxState.metadata.powerTablePtr = trampPowerTable_5G8_600; + vtxState.metadata.powerTableCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; - impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_600; - impl_vtxDevice.capability.powerCount = VTX_TRAMP_MAX_POWER_COUNT; + impl_vtxDevice.capability.powerNames = (char **)trampPowerNames_5G8_600; + impl_vtxDevice.capability.powerCount = VTX_TRAMP_5G8_MAX_POWER_COUNT; + } + break; } - } bool vtxTrampInit(void) @@ -609,6 +642,7 @@ bool vtxTrampInit(void) if (portConfig) { portOptions_t portOptions = 0; portOptions = portOptions | (vtxConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR); + portOptions = portOptions | (vtxConfig()->softSerialShortStop ? SERIAL_SHORTSTOP : SERIAL_LONGSTOP); vtxState.port = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, NULL, 9600, MODE_RXTX, portOptions); } diff --git a/src/main/io/vtx_tramp.h b/src/main/io/vtx_tramp.h index 3d2643c19..1f4420185 100644 --- a/src/main/io/vtx_tramp.h +++ b/src/main/io/vtx_tramp.h @@ -19,13 +19,24 @@ #include +// 5.8 GHz #define VTX_TRAMP_5G8_BAND_COUNT 5 #define VTX_TRAMP_5G8_CHANNEL_COUNT 8 -#define VTX_TRAMP_MAX_POWER_COUNT 5 -#define VTX_TRAMP_DEFAULT_POWER 1 +#define VTX_TRAMP_5G8_MAX_POWER_COUNT 5 +#define VTX_TRAMP_5G8_DEFAULT_POWER 1 -#define VTX_TRAMP_MIN_FREQUENCY_MHZ 5000 //min freq in MHz -#define VTX_TRAMP_MAX_FREQUENCY_MHZ 5999 //max freq in MHz +#define VTX_TRAMP_5G8_MIN_FREQUENCY_MHZ 5000 //min freq in MHz +#define VTX_TRAMP_5G8_MAX_FREQUENCY_MHZ 5999 //max freq in MHz + +// 1.3 GHz +#define VTX_TRAMP_1G3_BAND_COUNT 2 +#define VTX_TRAMP_1G3_CHANNEL_COUNT 8 + +#define VTX_TRAMP_1G3_MAX_POWER_COUNT 3 +#define VTX_TRAMP_1G3_DEFAULT_POWER 1 + +#define VTX_TRAMP_1G3_MIN_FREQUENCY_MHZ 1000 +#define VTX_TRAMP_1G3_MAX_FREQUENCY_MHZ 1399 bool vtxTrampInit(void); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 9abf846e6..f5201ccf8 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3200,13 +3200,9 @@ static void processNavigationRCAdjustments(void) } if (navStateFlags & NAV_RC_POS) { - if (!FLIGHT_MODE(FAILSAFE_MODE)) { - posControl.flags.isAdjustingPosition = adjustPositionFromRCInput(); - } - else { - if (!STATE(FIXED_WING_LEGACY)) { - resetMulticopterBrakingMode(); - } + posControl.flags.isAdjustingPosition = adjustPositionFromRCInput() && !FLIGHT_MODE(FAILSAFE_MODE); + if (STATE(MULTIROTOR) && FLIGHT_MODE(FAILSAFE_MODE)) { + resetMulticopterBrakingMode(); } } else { diff --git a/src/main/target/AOCODARCF7DUAL/CMakeLists.txt b/src/main/target/AOCODARCF7DUAL/CMakeLists.txt new file mode 100644 index 000000000..ca0b580d5 --- /dev/null +++ b/src/main/target/AOCODARCF7DUAL/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(AOCODARCF7DUAL) diff --git a/src/main/target/AOCODARCF7DUAL/target.c b/src/main/target/AOCODARCF7DUAL/target.c new file mode 100644 index 000000000..d4c4143be --- /dev/null +++ b/src/main/target/AOCODARCF7DUAL/target.c @@ -0,0 +1,50 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6000_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_bmi270, DEVHW_BMI270, BMI270_SPI_BUS, BMI270_CS_PIN, BMI270_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_BMI270_ALIGN); + + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH3, PA10, TIM_USE_PPM, 0, 0), //PPM + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S1 D(2, 2, 7) + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S2 D(2, 3, 7) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // S3 D(2, 4, 7) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4 D(2, 7, 7) + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S5 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S6 D(1, 2, 5) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S7 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR |TIM_USE_FW_SERVO, 0, 0), // S8 D(1, 3, 2) + + DEF_TIM(TIM2, CH1, PA0, TIM_USE_LED, 0, 0), // LED_TRIP +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/AOCODARCF7DUAL/target.h b/src/main/target/AOCODARCF7DUAL/target.h new file mode 100644 index 000000000..25d618c5a --- /dev/null +++ b/src/main/target/AOCODARCF7DUAL/target.h @@ -0,0 +1,182 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "AO7D" +#define USBD_PRODUCT_STRING "AocodaRCF7Dual" + + +#define LED0 PC14 //Blue + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* +#define USE_SPI +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_EXTI +#define USE_DUAL_GYRO +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_BUS BUS_SPI2 +#define MPU6000_EXTI_PIN PC4 + +#define USE_IMU_MPU6500 +#define IMU_MPU6500_ALIGN CW270_DEG +#define MPU6500_CS_PIN PB12 +#define MPU6500_SPI_BUS BUS_SPI2 +#define MPU6500_EXTI_PIN PC4 + +#define USE_IMU_BMI270 +#define IMU_BMI270_ALIGN CW180_DEG +#define BMI270_CS_PIN PA13 +#define BMI270_SPI_BUS BUS_SPI2 +#define BMI270_EXTI_PIN PA8 + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_MS5607 +#define USE_BARO_DPS310 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 + +#define PITOT_I2C_BUS BUS_I2C2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +// *************** SPI2 OSD *********************** +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI1 +#define MAX7456_CS_PIN PA4 + +// *************** SPI3 FLASH BLACKBOX******************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PC0 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC15 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PC10 +#define UART3_RX_PIN PC11 + +#define USE_UART4 +#define UART4_TX_PIN NONE +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC1 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC3 + + +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA0 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 650 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 10 +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/CMakeLists.txt b/src/main/target/IFLIGHT_H743_AIO_V2/CMakeLists.txt new file mode 100644 index 000000000..66f1731aa --- /dev/null +++ b/src/main/target/IFLIGHT_H743_AIO_V2/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(IFLIGHT_H743_AIO_V2 SKIP_RELEASES) diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/config.c b/src/main/target/IFLIGHT_H743_AIO_V2/config.c new file mode 100644 index 000000000..8ec9f1384 --- /dev/null +++ b/src/main/target/IFLIGHT_H743_AIO_V2/config.c @@ -0,0 +1,26 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include "platform.h" +#include "fc/fc_msp_box.h" +#include "fc/config.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ +} diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/target.c b/src/main/target/IFLIGHT_H743_AIO_V2/target.c new file mode 100644 index 000000000..3e02bff3e --- /dev/null +++ b/src/main/target/IFLIGHT_H743_AIO_V2/target.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // M2 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // M3 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 3), // M4 + + DEF_TIM( TIM1, CH1, PA8, TIM_USE_LED, 0, 4) // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_H743_AIO_V2/target.h b/src/main/target/IFLIGHT_H743_AIO_V2/target.h new file mode 100644 index 000000000..c023f3fe3 --- /dev/null +++ b/src/main/target/IFLIGHT_H743_AIO_V2/target.h @@ -0,0 +1,177 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "IF7A" +#define USBD_PRODUCT_STRING "IFLIGHT_H743_AIO_V2" + +#define LED0 PC13 + +#define BEEPER_PIN PD2 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA4 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PD0 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +// *************** I2C1 Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +//UUART3 +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +// + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define BNO055_I2C_BUS BUS_I2C2 +#define PITOT_I2C_BUS BUS_I2C2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +// *************** SPI2 *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define SPI2_NSS_PIN PB12 + +// *************** SPI3 BLACKBOX ******************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 +#define SPI3_NSS_PIN PA15 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** SPI4 OSD ******************* +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 +#define SPI4_NSS_PIN PE4 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI4 +#define MAX7456_CS_PIN SPI4_NSS_PIN + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define USE_UART7 +#define UART7_RX_PIN PE7 +#define UART7_TX_PIN PE8 + +#define USE_UART8 +#define UART8_RX_PIN PE0 +#define UART8_TX_PIN PE1 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART4 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC3 + +#define ADC_CHANNEL_1_PIN PC3 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC5 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 100 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 4 +#define USE_DSHOT +#define USE_ESC_SENSOR diff --git a/src/main/target/JHEH7AIO/CMakeLists.txt b/src/main/target/JHEH7AIO/CMakeLists.txt new file mode 100644 index 000000000..b5fc68d4f --- /dev/null +++ b/src/main/target/JHEH7AIO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32h743xi(JHEH7AIO SKIP_RELEASES) diff --git a/src/main/target/JHEH7AIO/config.c b/src/main/target/JHEH7AIO/config.c new file mode 100644 index 000000000..8ec9f1384 --- /dev/null +++ b/src/main/target/JHEH7AIO/config.c @@ -0,0 +1,26 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include "platform.h" +#include "fc/fc_msp_box.h" +#include "fc/config.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ +} diff --git a/src/main/target/JHEH7AIO/target.c b/src/main/target/JHEH7AIO/target.c new file mode 100644 index 000000000..479816acd --- /dev/null +++ b/src/main/target/JHEH7AIO/target.c @@ -0,0 +1,38 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 1), // M2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 2), // M3 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 3), // M4 + + DEF_TIM( TIM4, CH1, PD12, TIM_USE_LED, 0, 4) // LED_2812 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); \ No newline at end of file diff --git a/src/main/target/JHEH7AIO/target.h b/src/main/target/JHEH7AIO/target.h new file mode 100644 index 000000000..fe16fa07c --- /dev/null +++ b/src/main/target/JHEH7AIO/target.h @@ -0,0 +1,175 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#pragma once + +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "JH7A" +#define USBD_PRODUCT_STRING "JHEH743AIO" + +#define LED0 PC13 + +#define BEEPER_PIN PD15 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN PA4 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PD0 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +// *************** I2C1 Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define BNO055_I2C_BUS BUS_I2C1 +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** SPI2 *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define SPI2_NSS_PIN PB12 + +// *************** SPI3 BLACKBOX ******************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 +#define SPI3_NSS_PIN PA15 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN SPI3_NSS_PIN +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** SPI4 OSD ******************* +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 +#define SPI4_NSS_PIN PE4 + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI4 +#define MAX7456_CS_PIN SPI4_NSS_PIN + +// *************** UART ***************************** +#define USE_VCP + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define USE_UART7 +#define UART7_RX_PIN PE7 +#define UART7_TX_PIN PE8 + +#define USE_UART8 +#define UART8_RX_PIN PE0 +#define UART8_TX_PIN PE1 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC3 + +#define ADC_CHANNEL_1_PIN PC3 +#define ADC_CHANNEL_2_PIN PC2 +#define ADC_CHANNEL_3_PIN PC5 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PD12 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 100 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 4 +#define USE_DSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/KAKUTEH7/target.c b/src/main/target/KAKUTEH7/target.c index be6402a63..086d941f1 100644 --- a/src/main/target/KAKUTEH7/target.c +++ b/src/main/target/KAKUTEH7/target.c @@ -33,12 +33,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S1 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S2 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 6), // S3 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 7), // S4 + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 7), // S8 - DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 8), // LED_2812 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 9), // LED_2812 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/MAMBAF722_2022A/target.c b/src/main/target/MAMBAF722_2022A/target.c index afe6e3635..56f5483cb 100644 --- a/src/main/target/MAMBAF722_2022A/target.c +++ b/src/main/target/MAMBAF722_2022A/target.c @@ -32,10 +32,10 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S3 DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1 ), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S6 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S7 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0 ), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S6 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S7 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0 ), // S8 DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3) }; diff --git a/src/main/target/MAMBAH743/target.c b/src/main/target/MAMBAH743/target.c index 9802d0581..909df49a0 100644 --- a/src/main/target/MAMBAH743/target.c +++ b/src/main/target/MAMBAH743/target.c @@ -36,12 +36,12 @@ timerHardware_t timerHardware[] = { DEF_TIM(TIM5, CH3, PA2, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // S3 DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 3), // S4 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 4), // S5 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 5), // S6 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 6), // S7 - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 7), // S8 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 4), // S5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 5), // S6 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 6), // S7 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 7), // S8 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 8), // LED_2812 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 9), // LED_2812 }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/TMOTORF7V2/target.h b/src/main/target/TMOTORF7V2/target.h index 6e9fc6dd3..d94412179 100644 --- a/src/main/target/TMOTORF7V2/target.h +++ b/src/main/target/TMOTORF7V2/target.h @@ -86,6 +86,9 @@ #define SPI3_SCK_PIN PC10 #define SPI3_MISO_PIN PC11 #define SPI3_MOSI_PIN PB2 +#define SPI3_SCK_AF GPIO_AF6_SPI3 +#define SPI3_MISO_AF GPIO_AF6_SPI3 +#define SPI3_MOSI_AF GPIO_AF7_SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16