Skip to content

Commit

Permalink
Merge branch 'master' into MrD_Set-OSD-elements-precision
Browse files Browse the repository at this point in the history
  • Loading branch information
MrD-RC committed Oct 25, 2024
2 parents 16746b8 + d98756b commit 5383262
Show file tree
Hide file tree
Showing 12 changed files with 394 additions and 35 deletions.
8 changes: 8 additions & 0 deletions readme.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,11 @@
# INAV 8.0 feature freeze

It is that time of the year again, and the time for a new INAV release is near!

The current plan is to have a feature freeze on **15th of November 2024**.

For a preview of what is comming, have a look at ![milestone 8.0](https://github.com/iNavFlight/inav/milestone/43).

# INAV - navigation capable flight controller

# F411 PSA
Expand Down
134 changes: 103 additions & 31 deletions src/main/drivers/serial_uart_at32f43x.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,28 +36,37 @@ typedef struct uartDevice_s {
usart_type* dev;
uartPort_t port;
ioTag_t rx;
uint8_t rx_af;
ioTag_t tx;
uint8_t tx_af;
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
uint32_t rcc_ahb1;
rccPeriphTag_t rcc_apb2;
rccPeriphTag_t rcc_apb1;
uint8_t af;
uint8_t irq;
uint32_t irqPriority;
bool pinSwap;
} uartDevice_t;

#ifdef USE_UART1
static uartDevice_t uart1 =
{
static uartDevice_t uart1 = {
.dev = USART1,
.rx = IO_TAG(UART1_RX_PIN),
.tx = IO_TAG(UART1_TX_PIN),
#ifdef UART1_AF
.af = CONCAT(GPIO_MUX_, UART1_AF),
#if defined(UART1_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART1_RX_AF),
#elif defined(UART1_AF)
.rx_af = CONCAT(GPIO_MUX_, UART1_AF),
#else
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART1_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART1_TX_AF),
#elif defined(UART1_AF)
.tx_af = CONCAT(GPIO_MUX_, UART1_AF),
#else
.af = GPIO_MUX_7,
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART1_AHB1_PERIPHERALS
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
Expand All @@ -79,10 +88,19 @@ static uartDevice_t uart2 =
.dev = USART2,
.rx = IO_TAG(UART2_RX_PIN),
.tx = IO_TAG(UART2_TX_PIN),
#ifdef UART2_AF
.af = CONCAT(GPIO_MUX_, UART2_AF),
#if defined(UART2_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART2_RX_AF),
#elif defined(UART2_AF)
.rx_af = CONCAT(GPIO_MUX_, UART2_AF),
#else
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART2_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART2_TX_AF),
#elif defined(UART2_AF)
.tx_af = CONCAT(GPIO_MUX_, UART2_AF),
#else
.af = GPIO_MUX_7,
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART2_AHB1_PERIPHERALS
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
Expand All @@ -104,10 +122,19 @@ static uartDevice_t uart3 =
.dev = USART3,
.rx = IO_TAG(UART3_RX_PIN),
.tx = IO_TAG(UART3_TX_PIN),
#ifdef UART3_AF
.af = CONCAT(GPIO_MUX_, UART3_AF),
#if defined(UART3_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART3_RX_AF),
#elif defined(UART3_AF)
.rx_af = CONCAT(GPIO_MUX_, UART3_AF),
#else
.af = GPIO_MUX_7,
.rx_af = GPIO_MUX_7,
#endif
#if defined(UART3_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART3_TX_AF),
#elif defined(UART3_AF)
.tx_af = CONCAT(GPIO_MUX_, UART3_AF),
#else
.tx_af = GPIO_MUX_7,
#endif
#ifdef UART3_AHB1_PERIPHERALS
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
Expand All @@ -129,10 +156,19 @@ static uartDevice_t uart4 =
.dev = UART4,
.rx = IO_TAG(UART4_RX_PIN),
.tx = IO_TAG(UART4_TX_PIN),
#ifdef UART4_AF
.af = CONCAT(GPIO_MUX_, UART4_AF),
#if defined(UART4_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART4_RX_AF),
#elif defined(UART4_AF)
.rx_af = CONCAT(GPIO_MUX_, UART4_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART4_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART4_TX_AF),
#elif defined(UART4_AF)
.tx_af = CONCAT(GPIO_MUX_, UART4_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART4_AHB1_PERIPHERALS
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
Expand All @@ -154,10 +190,19 @@ static uartDevice_t uart5 =
.dev = UART5,
.rx = IO_TAG(UART5_RX_PIN),
.tx = IO_TAG(UART5_TX_PIN),
#ifdef UART5_AF
.af = CONCAT(GPIO_MUX_, UART5_AF),
#if defined(UART5_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART5_RX_AF),
#elif defined(UART5_AF)
.rx_af = CONCAT(GPIO_MUX_, UART5_AF),
#else
.af = GPIO_MUX_8,
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART5_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART5_TX_AF),
#elif defined(UART5_AF)
.tx_af = CONCAT(GPIO_MUX_, UART5_AF),
#else
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART5_AHB1_PERIPHERALS
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
Expand All @@ -179,10 +224,19 @@ static uartDevice_t uart6 =
.dev = USART6,
.rx = IO_TAG(UART6_RX_PIN),
.tx = IO_TAG(UART6_TX_PIN),
#ifdef UART6_AF
.af = CONCAT(GPIO_MUX_, UART6_AF),
#if defined(UART6_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART6_RX_AF),
#elif defined(UART6_AF)
.rx_af = CONCAT(GPIO_MUX_, UART6_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART6_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART6_TX_AF),
#elif defined(UART6_AF)
.tx_af = CONCAT(GPIO_MUX_, UART6_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
#ifdef UART6_AHB1_PERIPHERALS
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
Expand All @@ -204,10 +258,19 @@ static uartDevice_t uart7 =
.dev = UART7,
.rx = IO_TAG(UART7_RX_PIN),
.tx = IO_TAG(UART7_TX_PIN),
#ifdef UART7_AF
.af = CONCAT(GPIO_MUX_, UART7_AF),
#if defined(UART7_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART7_RX_AF),
#elif defined(UART7_AF)
.rx_af = CONCAT(GPIO_MUX_, UART7_AF),
#else
.af = GPIO_MUX_8,
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART7_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART7_TX_AF),
#elif defined(UART7_AF)
.tx_af = CONCAT(GPIO_MUX_, UART7_AF),
#else
.tx_af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART7),
.irq = UART7_IRQn,
Expand All @@ -226,10 +289,19 @@ static uartDevice_t uart8 =
.dev = UART8,
.rx = IO_TAG(UART8_RX_PIN),
.tx = IO_TAG(UART8_TX_PIN),
#ifdef UART8_AF
.af = CONCAT(GPIO_MUX_, UART8_AF),
#if defined(UART8_RX_AF)
.rx_af = CONCAT(GPIO_MUX_, UART8_RX_AF),
#elif defined(UART8_AF)
.rx_af = CONCAT(GPIO_MUX_, UART8_AF),
#else
.rx_af = GPIO_MUX_8,
#endif
#if defined(UART8_TX_AF)
.tx_af = CONCAT(GPIO_MUX_, UART8_TX_AF),
#elif defined(UART8_AF)
.tx_af = CONCAT(GPIO_MUX_, UART8_AF),
#else
.af = GPIO_MUX_8,
.tx_af = GPIO_MUX_8,
#endif
.rcc_apb1 = RCC_APB1(UART8),
.irq = UART8_IRQn,
Expand Down Expand Up @@ -389,22 +461,22 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode,
if (options & SERIAL_BIDIR) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
if (options & SERIAL_BIDIR_PP) {
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->tx_af);
} else {
IOConfigGPIOAF(tx,
(options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_OD : IOCFG_AF_OD_UP,
uart->af);
uart->tx_af);
}
}
else {
if (mode & MODE_TX) {
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->rx_af);
}

if (mode & MODE_RX) {
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->rx_af);
}
}

Expand Down
12 changes: 12 additions & 0 deletions src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1674,6 +1674,18 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
}
break;

case MSP2_INAV_ESC_TELEM:
{
uint8_t motorCount = getMotorCount();
sbufWriteU8(dst, motorCount);

for (uint8_t i = 0; i < motorCount; i++){
const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry
sbufWriteDataSafe(dst, escState, sizeof(escSensorData_t));
}
}
break;
#endif

#ifdef USE_EZ_TUNE
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ tables:
values: ["GENERIC", "ELRS", "SIK"]
enum: mavlinkRadio_e
- name: default_altitude_source
values: ["GPS", "BARO", "GPS ONLY", "BARO ONLY"]
values: ["GPS", "BARO", "GPS_ONLY", "BARO_ONLY"]
enum: navDefaultAltitudeSensor_e

constants:
Expand Down
4 changes: 2 additions & 2 deletions src/main/io/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -4793,7 +4793,7 @@ uint8_t drawStat_UsedEnergy(uint8_t col, uint8_t row, uint8_t statValX)
strcat(buff, "/");
osdFormatCentiNumber(preBuff, getMWhDrawn() / 10, 0, 2, 0, 3, false);
strcat(buff, osdFormatTrimWhiteSpace(preBuff));
tfp_sprintf(buff + strlen(buff), "%s%c", buff, SYM_WH);
tfp_sprintf(buff + strlen(buff), "%c", SYM_WH);
}
displayWrite(osdDisplayPort, statValX, row++, buff);

Expand Down Expand Up @@ -4855,7 +4855,7 @@ uint8_t drawStat_AverageEfficiency(uint8_t col, uint8_t row, uint8_t statValX, b
osdFormatCentiNumber(buff, (int32_t)((getMWhDrawn() - stats.flightStartMWh) * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false);
strcat(outBuff, osdFormatTrimWhiteSpace(buff));
strcat(outBuff, "/");
osdFormatCentiNumber(buff + strlen(buff), (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false);
osdFormatCentiNumber(buff, (int32_t)(getMWhDrawn() * 10.0f * METERS_PER_MILE / totalDistance), 0, 2, 0, digits, false);
strcat(outBuff, osdFormatTrimWhiteSpace(buff));
} else {
strcat(outBuff, "---/---");
Expand Down
1 change: 1 addition & 0 deletions src/main/msp/msp_protocol_v2_inav.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,7 @@
#define MSP2_INAV_LOGIC_CONDITIONS_SINGLE 0x203B

#define MSP2_INAV_ESC_RPM 0x2040
#define MSP2_INAV_ESC_TELEM 0x2041

#define MSP2_INAV_LED_STRIP_CONFIG_EX 0x2048
#define MSP2_INAV_SET_LED_STRIP_CONFIG_EX 0x2049
Expand Down
2 changes: 2 additions & 0 deletions src/main/target/NEUTRONRCF435MINI/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,9 @@

#define USE_UART2
#define UART2_RX_PIN PB0
#define UART2_RX_AF 6
#define UART2_TX_PIN PA2
#define UART2_TX_AF 7

#define USE_UART3
#define USE_UART3_PIN_SWAP
Expand Down
1 change: 1 addition & 0 deletions src/main/target/PRINCIPIOTF7/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
target_stm32f722xe(PRINCIPIOTF7)
32 changes: 32 additions & 0 deletions src/main/target/PRINCIPIOTF7/config.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*
* This target has been autgenerated by bf2inav.py
*/

#include <stdint.h>

#include "platform.h"

#include "fc/fc_msp_box.h"
#include "fc/config.h"

#include "io/piniobox.h"

void targetConfiguration(void)
{

}
Loading

0 comments on commit 5383262

Please sign in to comment.