From e92af8f08d4a31d543c6d27bb2ec669658074443 Mon Sep 17 00:00:00 2001 From: Jeff Hendrix Date: Thu, 26 Sep 2024 11:52:45 -0600 Subject: [PATCH 1/8] Add MSP command to get ESC telemetry --- src/main/fc/fc_msp.c | 12 ++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 1 + 2 files changed, 13 insertions(+) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index f82f3cbaeaf..784e14405dc 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -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 diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 02c8c979aae..465f5098536 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -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 From 8d6c2e7b5ea58f2092abcc64c0614a4e8c9a0ae5 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 14 Oct 2024 19:53:05 +0100 Subject: [PATCH 2/8] Update settings.yaml --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e43ad233b0c..2f5ef09d77d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -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: From a1cd050f00d2c9924b6b6447152192819b89b601 Mon Sep 17 00:00:00 2001 From: Mr D - RC Date: Tue, 15 Oct 2024 12:31:16 +0100 Subject: [PATCH 3/8] Fix lockup on disarm when wh used in post-flight stats - Fixed issue - Tidied up formatting --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 1b88226b9cb..cdda88521b2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -4789,7 +4789,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); @@ -4851,7 +4851,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, "---/---"); From 9cd1706314efdc3ea3cc0d6d3cb391f9552b84d9 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 21 Oct 2024 14:44:40 +0200 Subject: [PATCH 4/8] Add PrincipioIoT F7 target --- src/main/target/PRINCIPIOTF7/CMakeLists.txt | 1 + src/main/target/PRINCIPIOTF7/config.c | 32 ++++ src/main/target/PRINCIPIOTF7/target.c | 74 ++++++++++ src/main/target/PRINCIPIOTF7/target.h | 156 ++++++++++++++++++++ 4 files changed, 263 insertions(+) create mode 100644 src/main/target/PRINCIPIOTF7/CMakeLists.txt create mode 100644 src/main/target/PRINCIPIOTF7/config.c create mode 100644 src/main/target/PRINCIPIOTF7/target.c create mode 100644 src/main/target/PRINCIPIOTF7/target.h diff --git a/src/main/target/PRINCIPIOTF7/CMakeLists.txt b/src/main/target/PRINCIPIOTF7/CMakeLists.txt new file mode 100644 index 00000000000..5988719a7ef --- /dev/null +++ b/src/main/target/PRINCIPIOTF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(PRINCIPIOTF7) diff --git a/src/main/target/PRINCIPIOTF7/config.c b/src/main/target/PRINCIPIOTF7/config.c new file mode 100644 index 00000000000..c13aeda29b8 --- /dev/null +++ b/src/main/target/PRINCIPIOTF7/config.c @@ -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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#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/PRINCIPIOTF7/target.c b/src/main/target/PRINCIPIOTF7/target.c new file mode 100644 index 00000000000..9268af45585 --- /dev/null +++ b/src/main/target/PRINCIPIOTF7/target.c @@ -0,0 +1,74 @@ +/* + * 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 . + * + * This target has been autogenerated by bf2inav.py + */ + +#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[] = { + // Motor 1 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), // S1 + //DEF_TIM(TIM8, CH3, PC8, TIM_USE_OUTPUT_AUTO, 0, 0), + + // Motor 2 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), // S2 + //DEF_TIM(TIM8, CH4, PC9, TIM_USE_OUTPUT_AUTO, 0, 0), + + // Motor 3 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_OUTPUT_AUTO, 0, 0), // S3 + + // Motor 4 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_OUTPUT_AUTO, 0, 0), // S4 + + // Motor 5 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), // S5 + //DEF_TIM(TIM3, CH3, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH2N, PB0, TIM_USE_OUTPUT_AUTO, 0, 0), + + // Motor 6 + DEF_TIM(TIM1, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), // S6 + //DEF_TIM(TIM3, CH4, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + //DEF_TIM(TIM8, CH3N, PB1, TIM_USE_OUTPUT_AUTO, 0, 0), + + // Motor 7 + DEF_TIM(TIM2, CH3, PB10, TIM_USE_OUTPUT_AUTO, 0, 0), // S7 + + // Motor 8 + DEF_TIM(TIM2, CH4, PB11, TIM_USE_OUTPUT_AUTO, 0, 0), // S8 + + // Servo 1 + DEF_TIM(TIM4, CH1, PB6, TIM_USE_OUTPUT_AUTO, 0, 0), // S9 + + // Servo 2 + DEF_TIM(TIM4, CH2, PB7, TIM_USE_OUTPUT_AUTO, 0, 0), // S10 + + // LED Strip + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/PRINCIPIOTF7/target.h b/src/main/target/PRINCIPIOTF7/target.h new file mode 100644 index 00000000000..aa486d6af25 --- /dev/null +++ b/src/main/target/PRINCIPIOTF7/target.h @@ -0,0 +1,156 @@ +/* + * 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 . + * + * This target has been autgenerated by bf2inav.py + */ + +#pragma once + +//#define USE_TARGET_CONFIG + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY ) + + + +#define TARGET_BOARD_IDENTIFIER "PRF7" +#define USBD_PRODUCT_STRING "PRINCIPIOTF7" + +// Beeper +#define USE_BEEPER +#define BEEPER PC13 + +// Leds +#define USE_LED_STRIP +#define WS2811_PIN PA8 +#define LED0 PA4 +#define LED1 PB15 + +// UARTs +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_DISABLED + +#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 PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 7 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_CRSF +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART2 + +// SPI +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA7 +#define SPI1_MOSI_PIN PA6 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC3 +#define SPI2_MOSI_PIN PB14 + +// I2C +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// MAG +#define USE_MAG +#define USE_MAG_ALL +#define MAG_I2C_BUS BUS_I2C1 + +// ADC +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC2 +#define VBAT_ADC_CHANNEL ADC_CHN_1 + +#define ADC_CHANNEL_2_PIN PC1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// Gyro & ACC + +// ICM42688-P +#define USE_IMU_ICM42605 +#define IMU_ICM42605_ALIGN CW90_DEG +#define ICM42605_CS_PIN PB2 +#define ICM42605_SPI_BUS BUS_SPI1 + +// BARO +// DPS310 +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_DPS310 + +// Blackbox +#define USE_FLASHFS +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +// Not sure which to use for the onboard chip (W25Q128JVPIQ) +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB12 +#define USE_FLASH_W25M +#define W25M_SPI_BUS BUS_SPI2 +#define W25M_CS_PIN PB12 +#define USE_FLASH_W25M02G +#define W25M02G_SPI_BUS BUS_SPI2 +#define W25M02G_CS_PIN PB12 +#define USE_FLASH_W25M512 +#define W25M512_SPI_BUS BUS_SPI2 +#define W25M512_CS_PIN PB12 +#define USE_FLASH_W25N01G +#define W25N01G_SPI_BUS BUS_SPI2 +#define W25N01G_CS_PIN PB12 + +// Others + +#define MAX_PWM_OUTPUT_PORTS 10 +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define USE_DSHOT +#define USE_ESC_SENSOR + +#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 TARGET_IO_PORTF 0xffff From 51d98cffe5642b5e149ed0694bf4e0322c5dff40 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Tue, 1 Oct 2024 10:29:52 +0200 Subject: [PATCH 5/8] at32: add ability to specify uart rx/tx af independently --- src/main/drivers/serial_uart_at32f43x.c | 134 ++++++++++++++++++------ 1 file changed, 103 insertions(+), 31 deletions(-) diff --git a/src/main/drivers/serial_uart_at32f43x.c b/src/main/drivers/serial_uart_at32f43x.c index ad4b4e0c458..f58e0a956aa 100644 --- a/src/main/drivers/serial_uart_at32f43x.c +++ b/src/main/drivers/serial_uart_at32f43x.c @@ -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, @@ -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, @@ -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, @@ -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, @@ -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, @@ -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, @@ -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, @@ -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, @@ -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); } } From a0a83cccd0c793420c74fa62177cd4c6c72b3276 Mon Sep 17 00:00:00 2001 From: bkleiner Date: Tue, 1 Oct 2024 10:42:06 +0200 Subject: [PATCH 6/8] at32: re-check all serial pins and add swap/af defines as necessary --- src/main/target/NEUTRONRCF435MINI/target.h | 2 ++ src/main/target/TBS_LUCID_FC/target.h | 3 ++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/main/target/NEUTRONRCF435MINI/target.h b/src/main/target/NEUTRONRCF435MINI/target.h index 6ef53abf64d..d4653ca6c25 100644 --- a/src/main/target/NEUTRONRCF435MINI/target.h +++ b/src/main/target/NEUTRONRCF435MINI/target.h @@ -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 diff --git a/src/main/target/TBS_LUCID_FC/target.h b/src/main/target/TBS_LUCID_FC/target.h index 6e755b9a1a5..9baab07355d 100644 --- a/src/main/target/TBS_LUCID_FC/target.h +++ b/src/main/target/TBS_LUCID_FC/target.h @@ -42,10 +42,11 @@ #define USE_UART2 #define UART2_AF 6 -#define UART2_TX_PIN NONE +#define UART2_TX_PIN PB0 #define UART2_RX_PIN PB0 #define USE_UART3 +#define USE_UART3_PIN_SWAP #define UART3_TX_PIN PB11 #define UART3_RX_PIN PB10 From 4cdd6b9002e2bb9cb20277df8ab7ebf5a4504c8d Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 24 Oct 2024 18:36:06 +0200 Subject: [PATCH 7/8] Update readme.md --- readme.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/readme.md b/readme.md index 1c313de3569..58c9dce7950 100644 --- a/readme.md +++ b/readme.md @@ -1,3 +1,11 @@ +# INAV 8.0 feature freeze + +It is that time of the year again, and the time for a new inav realease 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 From b3569812fcea76d269f07800a3e858d3dcf9dee4 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Thu, 24 Oct 2024 18:47:31 +0200 Subject: [PATCH 8/8] Update readme.md --- readme.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/readme.md b/readme.md index 58c9dce7950..5107d4661ea 100644 --- a/readme.md +++ b/readme.md @@ -1,6 +1,6 @@ # INAV 8.0 feature freeze -It is that time of the year again, and the time for a new inav realease is near! +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**.