From 9b20fc84eab721168752591929ec61142efb9c20 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 28 Nov 2023 10:59:36 -0600
Subject: [PATCH 01/33] [Target] FOXEERF722V4 ICM42668P MPU6000 (#922)
[Target] FOXEERF722V4 MPU6000 ICM42688P
---
src/main/target/FOXEERF722V4/target.c | 44 +++++++
src/main/target/FOXEERF722V4/target.h | 155 +++++++++++++++++++++++++
src/main/target/FOXEERF722V4/target.mk | 16 +++
3 files changed, 215 insertions(+)
create mode 100644 src/main/target/FOXEERF722V4/target.c
create mode 100644 src/main/target/FOXEERF722V4/target.h
create mode 100644 src/main/target/FOXEERF722V4/target.mk
diff --git a/src/main/target/FOXEERF722V4/target.c b/src/main/target/FOXEERF722V4/target.c
new file mode 100644
index 0000000000..a0255f4f3a
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.c
@@ -0,0 +1,44 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is free software. You can redistribute this software
+ * and/or modify this software 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: bc7d9ef
+
+#include
+#include "platform.h"
+#include "drivers/io.h"
+#include "drivers/dma.h"
+#include "drivers/timer.h"
+#include "drivers/timer_def.h"
+
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // ppm
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // could not determine TIM_USE_xxxxx - please check
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // cam ctrl
+};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FOXEERF722V4/target.h b/src/main/target/FOXEERF722V4/target.h
new file mode 100644
index 0000000000..47c8a127e7
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.h
@@ -0,0 +1,155 @@
+/*
+ * This file is part of EmuFlight. It is derived from Betaflight.
+ *
+ * This is free software. You can redistribute this software
+ * and/or modify this software 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.
+ *
+ * This software 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 this software.
+ *
+ * If not, see .
+ */
+
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: bc7d9ef
+
+#pragma once
+
+#define TARGET_MANUFACTURER_IDENTIFIER "FOXE"
+#define USBD_PRODUCT_STRING "FOXEERF722V4"
+
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
+
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_BARO
+#define USE_BARO_DPS310
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+#define USE_ADC
+#define USE_SPI_GYRO
+#define USE_BARO
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 //works in place of W25Q128FV
+#define USE_OSD
+
+#define USE_LED
+#define LED0_PIN PC15
+#define LED_STRIP_PIN PA15
+#define USE_BEEPER
+#define BEEPER_PIN PA4
+#define BEEPER_INVERTED
+#define CAMERA_CONTROL_PIN PB3
+
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PB5
+
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_EXTI_PIN PC4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define MPU_INT_EXTI PC4
+
+#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define ACC_ICM42688P_ALIGN CW270_DEG
+#define GYRO_ICM42688P_ALIGN CW270_DEG
+#define ICM42688P_CS_PIN PB2
+#define ICM42688P_SPI_INSTANCE SPI1
+
+#define USE_UART1
+#define USE_UART2
+#define USE_UART3
+#define USE_UART4
+#define USE_UART5
+#define USE_UART6
+#define UART1_TX_PIN PB6
+#define UART2_TX_PIN PA2
+#define UART3_TX_PIN PB10
+#define UART4_TX_PIN PA0
+#define UART5_TX_PIN PC12
+#define UART6_TX_PIN PC6
+#define UART1_RX_PIN PB7
+#define UART2_RX_PIN PA3
+#define UART3_RX_PIN PB11
+#define UART4_RX_PIN PA1
+#define UART5_RX_PIN PD2
+#define UART6_RX_PIN PC7
+#define RX_PPM_PIN PB7
+#define SERIAL_PORT_COUNT 7
+
+#define USE_I2C
+#define USE_I2C_DEVICE_1
+#define I2C_DEVICE (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+
+#define MAX7456_SPI_CS_PIN PC3
+#define MAX7456_SPI_INSTANCE SPI3
+
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC2
+#define RSSI_ADC_PIN PA0
+#define ADC3_DMA_STREAM DMA2_Stream0 //# ADC 3: DMA2 Stream 0 Channel 2
+#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
+#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define ADC_INSTANCE ADC3
+
+#define ENABLE_DSHOT_DMAR true
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+// notice - masks were programmatically generated - please verify last port group for 0xffff or (BIT(2))
+
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
+
+#define USABLE_TIMER_CHANNEL_COUNT 9
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(8) )
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/FOXEERF722V4/target.mk b/src/main/target/FOXEERF722V4/target.mk
new file mode 100644
index 0000000000..4cac437e26
--- /dev/null
+++ b/src/main/target/FOXEERF722V4/target.mk
@@ -0,0 +1,16 @@
+F7X2RE_TARGETS += $(TARGET)
+FEATURES += VCP ONBOARDFLASH
+
+TARGET_SRC = \
+drivers/accgyro/accgyro_mpu.c \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# notice - this file was programmatically generated and may be incomplete.
+# eg: flash, compass, barometer, vtx6705, ledstrip, pinio, etc. especially mag/baro
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: bc7d9ef
From 75b413e75400739eacd5f51b6a012c6896e5a573 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Mon, 18 Dec 2023 10:04:43 -0600
Subject: [PATCH 02/33] [target] RUSH BLADEF7 update/repair (#957)
---
src/main/target/RUSHBLADEF7/target.c | 50 +++---
src/main/target/RUSHBLADEF7/target.h | 219 +++++++++++++-------------
src/main/target/RUSHBLADEF7/target.mk | 21 ++-
3 files changed, 155 insertions(+), 135 deletions(-)
diff --git a/src/main/target/RUSHBLADEF7/target.c b/src/main/target/RUSHBLADEF7/target.c
index 5cd05775bc..fefead3d9e 100644
--- a/src/main/target/RUSHBLADEF7/target.c
+++ b/src/main/target/RUSHBLADEF7/target.c
@@ -1,41 +1,45 @@
/*
- * This file is part of Cleanflight and Betaflight.
+ * This file is part of EmuFlight. It is derived from Betaflight.
*
- * Cleanflight and Betaflight are free software. You can redistribute
- * this software and/or modify this software 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.
+ * This is free software. You can redistribute this software
+ * and/or modify this software 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.
+ *
+ * This software 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.
*
- * Cleanflight and Betaflight are distributed in the hope that they
- * 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 this software.
+ * You should have received a copy of the GNU General Public
+ * License along with this software.
*
* If not, see .
*/
-#include
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: c4eda1b
+#include
#include "platform.h"
#include "drivers/io.h"
-
#include "drivers/dma.h"
#include "drivers/timer.h"
#include "drivers/timer_def.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // PPM&SBUS
-
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S1
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // S2
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S3
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S4
- DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // S5
- DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // S6
-
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // LED STRIP
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // motor 1
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // motor 2
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // motor 3
+ DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // motor 4
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 0), // motor 5
+ DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), // motor 6
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // motor 7
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // motor 8
+ DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // led
+ DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // cam ctrl
};
+
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/RUSHBLADEF7/target.h b/src/main/target/RUSHBLADEF7/target.h
index 8559f4f88d..102932a3df 100644
--- a/src/main/target/RUSHBLADEF7/target.h
+++ b/src/main/target/RUSHBLADEF7/target.h
@@ -1,148 +1,155 @@
/*
- * This file is part of Cleanflight and Betaflight.
+ * This file is part of EmuFlight. It is derived from Betaflight.
*
- * Cleanflight and Betaflight are free software. You can redistribute
- * this software and/or modify this software 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.
+ * This is free software. You can redistribute this software
+ * and/or modify this software 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.
+ *
+ * This software 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.
*
- * Cleanflight and Betaflight are distributed in the hope that they
- * 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 this software.
+ * You should have received a copy of the GNU General Public
+ * License along with this software.
*
* If not, see .
*/
+// This resource file generated using https://github.com/nerdCopter/target-convert
+// Commit: c4eda1b
+
#pragma once
-#define TARGET_BOARD_IDENTIFIER "RSF7"
-#define USBD_PRODUCT_STRING "RUSHBLADE F7"
+#define TARGET_MANUFACTURER_IDENTIFIER "RUSH"
+#define USBD_PRODUCT_STRING "BLADE_F7"
-#define ENABLE_DSHOT_DMAR true
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
-#define LED0_PIN PB10
+#define USE_ACC
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO
+#define USE_GYRO_SPI_MPU6000
+#define USE_GYRO_SPI_ICM42688P
+#define USE_ACC_SPI_ICM42688P
+#define USE_BARO
+#define USE_BARO_DPS310
+#define USE_BARO_BMP280
+#define USE_FLASH
+#define USE_FLASH_W25Q128FV
+#define USE_MAX7456
+#define USE_SPI_GYRO
+#define USE_BARO
+
+#define USE_VCP
+#define USE_FLASHFS
+#define USE_FLASH_M25P16 // 16MB Micron M25P16 and others (ref: https://github.com/betaflight/betaflight/blob/master/src/main/drivers/flash_m25p16.c)
+#define USE_OSD
+#define USE_LED
+#define LED0_PIN PB10
+#define LED_STRIP_PIN PA15
#define USE_BEEPER
-#define BEEPER_PIN PB2
+#define BEEPER_PIN PB2
#define BEEPER_INVERTED
-//#define BEEPER_PWM_HZ 1100
+#define BEEPER_PWM_HZ 1100
+#define CAMERA_CONTROL_PIN PA8
-#define USE_EXTI
-#define MPU_INT_EXTI PA4
-#define USE_MPU_DATA_READY_SIGNAL
+#define USE_SPI
+#define USE_SPI_DEVICE_1
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+#define USE_SPI_DEVICE_2
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+#define USE_SPI_DEVICE_3
+#define SPI3_SCK_PIN PB3
+#define SPI3_MISO_PIN PB4
+#define SPI3_MOSI_PIN PB5
-#define USE_ACC
-#define USE_GYRO
-//------MPU6000
-#define MPU6000_CS_PIN PC4
-#define MPU6000_SPI_INSTANCE SPI1
+#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI
+#define USE_GYRO_EXTI
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW270_DEG
+#define USE_MPU_DATA_READY_SIGNAL
-#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PC4
+#define GYRO_1_EXTI_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define MPU_INT_EXTI PA4
-#define USE_ACC_MPU6000
-#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_MPU6000
-#define USE_GYRO_SPI_MPU6000
-
-#define USE_BARO
-#define USE_BARO_BMP280
-#define USE_BARO_MS5611
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PC4
+#define MPU6000_SPI_INSTANCE SPI1
-#define USE_MAG
-#define USE_MAG_HMC5883
+#define ACC_ICM42688P_ALIGN CW270_DEG
+#define GYRO_ICM42688P_ALIGN CW270_DEG
+#define ICM42688P_CS_PIN PC4
+#define ICM42688P_SPI_INSTANCE SPI1
-#define USE_VCP
#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 PA0
+#define UART4_RX_PIN PA1
#define USE_UART5
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA2
-#define UART2_RX_PIN PA3
-
-#define UART3_TX_PIN PC10
-#define UART3_RX_PIN PC11
-
-#define UART4_TX_PIN PA0
-#define UART4_RX_PIN PA1
-
-#define UART5_TX_PIN PC12
-#define UART5_RX_PIN PD2
-
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-
-#define SERIAL_PORT_COUNT 8
+#define UART5_TX_PIN PC12
+#define UART5_RX_PIN PD2
+#define SERIAL_PORT_COUNT 6
+//#define USE_SOFTSERIAL1 //old defines had softserial, maybe in error
+//#define USE_SOFTSERIAL2
+//#define SERIAL_PORT_COUNT 8
#define USE_I2C
#define USE_I2C_DEVICE_1
-#define I2C_DEVICE I2CDEV_1
-#define I2C1_SCL PB8
-#define I2C1_SDA PB9
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1 //GYRO/ACC
-#define SPI1_SCK_PIN PA5
-#define SPI1_MISO_PIN PA6
-#define SPI1_MOSI_PIN PA7
-
-#define USE_SPI_DEVICE_2 //MAX7456
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define USE_SPI_DEVICE_3
-#define SPI3_SCK_PIN PB3
-#define SPI3_MISO_PIN PB4
-#define SPI3_MOSI_PIN PB5
-
-#define USE_MAX7456
-#define MAX7456_SPI_INSTANCE SPI2
-#define MAX7456_SPI_CS_PIN PB11
+#define I2C_DEVICE (I2CDEV_1)
+#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define I2C1_SCL PB8
+#define I2C1_SDA PB9
+#define FLASH_CS_PIN PB12
+#define FLASH_SPI_INSTANCE SPI2
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-#define FLASH_CS_PIN PB12
-#define FLASH_SPI_INSTANCE SPI2
-
-#define USE_ADC
-#define ADC_INSTANCE ADC1
-#define ADC3_DMA_STREAM DMA2_Stream0
-#define VBAT_ADC_PIN PC0
-#define CURRENT_METER_ADC_PIN PC1
+#define MAX7456_SPI_CS_PIN PB11
+#define MAX7456_SPI_INSTANCE SPI2
+#define USE_ADC
+#define VBAT_ADC_PIN PC0
+#define CURRENT_METER_ADC_PIN PC1
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
+#define DEFAULT_CURRENT_METER_SCALE 179
-#define USE_OSD
-#define USE_LED_STRIP
+#define ENABLE_DSHOT_DMAR true
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define DEFAULT_FEATURES FEATURE_OSD
-#define SERIALRX_UART SERIAL_PORT_USART2
-#define SERIALRX_PROVIDER SERIALRX_SBUS
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+//#define TARGET_IO_PORTD (BIT(2)) //old defines used this instead
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_RX_SERIAL)
+#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
+#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
-#define USABLE_TIMER_CHANNEL_COUNT 9
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9) )
+// notice - this file was programmatically generated and may be incomplete.
diff --git a/src/main/target/RUSHBLADEF7/target.mk b/src/main/target/RUSHBLADEF7/target.mk
index eb35ec20ee..512a00a52e 100644
--- a/src/main/target/RUSHBLADEF7/target.mk
+++ b/src/main/target/RUSHBLADEF7/target.mk
@@ -2,9 +2,18 @@ F7X2RE_TARGETS += $(TARGET)
FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/barometer/barometer_ms5611.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/max7456.c
+drivers/accgyro/accgyro_mpu.c \
+drivers/accgyro/accgyro_spi_mpu6000.c \
+drivers/accgyro/accgyro_spi_icm426xx.c \
+drivers/barometer/barometer_ms5611.c \
+drivers/barometer/barometer_bmp280.c \
+drivers/compass/compass_hmc5883l.c \
+drivers/light_led.h \
+drivers/light_ws2811strip.c \
+drivers/max7456.c \
+
+# notice - this file was programmatically generated and may be incomplete.
+# drivers for ms5611 & compass manually added
+
+# This resource file generated using https://github.com/nerdCopter/target-convert
+# Commit: c4eda1b
From d23611a5533790ffb6f96ef9d6709c1cd0d68378 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 20 Dec 2023 08:20:58 -0600
Subject: [PATCH 03/33] [gh actions] use date as tag for dev-unstable
dev-master (#959)
---
.github/workflows/build.yml | 5 +++--
1 file changed, 3 insertions(+), 2 deletions(-)
diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml
index ed938545a9..54922794f6 100644
--- a/.github/workflows/build.yml
+++ b/.github/workflows/build.yml
@@ -159,6 +159,7 @@ jobs:
echo "outputs.shortsha: ${{ needs.build.outputs.shortsha }}"
echo "outputs.artfact: ${{ needs.build.outputs.artifact }}"
echo "outputs.artfact: ${{ needs.build.outputs.version }}"
+ echo "NOW=$(date +'%Y%m%d.%H%M%S')" >> $GITHUB_ENV
continue-on-error: true
- name: download artifacts
@@ -181,7 +182,7 @@ jobs:
repo: dev-unstable
owner: emuflight
token: ${{ secrets.NC_PAT_EMUF }}
- tag: "hex-${{ github.run_number }}"
+ tag: "${{ env.NOW }}-hex"
draft: true
prerelease: true
allowUpdates: true
@@ -213,7 +214,7 @@ jobs:
repo: dev-master
owner: emuflight
token: ${{ secrets.NC_PAT_EMUF }}
- tag: "hex-${{ github.run_number }}"
+ tag: "${{ env.NOW }}-hex"
draft: true
prerelease: true
allowUpdates: true
From 91c5ad700368229f3169b4cb9b590ee40e2409db Mon Sep 17 00:00:00 2001
From: Dinesh Manajipet
Date: Wed, 7 Feb 2024 21:30:20 +0530
Subject: [PATCH 04/33] Import HDZero OSD Driver from iNav (#775)
* Import HDZero OSD Driver from iNav Mostly from https://github.com/iNavFlight/inav/pull/7668/files commit
* And added missing functions to bitarray.h/.c, msp_serial.h/.c
* Used "drivers/max7456_symbols.h" instead of "drivers/osd_symbols.h"
* Used baudRates[portConfig->msp_baudrateIndex] instead of baudRates[portConfig->peripheral_baudrateIndex]
* Additional changes: serial: serialPortFunction_e now needs 32 bits
* How to use: In CLI, assuming to use serial port 4, enter the following CLI commands to enable FUNCTION_HDZERO_OSD in EmuFlight Configurator `serial 3 65536 115200 115200 0 115200`, `save`
* Update msp_protocol minor version to 52 This is because we changed the size of serialPortConfig_s.functionMask
* TODO: Add the peripheral_baudrateIndex entry to serialPortConfig_s ?
* displayport_hdzero_osd.c: Hardcode BAUD_115200 for this for now. As per geoffsim, the HDZero VTX hardcodes thE baudrate at 115200. So No point making this configurable in EmuFlight As of now. We can bring back the configurability later on if needed
* displayport_hdzero_osd: drop MSP_SET_VTXTABLE_BAND/POWERLEVEL Emuflight does not implement vtx tables and that causes corruption on certain hdzero firmware. Everything seems smooth as Buttercake
* displayport_hdzero_osd: Remove an unused variable
---
make/source.mk | 1 +
src/main/common/bitarray.c | 50 +++
src/main/common/bitarray.h | 13 +
src/main/drivers/display_font_metadata.c | 11 +
src/main/drivers/display_font_metadata.h | 24 ++
src/main/drivers/serial_softserial.c | 2 +-
src/main/fc/fc_init.c | 24 +-
src/main/fc/fc_tasks.c | 6 +
src/main/interface/cli.c | 2 +-
src/main/interface/msp.c | 6 +-
src/main/interface/msp_protocol.h | 2 +-
src/main/interface/settings.c | 4 +-
src/main/io/displayport_hdzero_osd.c | 417 +++++++++++++++++++++++
src/main/io/displayport_hdzero_osd.h | 34 ++
src/main/io/osd.c | 2 +-
src/main/io/osd.h | 8 +-
src/main/io/serial.c | 4 +-
src/main/io/serial.h | 7 +-
src/main/msp/msp_serial.c | 58 +++-
src/main/msp/msp_serial.h | 4 +
src/main/target/common_fc_pre.h | 1 +
src/test/unit/rx_ibus_unittest.cc | 2 +-
src/test/unit/telemetry_ibus_unittest.cc | 2 +-
23 files changed, 655 insertions(+), 29 deletions(-)
create mode 100644 src/main/drivers/display_font_metadata.c
create mode 100644 src/main/drivers/display_font_metadata.h
create mode 100644 src/main/io/displayport_hdzero_osd.c
create mode 100644 src/main/io/displayport_hdzero_osd.h
diff --git a/make/source.mk b/make/source.mk
index dd602fab3c..e12e19aa7f 100644
--- a/make/source.mk
+++ b/make/source.mk
@@ -139,6 +139,7 @@ COMMON_SRC = \
io/dashboard.c \
io/displayport_max7456.c \
io/displayport_msp.c \
+ io/displayport_hdzero_osd.c \
io/displayport_oled.c \
io/displayport_srxl.c \
io/displayport_crsf.c \
diff --git a/src/main/common/bitarray.c b/src/main/common/bitarray.c
index 8884146fbb..3c523c1baa 100644
--- a/src/main/common/bitarray.c
+++ b/src/main/common/bitarray.c
@@ -51,3 +51,53 @@ void bitArrayCopy(void *array, unsigned from, unsigned to) {
bitArrayClr(array, to);
}
}
+
+void bitArrayClrAll(bitarrayElement_t *array, size_t size)
+{
+ memset(array, 0, size);
+}
+
+__attribute__((always_inline)) static inline uint8_t __CTZ(uint32_t val)
+{
+ // __builtin_ctz is not defined for zero, since it's arch
+ // dependant. However, in ARM it gets translated to a
+ // rbit and then a clz, making it return 32 for zero on ARM.
+ // For other architectures, explicitely implement the same
+ // semantics.
+#ifdef __arm__
+ uint8_t zc;
+ __asm__ volatile ("rbit %1, %1\n\t"
+ "clz %0, %1"
+ : "=r" (zc)
+ : "r" (val) );
+ return zc;
+#else
+ // __builtin_clz is not defined for zero, since it's arch
+ // dependant. Make it return 32 like ARM's CLZ.
+ return val ? __builtin_ctz(val) : 32;
+#endif
+}
+
+int bitArrayFindFirstSet(const bitarrayElement_t *array, unsigned start, size_t size)
+{
+ const uint32_t *ptr = (uint32_t*)array;
+ const uint32_t *end = ptr + (size / 4);
+ const uint32_t *p = ptr + start / (8 * 4);
+
+ if (p < end) {
+ int ret;
+ // First iteration might need to mask some bits
+ uint32_t mask = 0xFFFFFFFF << (start % (8 * 4));
+ if ((ret = __CTZ(*p & mask)) != 32) {
+ return (((char *)p) - ((char *)ptr)) * 8 + ret;
+ }
+ p++;
+ while (p < end) {
+ if ((ret = __CTZ(*p)) != 32) {
+ return (((char *)p) - ((char *)ptr)) * 8 + ret;
+ }
+ p++;
+ }
+ }
+ return -1;
+}
\ No newline at end of file
diff --git a/src/main/common/bitarray.h b/src/main/common/bitarray.h
index 13fafe5550..eaa64b3905 100644
--- a/src/main/common/bitarray.h
+++ b/src/main/common/bitarray.h
@@ -20,8 +20,21 @@
#pragma once
+typedef uint32_t bitarrayElement_t;
+
bool bitArrayGet(const void *array, unsigned bit);
void bitArraySet(void *array, unsigned bit);
void bitArrayClr(void *array, unsigned bit);
void bitArrayXor(void *dest, size_t size, void *op1, void *op2);
void bitArrayCopy(void *array, unsigned from, unsigned to);
+void bitArrayClrAll(bitarrayElement_t *array, size_t size);
+// Returns the first set bit with pos >= start_bit, or -1 if all bits
+// are zero. Note that size must indicate the size of array in bytes.
+// In most cases, you should use the BITARRAY_FIND_FIRST_SET() macro
+// to call this function.
+int bitArrayFindFirstSet(const bitarrayElement_t *array, unsigned start_bit, size_t size);
+
+#define BITARRAY_DECLARE(name, bits) bitarrayElement_t name[(bits + 31) / 32]
+#define BITARRAY_SET_ALL(array) bitArraySetAll(array, sizeof(array))
+#define BITARRAY_CLR_ALL(array) bitArrayClrAll(array, sizeof(array))
+#define BITARRAY_FIND_FIRST_SET(array, start_bit) bitArrayFindFirstSet(array, start_bit, sizeof(array))
\ No newline at end of file
diff --git a/src/main/drivers/display_font_metadata.c b/src/main/drivers/display_font_metadata.c
new file mode 100644
index 0000000000..6bf01c383e
--- /dev/null
+++ b/src/main/drivers/display_font_metadata.c
@@ -0,0 +1,11 @@
+#include "drivers/display_font_metadata.h"
+#include "drivers/osd.h"
+
+bool displayFontMetadataUpdateFromCharacter(displayFontMetadata_t *metadata, const osdCharacter_t *chr)
+{
+ if (chr && FONT_CHR_IS_METADATA(chr)) {
+ metadata->version = chr->data[5];
+ return true;
+ }
+ return false;
+}
diff --git a/src/main/drivers/display_font_metadata.h b/src/main/drivers/display_font_metadata.h
new file mode 100644
index 0000000000..ebef4b635a
--- /dev/null
+++ b/src/main/drivers/display_font_metadata.h
@@ -0,0 +1,24 @@
+#pragma once
+
+#include
+#include
+
+typedef struct osdCharacter_s osdCharacter_t;
+
+typedef struct displayFontMetadata_s {
+ uint8_t version;
+ uint16_t charCount;
+} displayFontMetadata_t;
+
+// 'I', 'N', 'A', 'V'
+#define FONT_CHR_IS_METADATA(chr) ((chr)->data[0] == 'I' && \
+ (chr)->data[1] == 'N' && \
+ (chr)->data[2] == 'A' && \
+ (chr)->data[3] == 'V')
+
+#define FONT_METADATA_CHR_INDEX 255
+// Used for runtime detection of display drivers that might
+// support 256 or 512 characters.
+#define FONT_METADATA_CHR_INDEX_2ND_PAGE 256
+
+bool displayFontMetadataUpdateFromCharacter(displayFontMetadata_t *metadata, const osdCharacter_t *chr);
diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c
index 6a0767a153..56dd22c9b9 100644
--- a/src/main/drivers/serial_softserial.c
+++ b/src/main/drivers/serial_softserial.c
@@ -492,7 +492,7 @@ uint32_t softSerialTxBytesFree(const serialPort_t *instance) {
return 0;
}
softSerial_t *s = (softSerial_t *)instance;
- uint8_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
+ uint32_t bytesUsed = (s->port.txBufferHead - s->port.txBufferTail) & (s->port.txBufferSize - 1);
return (s->port.txBufferSize - 1) - bytesUsed;
}
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 1c7396a33a..22a4447479 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -115,6 +115,7 @@
#include "rx/spektrum.h"
#include "io/beeper.h"
+#include "io/displayport_hdzero_osd.h"
#include "io/displayport_max7456.h"
#include "io/displayport_srxl.h"
#include "io/serial.h"
@@ -508,12 +509,25 @@ void init(void) {
if (feature(FEATURE_OSD)) {
#if defined(USE_OSD_BEESIGN)
// If there is a beesign for the OSD then use it
- osdDisplayPort = beesignDisplayPortInit(vcdProfile());
-#elif defined(USE_MAX7456)
+ if (!osdDisplayPort) {
+ osdDisplayPort = beesignDisplayPortInit(vcdProfile());
+ }
+#endif
+#if defined(USE_HDZERO_OSD)
+ if (!osdDisplayPort) {
+ osdDisplayPort = hdzeroOsdDisplayPortInit();
+ }
+#endif
+#if defined(USE_MAX7456)
// If there is a max7456 chip for the OSD then use it
- osdDisplayPort = max7456DisplayPortInit(vcdProfile());
-#elif defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT) // OSD over MSP; not supported (yet)
- osdDisplayPort = displayPortMspInit();
+ if (!osdDisplayPort) {
+ osdDisplayPort = max7456DisplayPortInit(vcdProfile());
+ }
+#endif
+#if defined(USE_CMS) && defined(USE_MSP_DISPLAYPORT) && defined(USE_OSD_OVER_MSP_DISPLAYPORT) // OSD over MSP; not supported (yet)
+ if (!osdDisplayPort) {
+ osdDisplayPort = displayPortMspInit();
+ }
#endif
// osdInit will register with CMS by itself.
osdInit(osdDisplayPort);
diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c
index 12831714bf..121e5b702a 100644
--- a/src/main/fc/fc_tasks.c
+++ b/src/main/fc/fc_tasks.c
@@ -74,6 +74,7 @@
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/osd.h"
+#include "io/displayport_hdzero_osd.h"
#include "io/piniobox.h"
#include "io/serial.h"
#include "io/transponder_ir.h"
@@ -159,6 +160,11 @@ static void taskHandleSerial(timeUs_t currentTimeUs) {
bool evaluateMspData = osdSlaveIsLocked ? MSP_SKIP_NON_MSP_DATA : MSP_EVALUATE_NON_MSP_DATA;;
#endif
mspSerialProcess(evaluateMspData, mspFcProcessCommand, mspFcProcessReply);
+
+#ifdef USE_HDZERO_OSD
+ // Capture HDZero messages to determine if VTX is connected
+ hdzeroOsdSerialProcess(mspFcProcessCommand);
+#endif
}
static void taskBatteryAlerts(timeUs_t currentTimeUs) {
diff --git a/src/main/interface/cli.c b/src/main/interface/cli.c
index 80bac75d60..75879e5fae 100644
--- a/src/main/interface/cli.c
+++ b/src/main/interface/cli.c
@@ -990,7 +990,7 @@ static void cliSerial(char *cmdline) {
ptr = nextArg(ptr);
if (ptr) {
val = atoi(ptr);
- portConfig.functionMask = val & 0xFFFF;
+ portConfig.functionMask = val & 0xFFFFFFFF;
validArgumentCount++;
}
for (int i = 0; i < 4; i ++) {
diff --git a/src/main/interface/msp.c b/src/main/interface/msp.c
index 684b85e213..bdffb85b36 100644
--- a/src/main/interface/msp.c
+++ b/src/main/interface/msp.c
@@ -1084,7 +1084,7 @@ bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) {
continue;
};
sbufWriteU8(dst, serialConfig()->portConfigs[i].identifier);
- sbufWriteU16(dst, serialConfig()->portConfigs[i].functionMask);
+ sbufWriteU32(dst, serialConfig()->portConfigs[i].functionMask);
sbufWriteU8(dst, serialConfig()->portConfigs[i].msp_baudrateIndex);
sbufWriteU8(dst, serialConfig()->portConfigs[i].gps_baudrateIndex);
sbufWriteU8(dst, serialConfig()->portConfigs[i].telemetry_baudrateIndex);
@@ -2219,7 +2219,7 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) {
}
break;
case MSP_SET_CF_SERIAL_CONFIG: {
- uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint16_t) + (sizeof(uint8_t) * 4);
+ uint8_t portConfigSize = sizeof(uint8_t) + sizeof(uint32_t) + (sizeof(uint8_t) * 4);
if (dataSize % portConfigSize != 0) {
return MSP_RESULT_ERROR;
}
@@ -2231,7 +2231,7 @@ mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src) {
return MSP_RESULT_ERROR;
}
portConfig->identifier = identifier;
- portConfig->functionMask = sbufReadU16(src);
+ portConfig->functionMask = sbufReadU32(src);
portConfig->msp_baudrateIndex = sbufReadU8(src);
portConfig->gps_baudrateIndex = sbufReadU8(src);
portConfig->telemetry_baudrateIndex = sbufReadU8(src);
diff --git a/src/main/interface/msp_protocol.h b/src/main/interface/msp_protocol.h
index 6b062f5387..0f7f5d3d7a 100644
--- a/src/main/interface/msp_protocol.h
+++ b/src/main/interface/msp_protocol.h
@@ -64,7 +64,7 @@
// API VERSION
#define API_VERSION_MAJOR 1 // increment when major changes are made
-#define API_VERSION_MINOR 51 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
+#define API_VERSION_MINOR 52 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_LENGTH 2
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index 9cedcd3a45..da26165c1e 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -245,7 +245,7 @@ static const char * const lookupTableRxSpi[] = {
"FLYSKY",
"FLYSKY_2A",
"KN",
- "SFHSS",
+ "SFHSS",
"REDPINE"
};
#endif
@@ -368,7 +368,7 @@ static const char * const lookupTableRescueSanityType[] = {
#ifdef USE_MAX7456
static const char * const lookupTableVideoSystem[] = {
- "AUTO", "PAL", "NTSC"
+ "AUTO", "PAL", "NTSC", "HDZERO"
};
#endif // USE_MAX7456
diff --git a/src/main/io/displayport_hdzero_osd.c b/src/main/io/displayport_hdzero_osd.c
new file mode 100644
index 0000000000..9bbcae6d0e
--- /dev/null
+++ b/src/main/io/displayport_hdzero_osd.c
@@ -0,0 +1,417 @@
+/*
+ * This file is part of INAV Project.
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this file,
+ * You can obtain one at http://mozilla.org/MPL/2.0/.
+ *
+ * Alternatively, the contents of this file may be used under the terms
+ * of the GNU General Public License Version 3, as described below:
+ *
+ * This file is free software: you may copy, redistribute 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.
+ *
+ * This file 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 this program. If not, see http://www.gnu.org/licenses/.
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#define FILE_COMPILE_FOR_SPEED _Pragma("GCC optimize(\"Ofast\")")
+
+#include "drivers/display_font_metadata.h"
+FILE_COMPILE_FOR_SPEED
+
+//#define HDZERO_STATS
+
+#if defined(USE_OSD) && defined(USE_HDZERO_OSD)
+#include "common/utils.h"
+#include "common/printf.h"
+#include "common/time.h"
+#include "common/bitarray.h"
+
+#include "drivers/display.h"
+#include "drivers/max7456_symbols.h"
+
+#include "interface/msp_protocol.h"
+#include "io/serial.h"
+#include "msp/msp_serial.h"
+
+#include "displayport_hdzero_osd.h"
+
+#define FONT_VERSION 3
+
+#define MSP_CLEAR_SCREEN 2
+#define MSP_WRITE_STRING 3
+#define MSP_DRAW_SCREEN 4
+#define MSP_SET_OPTIONS 5
+#define DRAW_FREQ_DENOM 4 // 60Hz
+#define TX_BUFFER_SIZE 1024
+#define VTX_TIMEOUT 1000 // 1 second timer
+
+static mspProcessCommandFnPtr mspProcessCommand;
+static mspPort_t hdZeroMspPort;
+static displayPort_t hdZeroOsdDisplayPort;
+static bool vtxSeen, vtxActive, vtxReset;
+static timeMs_t vtxHeartbeat;
+
+// HD screen size
+#define ROWS 18
+#define COLS 50
+#define SCREENSIZE (ROWS*COLS)
+static uint8_t screen[SCREENSIZE];
+static BITARRAY_DECLARE(fontPage, SCREENSIZE); // font page for each character on the screen
+static BITARRAY_DECLARE(dirty, SCREENSIZE); // change status for each character on the screen
+static bool screenCleared;
+
+extern uint8_t cliMode;
+
+#ifdef HDZERO_STATS
+static uint32_t dataSent;
+static uint8_t resetCount;
+#endif
+
+static int output(displayPort_t *displayPort, uint8_t cmd, uint8_t *subcmd, int len)
+{
+ UNUSED(displayPort);
+
+ int sent = 0;
+
+ if (!cliMode && vtxActive) {
+ sent = mspSerialPushPort(cmd, subcmd, len, &hdZeroMspPort, MSP_V1);
+ }
+
+#ifdef HDZERO_STATS
+ dataSent += sent;
+#endif
+
+ return sent;
+}
+
+static void checkVtxPresent(void)
+{
+ if (vtxActive && (millis()-vtxHeartbeat) > VTX_TIMEOUT) {
+ vtxActive = false;
+ }
+}
+
+static int setHdMode(displayPort_t *displayPort)
+{
+ checkVtxPresent();
+ uint8_t subcmd[] = { MSP_SET_OPTIONS, 0, 1 }; // font selection, mode (SD/HD)
+ return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
+}
+
+static void hdZeroInit(void)
+{
+ memset(screen, SYM_BLANK, sizeof(screen));
+ BITARRAY_CLR_ALL(fontPage);
+ BITARRAY_CLR_ALL(dirty);
+}
+
+static int clearScreen(displayPort_t *displayPort)
+{
+ uint8_t subcmd[] = { MSP_CLEAR_SCREEN };
+
+ hdZeroInit();
+ setHdMode(displayPort);
+ screenCleared = true;
+ return output(displayPort, MSP_DISPLAYPORT, subcmd, sizeof(subcmd));
+}
+
+static int setChar(const uint16_t pos, const uint16_t c)
+{
+ if (pos < SCREENSIZE) {
+ uint8_t ch = c & 0xFF;
+ bool page = (c >> 8);
+ if (screen[pos] != ch || bitArrayGet(fontPage, pos) != page) {
+ screen[pos] = ch;
+ (page) ? bitArraySet(fontPage, pos) : bitArrayClr(fontPage, pos);
+ bitArraySet(dirty, pos);
+ }
+ }
+ return 0;
+}
+
+static int writeChar(displayPort_t *displayPort, uint8_t col, uint8_t row, uint8_t c)
+{
+ UNUSED(displayPort);
+
+ return setChar((row * COLS) + col, c);
+}
+
+static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *string)
+{
+ UNUSED(displayPort);
+
+ uint16_t pos = (row * COLS) + col;
+ while (*string) {
+ setChar(pos++, *string++);
+ }
+ return 0;
+}
+
+#ifdef HDZERO_STATS
+static void printStats(displayPort_t *displayPort, uint32_t updates)
+{
+ static timeMs_t lastTime;
+ static uint32_t maxDataSent, maxBufferUsed, maxUpdates;
+ timeMs_t currentTime = millis();
+ char lineBuffer[100];
+
+ if (updates > maxUpdates) {
+ maxUpdates = updates; // updates sent per displayWrite
+ }
+
+ uint32_t bufferUsed = TX_BUFFER_SIZE - serialTxBytesFree(hdZeroMspPort.port);
+ if (bufferUsed > maxBufferUsed) {
+ maxBufferUsed = bufferUsed; // serial buffer used after displayWrite
+ }
+
+ uint32_t diff = (currentTime - lastTime);
+ if (diff > 1000) { // Data sampled in 1 second
+ if (dataSent > maxDataSent) {
+ maxDataSent = dataSent; // bps (max 11520 allowed)
+ }
+
+ dataSent = 0;
+ lastTime = currentTime;
+ }
+
+
+ tfp_sprintf(lineBuffer, "R:%2d %4ld %5ld(%5ld) U:%2ld(%2ld) B:%3ld(%4ld,%4ld)", resetCount, (millis()-vtxHeartbeat),
+ dataSent, maxDataSent, updates, maxUpdates, bufferUsed, maxBufferUsed, hdZeroMspPort.port->txBufferSize);
+ writeString(displayPort, 0, 17, lineBuffer, 0);
+}
+#endif
+
+/**
+ * Write only changed characters to the VTX
+ */
+static int drawScreen(displayPort_t *displayPort) // 250Hz
+{
+ static uint8_t counter = 0;
+
+ if ((counter++ % DRAW_FREQ_DENOM) == 0) {
+ uint8_t subcmd[COLS + 4];
+ uint8_t updateCount = 0;
+ subcmd[0] = MSP_WRITE_STRING;
+
+ int next = BITARRAY_FIND_FIRST_SET(dirty, 0);
+ while (next >= 0) {
+ // Look for sequential dirty characters on the same line for the same font page
+ int pos = next;
+ uint8_t row = pos / COLS;
+ uint8_t col = pos % COLS;
+ int endOfLine = row * COLS + COLS;
+ bool page = bitArrayGet(fontPage, pos);
+
+ uint8_t len = 4;
+ do {
+ bitArrayClr(dirty, pos);
+ subcmd[len++] = screen[pos++];
+
+ if (bitArrayGet(dirty, pos)) {
+ next = pos;
+ }
+ } while (next == pos && next < endOfLine && bitArrayGet(fontPage, next) == page);
+
+ subcmd[1] = row;
+ subcmd[2] = col;
+ subcmd[3] = page;
+ output(displayPort, MSP_DISPLAYPORT, subcmd, len);
+ updateCount++;
+ next = BITARRAY_FIND_FIRST_SET(dirty, pos);
+ }
+
+ if (updateCount > 0 || screenCleared) {
+ if (screenCleared) {
+ screenCleared = false;
+ }
+ subcmd[0] = MSP_DRAW_SCREEN;
+ output(displayPort, MSP_DISPLAYPORT, subcmd, 1);
+ }
+
+#ifdef HDZERO_STATS
+ printStats(displayPort, updateCount);
+#endif
+ checkVtxPresent();
+
+ if (vtxReset) {
+#ifdef HDZERO_STATS
+ resetCount++;
+#endif
+ clearScreen(displayPort);
+ vtxReset = false;
+ }
+ }
+
+ return 0;
+}
+
+static void resync(displayPort_t *displayPort)
+{
+ displayPort->rows = ROWS;
+ displayPort->cols = COLS;
+ setHdMode(displayPort);
+}
+
+static int screenSize(const displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return SCREENSIZE;
+}
+
+static uint32_t txBytesFree(const displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return mspSerialTxBytesFree();
+}
+
+static bool getFontMetadata(displayFontMetadata_t *metadata, const displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ metadata->charCount = 512;
+ metadata->version = FONT_VERSION;
+ return true;
+}
+
+static bool isTransferInProgress(const displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return false;
+}
+
+static bool isReady(displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return vtxActive;
+}
+
+static int grab(displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return 0;
+}
+
+static int heartbeat(displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return 0;
+}
+
+static int release(displayPort_t *displayPort)
+{
+ UNUSED(displayPort);
+ return 0;
+}
+
+static const displayPortVTable_t hdzeroOsdVTable = {
+ .grab = grab,
+ .release = release,
+ .clearScreen = clearScreen,
+ .drawScreen = drawScreen,
+ .screenSize = screenSize,
+ .writeString = writeString,
+ .writeChar = writeChar,
+ .isTransferInProgress = isTransferInProgress,
+ .heartbeat = heartbeat,
+ .resync = resync,
+ .txBytesFree = txBytesFree,
+};
+
+bool hdzeroOsdSerialInit(void)
+{
+ static volatile uint8_t txBuffer[TX_BUFFER_SIZE];
+ memset(&hdZeroMspPort, 0, sizeof(mspPort_t));
+
+ serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_HDZERO_OSD);
+ if (portConfig) {
+ // serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL,
+ // baudRates[portConfig->peripheral_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
+ serialPort_t *port = openSerialPort(portConfig->identifier, FUNCTION_HDZERO_OSD, NULL, NULL,
+ baudRates[BAUD_115200], MODE_RXTX, SERIAL_NOT_INVERTED);
+
+ if (port) {
+ // Use a bigger TX buffer size to accommodate the configuration menus
+ port->txBuffer = txBuffer;
+ port->txBufferSize = TX_BUFFER_SIZE;
+ port->txBufferTail = 0;
+ port->txBufferHead = 0;
+
+ resetMspPort(&hdZeroMspPort, port);
+
+ return true;
+ }
+ }
+
+ return false;
+}
+
+displayPort_t* hdzeroOsdDisplayPortInit(void)
+{
+ if (hdzeroOsdSerialInit()) {
+ hdZeroInit();
+ displayInit(&hdZeroOsdDisplayPort, &hdzeroOsdVTable);
+ return &hdZeroOsdDisplayPort;
+ }
+ return NULL;
+}
+
+/*
+ * Intercept MSP processor.
+ * VTX sends an MSP command every 125ms or so.
+ * VTX will have be marked as not ready if no commands received within VTX_TIMEOUT.
+ */
+static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn)
+{
+ if (vtxSeen && !vtxActive) {
+ vtxReset = true;
+ }
+
+ vtxSeen = vtxActive = true;
+ vtxHeartbeat = millis();
+
+ sbuf_t *dst = &reply->buf;
+
+ const uint8_t cmdMSP = cmd->cmd;
+ reply->cmd = cmd->cmd;
+ if (cmdMSP == MSP_FC_VARIANT) {
+ //We advertise as ARDU on this port for the prettier font
+ sbufWriteData(dst, "ARDU", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
+ return MSP_RESULT_ACK;
+ }
+
+ // #define MSP_SET_VTXTABLE_BAND 227
+ // #define MSP_SET_VTXTABLE_POWERLEVEL 228
+ // MSP_IMUF_CONFIG 227 -> MSP_SET_VTXTABLE_BAND (in betaflight)
+ // MSP_SET_IMUF_CONFIG 228 -> MSP_SET_VTXTABLE_POWERLEVEL (in betaflight)
+ if (cmdMSP == 227 || cmdMSP == 228) {
+ // We don't have VTX Tables so we just drop the packet and send ACK
+ return MSP_RESULT_ACK;
+ }
+
+ // Process MSP command
+ return mspProcessCommand(cmd, reply, mspPostProcessFn);
+}
+
+void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn)
+{
+ if (hdZeroMspPort.port) {
+ mspProcessCommand = mspProcessCommandFn;
+ mspSerialProcessOnePort(&hdZeroMspPort, MSP_SKIP_NON_MSP_DATA, hdZeroProcessMspCommand);
+ }
+}
+
+#endif // USE_HDZERO_OSD
diff --git a/src/main/io/displayport_hdzero_osd.h b/src/main/io/displayport_hdzero_osd.h
new file mode 100644
index 0000000000..2c00245421
--- /dev/null
+++ b/src/main/io/displayport_hdzero_osd.h
@@ -0,0 +1,34 @@
+
+/*
+ * This file is part of INAV Project.
+ *
+ * This Source Code Form is subject to the terms of the Mozilla Public
+ * License, v. 2.0. If a copy of the MPL was not distributed with this file,
+ * You can obtain one at http://mozilla.org/MPL/2.0/.
+ *
+ * Alternatively, the contents of this file may be used under the terms
+ * of the GNU General Public License Version 3, as described below:
+ *
+ * This file is free software: you may copy, redistribute 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.
+ *
+ * This file 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 this program. If not, see http://www.gnu.org/licenses/.
+ */
+
+#pragma once
+
+#include "osd.h"
+#include "msp/msp_serial.h"
+
+typedef struct displayPort_s displayPort_t;
+
+displayPort_t *hdzeroOsdDisplayPortInit(void);
+void hdzeroOsdSerialProcess(mspProcessCommandFnPtr mspProcessCommandFn);
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 3021608773..745ea9ce5f 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -1155,7 +1155,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse) {
if (!osdDisplayPortToUse) {
return;
}
- BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31, 31));
+ BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63, 63));
osdDisplayPort = osdDisplayPortToUse;
#ifdef USE_CMS
cmsDisplayPortRegister(osdDisplayPort);
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index 824506ce82..4667716eb2 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -28,13 +28,13 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define OSD_ELEMENT_BUFFER_LENGTH 32
-#define VISIBLE_FLAG 0x0800
+#define VISIBLE_FLAG 0x2000
#define VISIBLE(x) (x & VISIBLE_FLAG)
-#define OSD_POS_MAX 0x3FF
-#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x3FF) // For CLI values
+#define OSD_POS_MAX 0xFFF
+#define OSD_POSCFG_MAX (VISIBLE_FLAG|0xFFF) // For CLI values
// Character coordinate
-#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
+#define OSD_POSITION_BITS 6 // 6 bits gives a range 0-63
#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
#define OSD_X(x) (x & OSD_POSITION_XY_MASK)
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index 1d130f2fe2..da16313d93 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -214,11 +214,11 @@ portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialP
return portConfig->functionMask == function ? PORTSHARING_NOT_SHARED : PORTSHARING_SHARED;
}
-bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction) {
+bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction) {
return (portConfig) && (portConfig->functionMask & sharedWithFunction) && (portConfig->functionMask & functionMask);
}
-serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction) {
+serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction) {
for (unsigned i = 0; i < SERIAL_PORT_COUNT; i++) {
const serialPortConfig_t *candidate = &serialConfig()->portConfigs[i];
if (isSerialPortShared(candidate, functionMask, sharedWithFunction)) {
diff --git a/src/main/io/serial.h b/src/main/io/serial.h
index 071cdf45b6..3ec4a1a38c 100644
--- a/src/main/io/serial.h
+++ b/src/main/io/serial.h
@@ -50,6 +50,7 @@ typedef enum {
FUNCTION_VTX_TRAMP = (1 << 13), // 8192
FUNCTION_RCDEVICE = (1 << 14), // 16384
FUNCTION_LIDAR_TF = (1 << 15), // 32768
+ FUNCTION_HDZERO_OSD = (1 << 16), // 65536
} serialPortFunction_e;
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
@@ -107,13 +108,13 @@ typedef struct serialPortUsage_s {
serialPortIdentifier_e identifier;
} serialPortUsage_t;
-serialPort_t *findSharedSerialPort(uint16_t functionMask, serialPortFunction_e sharedWithFunction);
+serialPort_t *findSharedSerialPort(uint32_t functionMask, serialPortFunction_e sharedWithFunction);
//
// configuration
//
typedef struct serialPortConfig_s {
- uint16_t functionMask;
+ uint32_t functionMask;
serialPortIdentifier_e identifier;
uint8_t msp_baudrateIndex;
uint8_t gps_baudrateIndex;
@@ -145,7 +146,7 @@ serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function);
serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function);
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function);
-bool isSerialPortShared(const serialPortConfig_t *portConfig, uint16_t functionMask, serialPortFunction_e sharedWithFunction);
+bool isSerialPortShared(const serialPortConfig_t *portConfig, uint32_t functionMask, serialPortFunction_e sharedWithFunction);
void pgResetFn_serialConfig(serialConfig_t *serialConfig); //!!TODO remove need for this
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e identifier);
diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c
index 9a32ffc400..4cc7b40f70 100644
--- a/src/main/msp/msp_serial.c
+++ b/src/main/msp/msp_serial.c
@@ -41,10 +41,9 @@
static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
-static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort, bool sharedWithTelemetry) {
+void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort) {
memset(mspPortToReset, 0, sizeof(mspPort_t));
mspPortToReset->port = serialPort;
- mspPortToReset->sharedWithTelemetry = sharedWithTelemetry;
}
void mspSerialAllocatePorts(void) {
@@ -58,8 +57,8 @@ void mspSerialAllocatePorts(void) {
}
serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
if (serialPort) {
- bool sharedWithTelemetry = isSerialPortShared(portConfig, FUNCTION_MSP, TELEMETRY_PORT_FUNCTIONS_MASK);
- resetMspPort(mspPort, serialPort, sharedWithTelemetry);
+ resetMspPort(mspPort, serialPort);
+ mspPort->sharedWithTelemetry = isSerialPortShared(portConfig, FUNCTION_MSP, TELEMETRY_PORT_FUNCTIONS_MASK);
portIndex++;
}
portConfig = findNextSerialPortConfig(FUNCTION_MSP);
@@ -505,3 +504,54 @@ uint32_t mspSerialTxBytesFree(void) {
}
return ret;
}
+
+int mspSerialPushPort(uint16_t cmd, const uint8_t *data, int datalen, mspPort_t *mspPort, mspVersion_e version)
+{
+ uint8_t pushBuf[MSP_PORT_OUTBUF_SIZE];
+
+ mspPacket_t push = {
+ .buf = { .ptr = pushBuf, .end = ARRAYEND(pushBuf), },
+ .cmd = cmd,
+ .result = 0,
+ };
+
+ sbufWriteData(&push.buf, data, datalen);
+
+ sbufSwitchToReader(&push.buf, pushBuf);
+
+ return mspSerialEncode(mspPort, &push, version);
+}
+
+void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn)
+{
+ mspPostProcessFnPtr mspPostProcessFn = NULL;
+
+ if (serialRxBytesWaiting(mspPort->port)) {
+ // There are bytes incoming - abort pending request
+ mspPort->lastActivityMs = millis();
+ mspPort->pendingRequest = MSP_PENDING_NONE;
+
+ // Process incoming bytes
+ while (serialRxBytesWaiting(mspPort->port)) {
+ const uint8_t c = serialRead(mspPort->port);
+ const bool consumed = mspSerialProcessReceivedData(mspPort, c);
+
+ if (!consumed && evaluateNonMspData == MSP_EVALUATE_NON_MSP_DATA) {
+ mspEvaluateNonMspData(mspPort, c);
+ }
+
+ if (mspPort->c_state == MSP_COMMAND_RECEIVED) {
+ mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn);
+ break; // process one command at a time so as not to block.
+ }
+ }
+
+ if (mspPostProcessFn) {
+ waitForSerialPortToFinishTransmitting(mspPort->port);
+ mspPostProcessFn(mspPort->port);
+ }
+ }
+ else {
+ mspProcessPendingRequest(mspPort);
+ }
+}
\ No newline at end of file
diff --git a/src/main/msp/msp_serial.h b/src/main/msp/msp_serial.h
index b1718323a0..cac9ca8723 100644
--- a/src/main/msp/msp_serial.h
+++ b/src/main/msp/msp_serial.h
@@ -22,6 +22,7 @@
#include "drivers/time.h"
#include "interface/msp.h"
+#include "io/serial.h"
// Each MSP port requires state and a receive buffer, revisit this default if someone needs more than 3 MSP ports.
#define MAX_MSP_PORT_COUNT 3
@@ -122,3 +123,6 @@ void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialReleaseSharedTelemetryPorts(void);
int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction);
uint32_t mspSerialTxBytesFree(void);
+int mspSerialPushPort(uint16_t cmd, const uint8_t *data, int datalen, mspPort_t *mspPort, mspVersion_e version);
+void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort);
+void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
\ No newline at end of file
diff --git a/src/main/target/common_fc_pre.h b/src/main/target/common_fc_pre.h
index 4d378c10ac..1da8a2399c 100644
--- a/src/main/target/common_fc_pre.h
+++ b/src/main/target/common_fc_pre.h
@@ -170,6 +170,7 @@
#define MSP_OVER_CLI
#define USE_OSD
#define USE_OSD_OVER_MSP_DISPLAYPORT
+#define USE_HDZERO_OSD
#define USE_PINIO
#define USE_PINIOBOX
#define USE_RCDEVICE
diff --git a/src/test/unit/rx_ibus_unittest.cc b/src/test/unit/rx_ibus_unittest.cc
index 5f1ca6571f..ffd3f6bf9f 100644
--- a/src/test/unit/rx_ibus_unittest.cc
+++ b/src/test/unit/rx_ibus_unittest.cc
@@ -90,7 +90,7 @@ static serialPortStub_t serialWriteStub;
static bool portIsShared = false;
bool isSerialPortShared(const serialPortConfig_t *portConfig,
- uint16_t functionMask,
+ uint32_t functionMask,
serialPortFunction_e sharedWithFunction)
{
EXPECT_EQ(portConfig, findSerialPortConfig_stub_retval);
diff --git a/src/test/unit/telemetry_ibus_unittest.cc b/src/test/unit/telemetry_ibus_unittest.cc
index e1c093b0c5..1637180768 100644
--- a/src/test/unit/telemetry_ibus_unittest.cc
+++ b/src/test/unit/telemetry_ibus_unittest.cc
@@ -185,7 +185,7 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
bool isSerialPortShared(const serialPortConfig_t *portConfig,
- uint16_t functionMask,
+ uint32_t functionMask,
serialPortFunction_e sharedWithFunction)
{
EXPECT_EQ(findSerialPortConfig_stub_retval, portConfig);
From 3335565190b753fe09cf0367f349023b2f3e6781 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 7 Feb 2024 10:49:54 -0600
Subject: [PATCH 05/33] modding HDZero PR #755 to revert to 5bit compatible OSD
element positioning. (#958)
* HDZero - 5bit backward compatible OSD positioning
* hdzero - 30hz OSD and dont periodically force-advertise fc-variant
* hdzero - comment out unused code
* hdzero - unneeded comma
* hdzero - stupid alignment
---
src/main/drivers/display_font_metadata.h | 10 +++---
src/main/interface/msp_protocol.h | 2 +-
src/main/interface/settings.c | 2 +-
src/main/io/displayport_hdzero_osd.c | 44 ++++++++++++++----------
src/main/io/osd.c | 4 +--
src/main/io/osd.h | 16 +++++----
src/main/io/serial.h | 2 +-
7 files changed, 45 insertions(+), 35 deletions(-)
diff --git a/src/main/drivers/display_font_metadata.h b/src/main/drivers/display_font_metadata.h
index ebef4b635a..961c6b0751 100644
--- a/src/main/drivers/display_font_metadata.h
+++ b/src/main/drivers/display_font_metadata.h
@@ -10,11 +10,11 @@ typedef struct displayFontMetadata_s {
uint16_t charCount;
} displayFontMetadata_t;
-// 'I', 'N', 'A', 'V'
-#define FONT_CHR_IS_METADATA(chr) ((chr)->data[0] == 'I' && \
- (chr)->data[1] == 'N' && \
- (chr)->data[2] == 'A' && \
- (chr)->data[3] == 'V')
+// 'E', 'M', 'U', 'F'
+#define FONT_CHR_IS_METADATA(chr) ((chr)->data[0] == 'E' && \
+ (chr)->data[1] == 'M' && \
+ (chr)->data[2] == 'U' && \
+ (chr)->data[3] == 'F')
#define FONT_METADATA_CHR_INDEX 255
// Used for runtime detection of display drivers that might
diff --git a/src/main/interface/msp_protocol.h b/src/main/interface/msp_protocol.h
index 0f7f5d3d7a..8716c30f0c 100644
--- a/src/main/interface/msp_protocol.h
+++ b/src/main/interface/msp_protocol.h
@@ -64,7 +64,7 @@
// API VERSION
#define API_VERSION_MAJOR 1 // increment when major changes are made
-#define API_VERSION_MINOR 52 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
+#define API_VERSION_MINOR 53 // increment after a release, to set the version for all changes to go into the following release (if no changes to MSP are made between the releases, this can be reverted before the release)
#define API_VERSION_LENGTH 2
diff --git a/src/main/interface/settings.c b/src/main/interface/settings.c
index da26165c1e..3b7d50938c 100644
--- a/src/main/interface/settings.c
+++ b/src/main/interface/settings.c
@@ -368,7 +368,7 @@ static const char * const lookupTableRescueSanityType[] = {
#ifdef USE_MAX7456
static const char * const lookupTableVideoSystem[] = {
- "AUTO", "PAL", "NTSC", "HDZERO"
+ "AUTO", "PAL", "NTSC", "HD"
};
#endif // USE_MAX7456
diff --git a/src/main/io/displayport_hdzero_osd.c b/src/main/io/displayport_hdzero_osd.c
index 9bbcae6d0e..5cd0b22f2a 100644
--- a/src/main/io/displayport_hdzero_osd.c
+++ b/src/main/io/displayport_hdzero_osd.c
@@ -56,7 +56,8 @@ FILE_COMPILE_FOR_SPEED
#define MSP_WRITE_STRING 3
#define MSP_DRAW_SCREEN 4
#define MSP_SET_OPTIONS 5
-#define DRAW_FREQ_DENOM 4 // 60Hz
+//#define DRAW_FREQ_DENOM 4 // 60Hz
+#define DRAW_FREQ_DENOM 8 // 30Hz
#define TX_BUFFER_SIZE 1024
#define VTX_TIMEOUT 1000 // 1 second timer
@@ -279,13 +280,14 @@ static uint32_t txBytesFree(const displayPort_t *displayPort)
return mspSerialTxBytesFree();
}
-static bool getFontMetadata(displayFontMetadata_t *metadata, const displayPort_t *displayPort)
-{
- UNUSED(displayPort);
- metadata->charCount = 512;
- metadata->version = FONT_VERSION;
- return true;
-}
+//Commented out as compiler reports unused.
+//static bool getFontMetadata(displayFontMetadata_t *metadata, const displayPort_t *displayPort)
+//{
+// UNUSED(displayPort);
+// metadata->charCount = 512;
+// metadata->version = FONT_VERSION;
+// return true;
+//}
static bool isTransferInProgress(const displayPort_t *displayPort)
{
@@ -293,11 +295,12 @@ static bool isTransferInProgress(const displayPort_t *displayPort)
return false;
}
-static bool isReady(displayPort_t *displayPort)
-{
- UNUSED(displayPort);
- return vtxActive;
-}
+//Commented out as compiler reports unused.
+//static bool isReady(displayPort_t *displayPort)
+//{
+// UNUSED(displayPort);
+// return vtxActive;
+//}
static int grab(displayPort_t *displayPort)
{
@@ -383,15 +386,18 @@ static mspResult_e hdZeroProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply,
vtxSeen = vtxActive = true;
vtxHeartbeat = millis();
- sbuf_t *dst = &reply->buf;
+ //Commented out as compiler reports unused.
+ //sbuf_t *dst = &reply->buf;
const uint8_t cmdMSP = cmd->cmd;
reply->cmd = cmd->cmd;
- if (cmdMSP == MSP_FC_VARIANT) {
- //We advertise as ARDU on this port for the prettier font
- sbufWriteData(dst, "ARDU", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
- return MSP_RESULT_ACK;
- }
+
+ //Apparently no longer required as HDZero will send the MSP/EEPROM value of "EMUF" fc_variant
+ //if (cmdMSP == MSP_FC_VARIANT) {
+ // //We advertise as EMUF on this port for the prettier font
+ // sbufWriteData(dst, "EMUF", FLIGHT_CONTROLLER_IDENTIFIER_LENGTH);
+ // return MSP_RESULT_ACK;
+ //}
// #define MSP_SET_VTXTABLE_BAND 227
// #define MSP_SET_VTXTABLE_POWERLEVEL 228
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 745ea9ce5f..937b71c694 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -220,7 +220,7 @@ static const uint8_t osdElementDisplayOrder[] = {
OSD_COMPASS_BAR
};
-PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 4);
+PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 5);
/**
* Gets the correct altitude symbol for the current unit system
@@ -1155,7 +1155,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse) {
if (!osdDisplayPortToUse) {
return;
}
- BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63, 63));
+ BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(63, 31));
osdDisplayPort = osdDisplayPortToUse;
#ifdef USE_CMS
cmsDisplayPortRegister(osdDisplayPort);
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index 4667716eb2..02e01c14c2 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -30,14 +30,18 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define VISIBLE_FLAG 0x2000
#define VISIBLE(x) (x & VISIBLE_FLAG)
-#define OSD_POS_MAX 0xFFF
-#define OSD_POSCFG_MAX (VISIBLE_FLAG|0xFFF) // For CLI values
+
+#define OSD_POS_MAX 0x7FF
+#define OSD_POSCFG_MAX (VISIBLE_FLAG|0x7FF) // For CLI values
// Character coordinate
-#define OSD_POSITION_BITS 6 // 6 bits gives a range 0-63
-#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
-#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
-#define OSD_X(x) (x & OSD_POSITION_XY_MASK)
+#define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
+#define OSD_POSITION_BIT_XHD 10 // extra bit used to extend X range in a backward compatible manner for HD displays
+#define OSD_POSITION_XHD_MASK (1 << OSD_POSITION_BIT_XHD)
+#define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
+#define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((x << (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)) & OSD_POSITION_XHD_MASK) | \
+ ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
+#define OSD_X(x) ((x & OSD_POSITION_XY_MASK) | ((x & OSD_POSITION_XHD_MASK) >> (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)))
#define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
// Timer configuration
diff --git a/src/main/io/serial.h b/src/main/io/serial.h
index 3ec4a1a38c..fa4eeebc8a 100644
--- a/src/main/io/serial.h
+++ b/src/main/io/serial.h
@@ -50,7 +50,7 @@ typedef enum {
FUNCTION_VTX_TRAMP = (1 << 13), // 8192
FUNCTION_RCDEVICE = (1 << 14), // 16384
FUNCTION_LIDAR_TF = (1 << 15), // 32768
- FUNCTION_HDZERO_OSD = (1 << 16), // 65536
+ FUNCTION_HDZERO_OSD = (1 << 16) // 65536
} serialPortFunction_e;
#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_FRSKY_HUB | FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_MAVLINK)
From ebc98f03cfb0abc9e8d84f6ed6f73eef60dba1f0 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Sat, 17 Feb 2024 12:48:22 -0600
Subject: [PATCH 06/33] 20240217 fix merge conflict OSD 0x0800 (#961)
fix merge conflict for Analog OSD VISIBLE_FLAG 0x0800
---
src/main/io/osd.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index 02e01c14c2..886a3080d6 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -28,7 +28,7 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define OSD_ELEMENT_BUFFER_LENGTH 32
-#define VISIBLE_FLAG 0x2000
+#define VISIBLE_FLAG 0x0800
#define VISIBLE(x) (x & VISIBLE_FLAG)
#define OSD_POS_MAX 0x7FF
From 8be02888b361fe95c92682ccf53528c1771feaa4 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 22 Feb 2024 11:26:32 -0600
Subject: [PATCH 07/33] Add ICM-426xx IMU to list of IMUs with overflow
protection (#964)
ICM426xx have overflow protection
---
src/main/sensors/gyro.c | 2 ++
1 file changed, 2 insertions(+)
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index 9ec6a642fc..37bf1856cf 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -627,6 +627,8 @@ static bool gyroInitSensor(gyroSensor_t *gyroSensor) {
case GYRO_MPU6000:
case GYRO_MPU6500:
case GYRO_MPU9250:
+ case GYRO_ICM42688P:
+ case GYRO_ICM42605:
gyroSensor->gyroDev.gyroHasOverflowProtection = true;
break;
case GYRO_ICM20601:
From 752257b616c6a4cb6dab5937caf2261fcc6e1f43 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 23 Feb 2024 16:02:52 -0600
Subject: [PATCH 08/33] remove extraneous files (#972)
* CRASHTESTF7 was a fake target (template); no longer needed
* remove extraneous files
---
src/main/target/CRASHTESTF7/TALONF7V2.md | 12 --
src/main/target/CRASHTESTF7/config.c | 36 -----
src/main/target/CRASHTESTF7/target.c | 44 -----
src/main/target/CRASHTESTF7/target.h | 153 ------------------
src/main/target/CRASHTESTF7/target.mk | 8 -
.../target/STM32F7X2/config/CLRACINGF7.config | 89 ----------
src/main/target/STM32F7X2/config/NERO.config | 88 ----------
7 files changed, 430 deletions(-)
delete mode 100644 src/main/target/CRASHTESTF7/TALONF7V2.md
delete mode 100644 src/main/target/CRASHTESTF7/config.c
delete mode 100644 src/main/target/CRASHTESTF7/target.c
delete mode 100644 src/main/target/CRASHTESTF7/target.h
delete mode 100644 src/main/target/CRASHTESTF7/target.mk
delete mode 100644 src/main/target/STM32F7X2/config/CLRACINGF7.config
delete mode 100644 src/main/target/STM32F7X2/config/NERO.config
diff --git a/src/main/target/CRASHTESTF7/TALONF7V2.md b/src/main/target/CRASHTESTF7/TALONF7V2.md
deleted file mode 100644
index 8624f95d55..0000000000
--- a/src/main/target/CRASHTESTF7/TALONF7V2.md
+++ /dev/null
@@ -1,12 +0,0 @@
-MCU: STM32F722RE
-IMU: ICM-20602
-IMU Interrupt: yes
-BARO: NO
-VCP: YES
-Hardware UARTS: 6 uarts
-OSD: uses a AB7456 chip
-Blackbox: flash Chip
-PPM/UART NOT Shared: YES
-Battery Voltage Sensor: 10:1
-Current sensor: from 4 in 1 socket
-Integrated Voltage Regulator: 1.5A 5v/v1 2A 5v/v2
diff --git a/src/main/target/CRASHTESTF7/config.c b/src/main/target/CRASHTESTF7/config.c
deleted file mode 100644
index b9c6b5aea5..0000000000
--- a/src/main/target/CRASHTESTF7/config.c
+++ /dev/null
@@ -1,36 +0,0 @@
-/*
- * This file is part of Cleanflight and Betaflight.
- *
- * Cleanflight and Betaflight are free software. You can redistribute
- * this software and/or modify this software 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.
- *
- * Cleanflight and Betaflight are distributed in the hope that they
- * 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 this software.
- *
- * If not, see .
- */
-
-#include
-#include
-#include
-
-#include "platform.h"
-
-#include "pg/pinio.h"
-#include "pg/piniobox.h"
-
-#ifdef USE_TARGET_CONFIG
-
-
-void targetConfiguration(void) {
- pinioBoxConfigMutable()->permanentId[0] = 40;
-}
-#endif
diff --git a/src/main/target/CRASHTESTF7/target.c b/src/main/target/CRASHTESTF7/target.c
deleted file mode 100644
index c2489acc41..0000000000
--- a/src/main/target/CRASHTESTF7/target.c
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- * This file is part of Cleanflight and Betaflight.
- *
- * Cleanflight and Betaflight are free software. You can redistribute
- * this software and/or modify this software 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.
- *
- * Cleanflight and Betaflight are distributed in the hope that they
- * 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 this software.
- *
- * If not, see .
- */
-#include
-
-#include "platform.h"
-#include "drivers/io.h"
-
-#include "drivers/dma.h"
-#include "drivers/timer.h"
-#include "drivers/timer_def.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
-// FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION
- DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
-
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1
- DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // D2-ST2/D2-ST4 MOTOR4
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST4 MOTOR5
- DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // D2-ST7 MOTOR7
-
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5
-
-
-};
diff --git a/src/main/target/CRASHTESTF7/target.h b/src/main/target/CRASHTESTF7/target.h
deleted file mode 100644
index 859462f588..0000000000
--- a/src/main/target/CRASHTESTF7/target.h
+++ /dev/null
@@ -1,153 +0,0 @@
-/*
- * This file is part of Cleanflight and Betaflight.
- *
- * Cleanflight and Betaflight are free software. You can redistribute
- * this software and/or modify this software 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.
- *
- * Cleanflight and Betaflight are distributed in the hope that they
- * 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 this software.
- *
- * If not, see .
- */
-
-#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X2" //not sure if this even shows, but defaults on BF as STM used
-#define USBD_PRODUCT_STRING "BotF7" //board name on configurator drop down menu, flasher tab
-#define TARGET_MANUFACTURER_IDENTIFIER "BQEio" //Manufacturer abbreviation
-
-#define USE_TARGET_CONFIG
-
-#define ENABLE_DSHOT_DMAR true //Dshot default
-
-//Aux
-#define LED0_PIN PB0 //resource led 1
-
-#define USE_BEEPER
-#define BEEPER_PIN PB4 //resource beeper 1
-#define BEEPER_INVERTED //set beeper_inversion = on
-
-#define USE_PINIO
-#define PINIO1_PIN PA14 // VTX power switcher
-#define USE_PINIOBOX
-
-
-//define camera control
-#define CAMERA_CONTROL_PIN PB3 // resource camera_control 1
-
-//MPU-6000
-#define USE_GYRO //declaring usage of gyro accelerometer and Spi access
-#define USE_ACC
-#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_SPI_MPU6000
-#define USE_EXTI
-#define USE_MPU_DATA_READY_SIGNAL
-
-#define MPU_INT_EXTI PC4 //gyro_1_exti_pin for mpu6000
-#define MPU6000_CS_PIN PA4 //GYRO_1_CS_PIN
-#define MPU6000_SPI_INSTANCE SPI1 //GYRO_1_SPI_INSTANCE
-#define GYRO_MPU6000_ALIGN CW0_DEG //set gyro_1_align
-#define ACC_MPU6000_ALIGN CW0_DEG //set accel_1_align (normally same as gyro 1)
-
-// OSD
-#define USE_MAX7456 //osd driver
-#define MAX7456_SPI_INSTANCE SPI3 // set max7456
-#define MAX7456_SPI_CS_PIN PA15 // resource osd_cs 1
-#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD) // 10MHz
-#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
-
-// Blackbox
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-#define USE_FLASHFS // enable flash blackbox
-#define USE_FLASH_M25P16 //defines which driver type
-#define FLASH_CS_PIN PB12 //resource flash_cs
-#define FLASH_SPI_INSTANCE SPI2 //set flash spi bus
-
-// Uarts
-#define USE_UART1 //enable corresponding UARTS
-#define UART1_RX_PIN PA10 //resource serial_rx 1
-#define UART1_TX_PIN PA9 //resource serial_tx 1
-
-#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_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 USE_SOFTSERIAL1
-#define SERIAL_PORT_COUNT 7 //VCP, USART1, USART2,USART3,USART4,USART5,USART6
-
-// ESC
-#define USE_ADC // enable adc
-#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC //define source.. same as battery tab in configurator
-#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
-#define CURRENT_METER_ADC_PIN PC1 //resource adc_curr
-#define VBAT_ADC_PIN PC2 //resource adc_batt
-#define RSSI_ADC_PIN PC3 //resource adc_rssi
-#define CURRENT_METER_SCALE_DEFAULT 150 // 3.3/120A = 25mv/A
-#define VBAT_SCALE 160 //configurator tab voltage scale
-
-
-
-
-// SPI devices
-#define USE_SPI
-#define USE_SPI_DEVICE_1
-#define USE_SPI_DEVICE_2
-#define USE_SPI_DEVICE_3
-
-#define SPI1_NSS_PIN PA4 //resource usually matches cs pin of device that calls for it
-#define SPI1_SCK_PIN PA5 // resource spi_sck 1
-#define SPI1_MISO_PIN PA6 //resource spi_miso 1
-#define SPI1_MOSI_PIN PA7 //resource spi_mosi
-
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define SPI3_NSS_PIN PA15
-#define SPI3_SCK_PIN PC10
-#define SPI3_MISO_PIN PC11
-#define SPI3_MOSI_PIN PB5
-
-// USB
-#define USE_VCP
-#define BINDPLUG_PIN PB2
-#define SERIALRX_PROVIDER SERIALRX_CRSF
-#define SERIALRX_UART SERIAL_PORT_USART3
-
-//FEATURE
-#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE)
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-
-// IO Ports
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
-
-// timers
-#define USABLE_TIMER_CHANNEL_COUNT 9 //updated timer count to compensate for Nf Motor 4, total timers defined in target.c
-#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) //update based on update CLRACINGF7 Target BF4.1+ timers defined, enumerated as per use
diff --git a/src/main/target/CRASHTESTF7/target.mk b/src/main/target/CRASHTESTF7/target.mk
deleted file mode 100644
index 8626fa065d..0000000000
--- a/src/main/target/CRASHTESTF7/target.mk
+++ /dev/null
@@ -1,8 +0,0 @@
-F7X2RE_TARGETS += $(TARGET)
-FEATURES += VCP ONBOARDFLASH
-TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/max7456.c
diff --git a/src/main/target/STM32F7X2/config/CLRACINGF7.config b/src/main/target/STM32F7X2/config/CLRACINGF7.config
deleted file mode 100644
index 2675de0d93..0000000000
--- a/src/main/target/STM32F7X2/config/CLRACINGF7.config
+++ /dev/null
@@ -1,89 +0,0 @@
-# Betaflight / STM32F745 (S745) 4.0.0 Mar 10 2019 / 21:49:53 (d6138c41e) MSP API: 1.41
-
-board_name CLRACINGF7
-manufacturer_id CLRC
-
-# BEEPER
-resource BEEPER 1 PB4
-set beeper_inversion = ON
-set beeper_od = OFF
-
-# INDICATOR LED
-resource LED 1 B00
-
-#MOTOR AND LED
-resource MOTOR 1 B06
-resource MOTOR 2 B07
-resource MOTOR 3 B08
-resource MOTOR 4 B09
-resource MOTOR 5 B01
-resource LED_STRIP 1 B01
-
-# UARTS
-resource SERIAL_TX 1 A09
-resource SERIAL_TX 2 A02
-resource SERIAL_TX 3 B10
-resource SERIAL_TX 4 A00
-resource SERIAL_TX 5 C12
-resource SERIAL_TX 6 C06
-resource SERIAL_RX 1 A10
-resource SERIAL_RX 2 A03
-resource SERIAL_RX 3 B11
-resource SERIAL_RX 4 A01
-resource SERIAL_RX 5 D02
-resource SERIAL_RX 6 C07
-
-#SPI BUS
-resource SPI_SCK 1 A05
-resource SPI_SCK 2 B13
-resource SPI_SCK 3 C10
-resource SPI_MISO 1 A06
-resource SPI_MISO 2 B14
-resource SPI_MISO 3 C11
-resource SPI_MOSI 1 A07
-resource SPI_MOSI 2 B15
-resource SPI_MOSI 3 B05
-
-#ADC
-resource ADC_BATT 1 C02
-resource ADC_RSSI 1 C03
-resource ADC_CURR 1 C01
-set current_meter = ADC
-set battery_meter = ADC
-
-#SPI FLASH
-resource FLASH_CS 1 B03
-set flash_spi_bus = 2
-
-#OSD
-resource OSD_CS 1 A15
-set max7456_spi_bus = 3
-
-#GYRO
-resource GYRO_EXTI 1 C04
-resource GYRO_CS 1 A04
-set gyro_1_bustype = SPI
-set gyro_1_spibus = 1
-set gyro_1_sensor_align = CW0
-
-# timer
-timer B03 0
-timer B06 0
-timer B07 0
-timer B08 0
-timer B09 0
-timer B01 1
-
-# dma
-dma ADC 1 1 # ADC 1: DMA2 Stream 4 Channel 0
-dma pin B03 0 # pin B03: DMA1 Stream 6 Channel 3
-dma pin B06 0 # pin B06: DMA1 Stream 0 Channel 2
-dma pin B07 0 # pin B07: DMA1 Stream 3 Channel 2
-dma pin B08 0 # pin B08: DMA1 Stream 7 Channel 2
-dma pin B01 0 # pin B01: DMA1 Stream 2 Channel 5
-
-# master
-set system_hse_mhz = 8
-set dashboard_i2c_bus = 1
-resource RX_BIND_PLUG 1 B02
-resource CAMERA_CONTROL 1 B03
diff --git a/src/main/target/STM32F7X2/config/NERO.config b/src/main/target/STM32F7X2/config/NERO.config
deleted file mode 100644
index 48672e785d..0000000000
--- a/src/main/target/STM32F7X2/config/NERO.config
+++ /dev/null
@@ -1,88 +0,0 @@
-# Usual lawyer stuff here?
-
-# Name: NERO
-# Description: NERO Standard target configuration
-# XXX We need something that remembers which config was loaded
-
-defaults nosave
-
-# Basic I/O
-resource LED 1 B06
-resource LED 2 B05
-resource LED 3 B04
-resource beeper C1
-set beeper_inversion = ON
-set beeper_od = OFF
-
-# Buses
-resource I2C_SCL 1 B08
-resource I2C_SDA 1 B09
-
-resource SPI_SCK 1 A05
-resource SPI_MISO 1 A06
-resource SPI_MOSI 1 A07
-
-resource SPI_SCK 2 B13
-resource SPI_MISO 2 B14
-resource SPI_MOSI 2 B15
-
-resource SPI_SCK 3 C10
-resource SPI_MISO 3 C11
-resource SPI_MOSI 3 C12
-
-# SPI CS pins to pre-initialize
-resource SPI_PREINIT_IPU 1 C04 // MPU6500
-resource SPI_PREINIT_IPU 2 A15 // SDCARD
-
-# Timers
-# First four timers
-# timer is zero origin
-timer A0 1
-timer A1 1
-timer A2 1
-timer A3 1
-resource MOTOR 1 A0
-resource MOTOR 2 A1
-resource MOTOR 3 A2
-resource MOTOR 4 A3
-
-# DMA stream conflict if burst mode is not used
-# XXX Need a mechanism to specify dmaopt
-set dshot_burst = ON
-
-# Remaining timers
-timer B0 1
-timer B1 1
-timer C7 1
-timer C8 1
-timer C9 1
-resource LED_STRIP B0
-resource PPM C7
-
-# Serial ports
-
-resource SERIAL_TX 1 A9
-resource SERIAL_RX 1 A10
-
-resource SERIAL_TX 3 B10
-resource SERIAL_RX 3 B11
-
-resource SERIAL_TX 6 C6
-resource SERIAL_RX 6 C7
-
-# ADC
-
-resource ADC_BATT 1 C03
-
-# Remaining
-
-resource ESCSERIAL 1 C07
-resource SDCARD_CS 1 A15
-resource SDCARD_DETECT 1 D02
-
-# Some configs
-
-FEATURE RX_SERIAL
-set serialrx_provider = SBUS
-serial 5 64 115200 57600 0 115200
-set battery_meter = ADC
From 9f0358c0f80533e884c3af464600f6556547b84b Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Mon, 26 Feb 2024 09:02:00 -0600
Subject: [PATCH 09/33] fix compiler warning - FLWO_FLYWOOF411FR 10 timers not
7 (#971)
---
src/main/target/FLWO_FLYWOOF411FR/target.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.h b/src/main/target/FLWO_FLYWOOF411FR/target.h
index 42724e2881..3e95bdc8cf 100644
--- a/src/main/target/FLWO_FLYWOOF411FR/target.h
+++ b/src/main/target/FLWO_FLYWOOF411FR/target.h
@@ -169,5 +169,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
-#define USABLE_TIMER_CHANNEL_COUNT 7
+#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4) )
From c9d0d7b7e0b2230fdf96b34ccbe5e1cda2a0effa Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 27 Feb 2024 10:41:05 -0600
Subject: [PATCH 10/33] fix compiler warning - comment out getGhstFrame
(defined but not used) (#966)
---
src/main/telemetry/ghst.c | 3 +++
1 file changed, 3 insertions(+)
diff --git a/src/main/telemetry/ghst.c b/src/main/telemetry/ghst.c
index b8dad14b4a..22b76681cb 100644
--- a/src/main/telemetry/ghst.c
+++ b/src/main/telemetry/ghst.c
@@ -82,9 +82,12 @@ static void ghstInitializeFrame(sbuf_t *dst)
sbufWriteU8(dst, GHST_ADDR_RX);
}
+//compiler reports unused
+/*
STATIC_UNIT_TESTED uint8_t *getGhstFrame(){
return ghstFrame;
}
+*/
static void ghstFinalize(sbuf_t *dst)
{
From f4686c930dc158ed2f9eb5111da318f0434700b1 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 27 Feb 2024 10:43:02 -0600
Subject: [PATCH 11/33] fix compiler warnings - Beesign: comment out unused
code; fix function call parenthasis; (#967)
---
src/main/drivers/beesign.c | 5 ++++-
1 file changed, 4 insertions(+), 1 deletion(-)
diff --git a/src/main/drivers/beesign.c b/src/main/drivers/beesign.c
index ea6bfeee53..a84e6997c1 100644
--- a/src/main/drivers/beesign.c
+++ b/src/main/drivers/beesign.c
@@ -101,10 +101,13 @@ static uint8_t beesignCRC(const beesign_frame_t *pPackage) {
return crc;
}
+// compiler reports unused
+/*
static uint8_t beesignChkID(uint8_t id) {
UNUSED(id);
return BEESIGN_OK;
}
+*/
uint8_t beesignReceive(uint8_t **pRcvFrame) {
if (!receiveFrameValid) {
@@ -608,7 +611,7 @@ bool checkBeesignSerialPort(void) {
void beesignUpdate(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
- if (checkBeesignSerialPort) {
+ if (checkBeesignSerialPort()) {
#ifdef USE_OSD_BEESIGN
static uint32_t beesignTaskCounter = 0;
static uint32_t beesignSendNextCounterPoint = 0;
From e430b65fc6639bf27a57d59cbc9bafcfb536319a Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 27 Feb 2024 11:24:07 -0600
Subject: [PATCH 12/33] fix compiler warnings - USBD VCP strings resulting in
'condition has identical branches' (#968)
---
src/main/msc/usbd_msc_desc.c | 6 ++++--
src/main/vcp_hal/usbd_desc.c | 8 ++++----
2 files changed, 8 insertions(+), 6 deletions(-)
diff --git a/src/main/msc/usbd_msc_desc.c b/src/main/msc/usbd_msc_desc.c
index 2ebe7622fc..061c14563b 100644
--- a/src/main/msc/usbd_msc_desc.c
+++ b/src/main/msc/usbd_msc_desc.c
@@ -67,8 +67,10 @@
#define USBD_MANUFACTURER_STRING "STMicroelectronics"
#define USBD_PRODUCT_HS_STRING "Mass Storage in HS Mode"
#define USBD_PRODUCT_FS_STRING "Mass Storage in FS Mode"
-#define USBD_CONFIGURATION_HS_STRING "MSC Config"
-#define USBD_INTERFACE_HS_STRING "MSC Interface"
+#define USBD_CONFIGURATION_HS_STRING "MSC Config in HS Mode"
+#define USBD_INTERFACE_HS_STRING "MSC Interface in HS Mode"
+#define USBD_CONFIGURATION_FS_STRING "MSC Config in FS Mode"
+#define USBD_INTERFACE_FS_STRING "MSC Interface in FS Mode"
/**
* @}
*/
diff --git a/src/main/vcp_hal/usbd_desc.c b/src/main/vcp_hal/usbd_desc.c
index ab850449dc..42a38d7b80 100644
--- a/src/main/vcp_hal/usbd_desc.c
+++ b/src/main/vcp_hal/usbd_desc.c
@@ -66,10 +66,10 @@
#define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME
#define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode"
#define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
-#define USBD_CONFIGURATION_HS_STRING "VCP Config"
-#define USBD_INTERFACE_HS_STRING "VCP Interface"
-#define USBD_CONFIGURATION_FS_STRING "VCP Config"
-#define USBD_INTERFACE_FS_STRING "VCP Interface"
+#define USBD_CONFIGURATION_HS_STRING "VCP Config in HS Mode"
+#define USBD_INTERFACE_HS_STRING "VCP Interface in HS Mode"
+#define USBD_CONFIGURATION_FS_STRING "VCP Config in FS Mode"
+#define USBD_INTERFACE_FS_STRING "VCP Interface in FS Mode"
/* Private macro -------------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
From e65a7e06a05d266b6c9fb84c7afd7f8325d5aa9c Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 27 Feb 2024 12:43:50 -0600
Subject: [PATCH 13/33] fix compiler warnings - STM32F7 HAL Drivers: 'packed'
attribute ignored (#969)
---
.../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c
index c3ee209cc0..05d33296ce 100644
--- a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c
+++ b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c
@@ -817,7 +817,7 @@ HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, uin
count32b = (len + 3) / 4;
for (i = 0; i < count32b; i++, src += 4)
{
- USBx_DFIFO(ch_ep_num) = *((__packed uint32_t *)src);
+ USBx_DFIFO((uint32_t)ch_ep_num) = *((uint32_t *)src);
}
}
return HAL_OK;
@@ -843,7 +843,7 @@ void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len)
for ( i = 0; i < count32b; i++, dest += 4 )
{
- *(__packed uint32_t *)dest = USBx_DFIFO(0);
+ *(uint32_t *)dest = USBx_DFIFO(0);
}
return ((void *)dest);
From c655adee399482c25506ed5aca853e77a1facaba Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 27 Feb 2024 14:00:11 -0600
Subject: [PATCH 14/33] fix compiler warning - CRSF - unused parameter
'currentTimeUs' (#976)
---
src/main/rx/crsf.c | 1 +
1 file changed, 1 insertion(+)
diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c
index 649712c084..f9dedb68ba 100644
--- a/src/main/rx/crsf.c
+++ b/src/main/rx/crsf.c
@@ -130,6 +130,7 @@ typedef struct crsfPayloadLinkstatistics_s {
} crsfLinkStatistics_t;
static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, timeUs_t currentTimeUs) {
+ UNUSED(currentTimeUs);
const crsfLinkStatistics_t stats = *statsPtr;
CRSFsetLQ(stats.uplink_Link_quality);
CRSFsetRFMode(stats.rf_Mode);
From 9136d4c1c1992f94b7539d5939f8ce615d0d6857 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 29 Feb 2024 07:55:52 -0600
Subject: [PATCH 15/33] fix compiler warnings - SmartAudio CMS menu `FREQ`,
`POR FREQ` (#970)
fix compiler warnings - SmartAudio CMS menu `FREQ`, `POR FREQ`
---
src/main/cms/cms.c | 2 +-
src/main/cms/cms_menu_vtx_smartaudio.c | 4 ++--
2 files changed, 3 insertions(+), 3 deletions(-)
diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c
index c775c222e4..3a4730f66f 100644
--- a/src/main/cms/cms.c
+++ b/src/main/cms/cms.c
@@ -329,7 +329,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
buff[0] = 0x0;
if ((p->type == OME_Submenu) && p->func && (p->flags & OPTSTRING)) {
// Special case of sub menu entry with optional value display.
- char *str = ((CMSMenuOptFuncPtr)p->func)();
+ char *str = ((CMSMenuOptFuncPtr)(long)p->func)();
strncpy( buff, str, CMS_DRAW_BUFFER_LEN);
}
strncat(buff, ">", CMS_DRAW_BUFFER_LEN);
diff --git a/src/main/cms/cms_menu_vtx_smartaudio.c b/src/main/cms/cms_menu_vtx_smartaudio.c
index 77622df9e7..319da7d40e 100644
--- a/src/main/cms/cms_menu_vtx_smartaudio.c
+++ b/src/main/cms/cms_menu_vtx_smartaudio.c
@@ -492,7 +492,7 @@ static OSD_Entry saCmsMenuConfigEntries[] = {
{ "OP MODEL", OME_TAB, saCmsConfigOpmodelByGvar, &(OSD_TAB_t){ &saCmsOpmodel, 2, saCmsOpmodelNames }, DYNAMIC },
{ "FSEL MODE", OME_TAB, saCmsConfigFreqModeByGvar, &saCmsEntFselMode, DYNAMIC },
{ "PIT FMODE", OME_TAB, saCmsConfigPitFModeByGvar, &saCmsEntPitFMode, 0 },
- { "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING },
+ { "POR FREQ", OME_Submenu, (CMSEntryFuncPtr)(long)saCmsORFreqGetString, &saCmsMenuPORFreq, OPTSTRING },
#ifdef USE_EXTENDED_CMS_MENUS
{ "STATX", OME_Submenu, cmsMenuChange, &saCmsMenuStats, 0 },
#endif /* USE_EXTENDED_CMS_MENUS */
@@ -534,7 +534,7 @@ static OSD_Entry saCmsMenuFreqModeEntries[] = {
{ "- SMARTAUDIO -", OME_Label, NULL, NULL, 0 },
{ "", OME_Label, NULL, saCmsStatusString, DYNAMIC },
- { "FREQ", OME_Submenu, (CMSEntryFuncPtr)saCmsUserFreqGetString, &saCmsMenuUserFreq, OPTSTRING },
+ { "FREQ", OME_Submenu, (CMSEntryFuncPtr)(long)saCmsUserFreqGetString, &saCmsMenuUserFreq, OPTSTRING },
{ "POWER", OME_TAB, saCmsConfigPowerByGvar, &saCmsEntPower, 0 },
{ "SET", OME_Submenu, cmsMenuChange, &saCmsMenuCommence, 0 },
{ "CONFIG", OME_Submenu, cmsMenuChange, &saCmsMenuConfig, 0 },
From 2284366452d65c8c6aca2d81b1317c6118a4f444 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 29 Feb 2024 14:13:29 -0600
Subject: [PATCH 16/33] suppress (don't fix) compiler warnings for 3rd party
libraries - STM32F4 and STM32F7 (#978)
---
.../Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c | 3 +++
.../Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c | 3 +++
2 files changed, 6 insertions(+)
diff --git a/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c b/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
index 4aa38e731f..a1bf0317ee 100644
--- a/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
+++ b/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
@@ -423,6 +423,8 @@ void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
/* Get the PLLM value */
pllm = (uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLM);
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wduplicated-branches"
if((RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) == RCC_PLLCFGR_PLLSRC_HSE)
{
/* Get the I2S source clock value */
@@ -433,6 +435,7 @@ void I2S_Init(SPI_TypeDef* SPIx, I2S_InitTypeDef* I2S_InitStruct)
i2sclk = (uint32_t)(((HSI_VALUE / pllm) * plln) / pllr);
}
#endif /* I2S_EXTERNAL_CLOCK_VAL */
+#pragma GCC diagnostic pop
/* Compute the Real divider depending on the MCLK output state, with a floating point */
if(I2S_InitStruct->I2S_MCLKOutput == I2S_MCLKOutput_Enable)
diff --git a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c
index 4d9e318453..b3d1033aee 100644
--- a/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c
+++ b/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c
@@ -248,6 +248,8 @@ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart)
return HAL_ERROR;
}
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wduplicated-branches"
if(huart->Init.HwFlowCtl != UART_HWCONTROL_NONE)
{
/* Check the parameters */
@@ -258,6 +260,7 @@ HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart)
/* Check the parameters */
assert_param(IS_UART_INSTANCE(huart->Instance));
}
+#pragma GCC diagnostic pop
if(huart->gState == HAL_UART_STATE_RESET)
{
From f5c35c6d44bdf510d58cedf2723053efd8b877bb Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 08:09:37 -0600
Subject: [PATCH 17/33] fix compiler warnings - board.c - strncpy, allow
trailing null (5th character) (#974)
---
src/main/pg/board.c | 8 ++++----
1 file changed, 4 insertions(+), 4 deletions(-)
diff --git a/src/main/pg/board.c b/src/main/pg/board.c
index a3d17831ea..28f692c867 100644
--- a/src/main/pg/board.c
+++ b/src/main/pg/board.c
@@ -37,14 +37,14 @@ PG_REGISTER_WITH_RESET_FN(boardConfig_t, boardConfig, PG_BOARD_CONFIG, 0);
void pgResetFn_boardConfig(boardConfig_t *boardConfig) {
if (boardInformationIsSet()) {
- strncpy(boardConfig->manufacturerId, getManufacturerId(), MAX_MANUFACTURER_ID_LENGTH);
- strncpy(boardConfig->boardName, getBoardName(), MAX_BOARD_NAME_LENGTH);
+ strncpy(boardConfig->manufacturerId, getManufacturerId(), MAX_MANUFACTURER_ID_LENGTH + 1);
+ strncpy(boardConfig->boardName, getBoardName(), MAX_BOARD_NAME_LENGTH + 1);
boardConfig->boardInformationSet = true;
} else {
#if !defined(GENERIC_TARGET)
- strncpy(boardConfig->boardName, targetName, MAX_BOARD_NAME_LENGTH);
+ strncpy(boardConfig->boardName, targetName, MAX_BOARD_NAME_LENGTH + 1);
#if defined(TARGET_MANUFACTURER_IDENTIFIER)
- strncpy(boardConfig->manufacturerId, TARGET_MANUFACTURER_IDENTIFIER, MAX_MANUFACTURER_ID_LENGTH);
+ strncpy(boardConfig->manufacturerId, TARGET_MANUFACTURER_IDENTIFIER, MAX_MANUFACTURER_ID_LENGTH + 1);
#endif
boardConfig->boardInformationSet = true;
#else
From e2797b21f8413f74ce6197b2eda26442f5623209 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 11:43:27 -0600
Subject: [PATCH 18/33] fix compiler warnings - KAKUTEF7*; add icm20689 (#979)
* fix compiler warnings - KAKUTEF7*; add icm20689
* Update KAKUTEF7V2.mk
---
src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk | 1 +
src/main/target/KAKUTEF7HDV/target.h | 28 +++++++++++++++--------
src/main/target/KAKUTEF7HDV/target.mk | 1 +
3 files changed, 20 insertions(+), 10 deletions(-)
create mode 100644 src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk
diff --git a/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk b/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk
new file mode 100644
index 0000000000..52b9c1d1ff
--- /dev/null
+++ b/src/main/target/KAKUTEF7HDV/KAKUTEF7V2.mk
@@ -0,0 +1 @@
+#KAKUTEF7V2.mk file
diff --git a/src/main/target/KAKUTEF7HDV/target.h b/src/main/target/KAKUTEF7HDV/target.h
index d33171c058..4a824688fd 100644
--- a/src/main/target/KAKUTEF7HDV/target.h
+++ b/src/main/target/KAKUTEF7HDV/target.h
@@ -20,21 +20,21 @@
#pragma once
+#define FC_TARGET_MCU STM32F745 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+#define TARGET_MANUFACTURER_IDENTIFIER "HBRO"
+
//#define USE_TARGET_CONFIG
#if defined(KAKUTEF7MINIV2)
-#define TARGET_BOARD_IDENTIFIER "KF7M"
-#define USBD_PRODUCT_STRING "KakuteF7 Mini V2"
+#define USBD_PRODUCT_STRING "KAKUTEF7MINIV2"
+#elif defined(KAKUTEF7V2)
+#define USBD_PRODUCT_STRING "KAKUTEF7V2"
#elif defined(KAKUTEF7V15)
-#define TARGET_BOARD_IDENTIFIER "KTF7"
-#define USBD_PRODUCT_STRING "Kakutef7 v15"
+#define USBD_PRODUCT_STRING "KAKUTEF7V15"
#else
-#define TARGET_BOARD_IDENTIFIER "KTF7"
-#define USBD_PRODUCT_STRING "KakuteF7 HD"
+#define USBD_PRODUCT_STRING "KAKUTEF7HDV"
#endif
-#define TARGET_BOARD_IDENTIFIER "KTF7"
-#define USBD_PRODUCT_STRING "KakuteF7"
-
#define LED0_PIN PA2
#define USE_BEEPER
@@ -44,6 +44,14 @@
#define USE_ACC
#define USE_GYRO
+//ICM20689
+#define USE_ACC_SPI_ICM20689
+#define USE_GYRO_SPI_ICM20689
+#define ACC_ICM20689_ALIGN CW270_DEG
+#define GYRO_ICM20689_ALIGN CW270_DEG
+#define ICM20689_CS_PIN PE4
+#define ICM20689_SPI_INSTANCE SPI4
+
// MPU6000
#define USE_ACC_SPI_MPU6000
#define USE_GYRO_SPI_MPU6000
@@ -119,7 +127,7 @@
#define SPI4_MISO_PIN PE5
#define SPI4_MOSI_PIN PE6
-#if defined(KAKUTEF7V15) || defined(KAKUTEF7MINIV2)
+#if defined(KAKUTEF7V15) || defined(KAKUTEF7V2) ||defined(KAKUTEF7MINIV2)
#define CAMERA_CONTROL_PIN PB3
#define USE_MAX7456
diff --git a/src/main/target/KAKUTEF7HDV/target.mk b/src/main/target/KAKUTEF7HDV/target.mk
index 8d20f30a47..79bff4a092 100644
--- a/src/main/target/KAKUTEF7HDV/target.mk
+++ b/src/main/target/KAKUTEF7HDV/target.mk
@@ -7,6 +7,7 @@ endif
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm20689.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
From fabed9b718c333a1939e40e544307df4a3ce6ef9 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 13:45:43 -0600
Subject: [PATCH 19/33] [target] KAKUTEF7MINIV3 add ICM42688P (#980)
---
src/main/target/KAKUTEF7MINIV3/target.h | 50 +++++++++++++++++-------
src/main/target/KAKUTEF7MINIV3/target.mk | 1 +
2 files changed, 37 insertions(+), 14 deletions(-)
diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h
index ed470a1e01..4eb8ef6070 100644
--- a/src/main/target/KAKUTEF7MINIV3/target.h
+++ b/src/main/target/KAKUTEF7MINIV3/target.h
@@ -20,8 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "KTF7"
-#define USBD_PRODUCT_STRING "KakuteF7 Mini V3"
+#define TARGET_MANUFACTURER_IDENTIFIER "HBRO"
+#define USBD_PRODUCT_STRING "KAKUTEF7MINIV3"
+
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
#define LED0_PIN PD2
@@ -29,22 +32,41 @@
#define BEEPER_PIN PC8
#define BEEPER_INVERTED
-//MPU6000
#define USE_ACC
#define USE_GYRO
-#define USE_ACC_SPI_MPU6000
-#define USE_GYRO_SPI_MPU6000
-#define MPU_INT_EXTI PA4
-#define MPU6000_CS_PIN SPI1_NSS_PIN
-#define MPU6000_SPI_INSTANCE SPI1
-#define GYRO_1_CS_PIN MPU6000_CS_PIN
-#define GYRO_1_SPI_INSTANCE MPU6000_SPI_INSTANCE
+#define USE_SPI_GYRO
+#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI
+#define USE_GYRO_EXTI
+
+#define USE_MPU_DATA_READY_SIGNAL
+
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PB2
+#define GYRO_1_EXTI_PIN PA4
+#define GYRO_1_SPI_INSTANCE SPI1
+#define MPU_INT_EXTI PA4
+
+#define USE_DUAL_GYRO
+
+#define GYRO_2_ALIGN CW0_DEG
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI1
-#define GYRO_MPU6000_ALIGN CW270_DEG
-#define ACC_MPU6000_ALIGN CW270_DEG
-#define ACC_1_ALIGN ACC_MPU6000_ALIGN
-#define GYRO_1_ALIGN GYRO_MPU6000_ALIGN
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PB2
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_ACC_SPI_ICM42688P
+#define USE_GYRO_SPI_ICM42688P
+#define ACC_ICM42688P_ALIGN CW270_DEG
+#define GYRO_ICM42688P_ALIGN CW270_DEG
+#define ICM42688P_CS_PIN PB2
+#define ICM42688P_SPI_INSTANCE SPI1
#define USE_MPU_DATA_READY_SIGNAL
#define USE_EXTI
diff --git a/src/main/target/KAKUTEF7MINIV3/target.mk b/src/main/target/KAKUTEF7MINIV3/target.mk
index e0e4af6d5c..6a30ffc432 100644
--- a/src/main/target/KAKUTEF7MINIV3/target.mk
+++ b/src/main/target/KAKUTEF7MINIV3/target.mk
@@ -3,6 +3,7 @@ FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm426xx.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
From 31d981c654a0019890981a1347a5b033d8443a03 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 14:17:43 -0600
Subject: [PATCH 20/33] [target] KAKUTEF7 add MPU6000 and refresh naming (#981)
---
src/main/target/KAKUTEF7/target.h | 52 +++++++++++++++++++-----------
src/main/target/KAKUTEF7/target.mk | 1 +
2 files changed, 34 insertions(+), 19 deletions(-)
diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h
index 052e2a7cf5..930e60fd09 100644
--- a/src/main/target/KAKUTEF7/target.h
+++ b/src/main/target/KAKUTEF7/target.h
@@ -20,13 +20,16 @@
#pragma once
+#define TARGET_MANUFACTURER_IDENTIFIER "HBRO"
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+
//#define USE_TARGET_CONFIG
#if defined(KAKUTEF7MINIV1)
#define TARGET_BOARD_IDENTIFIER "KF7M"
-#define USBD_PRODUCT_STRING "KakuteF7 Mini V1"
+#define USBD_PRODUCT_STRING "KAKUTEF7MINIV1"
#else
#define TARGET_BOARD_IDENTIFIER "KTF7"
-#define USBD_PRODUCT_STRING "KakuteF7"
+#define USBD_PRODUCT_STRING "KAKUTEF7"
#endif
#define LED0_PIN PA2
@@ -37,24 +40,39 @@
#define USE_ACC
#define USE_GYRO
-
-// ICM-20689
#define USE_ACC_SPI_ICM20689
#define USE_GYRO_SPI_ICM20689
-#define GYRO_ICM20689_ALIGN CW270_DEG
-#define ACC_ICM20689_ALIGN CW270_DEG
-#define MPU_INT_EXTI PE1
-
-#define ICM20689_CS_PIN SPI4_NSS_PIN
-#define ICM20689_SPI_INSTANCE SPI4
-#define GYRO_1_CS_PIN ICM20689_CS_PIN
-#define GYRO_1_SPI_INSTANCE ICM20689_SPI_INSTANCE
+#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
-#define ACC_1_ALIGN ACC_ICM20689_ALIGN
-#define GYRO_1_ALIGN GYRO_ICM20689_ALIGN
+#define USE_SPI_GYRO
+#define USE_EXTI // notice - REQUIRED when USE_GYRO_EXTI
+#define USE_GYRO_EXTI
#define USE_MPU_DATA_READY_SIGNAL
-#define USE_EXTI
+
+#define GYRO_1_ALIGN CW270_DEG
+#define ACC_1_ALIGN CW270_DEG
+#define GYRO_1_CS_PIN PE4
+#define GYRO_1_EXTI_PIN PE1
+#define GYRO_1_SPI_INSTANCE SPI4
+#define MPU_INT_EXTI PE1
+
+#define USE_DUAL_GYRO
+
+#define GYRO_2_ALIGN CW0_DEG
+#define ACC_2_ALIGN CW0_DEG
+#define GYRO_2_SPI_INSTANCE SPI4
+
+#define ACC_MPU6000_ALIGN CW270_DEG
+#define GYRO_MPU6000_ALIGN CW270_DEG
+#define MPU6000_CS_PIN PE4
+#define MPU6000_SPI_INSTANCE SPI4
+
+#define ACC_ICM20689_ALIGN CW270_DEG
+#define GYRO_ICM20689_ALIGN CW270_DEG
+#define ICM20689_CS_PIN PE4
+#define ICM20689_SPI_INSTANCE SPI4
#define USE_VCP
#define USE_USB_DETECT
@@ -129,14 +147,10 @@
#define USE_SDCARD
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PD8
-
#define SDCARD_SPI_INSTANCE SPI1
#define SDCARD_SPI_CS_PIN SPI1_NSS_PIN
-
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 422kHz
-
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 8 // 27MHz
-
#define SDCARD_DMA_STREAM_TX_FULL DMA2_Stream5
#define SDCARD_DMA_CHANNEL 3
#endif
diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk
index 7f1392d6a1..154eef84dc 100644
--- a/src/main/target/KAKUTEF7/target.mk
+++ b/src/main/target/KAKUTEF7/target.mk
@@ -7,6 +7,7 @@ endif
TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_hmc5883l.c \
From 5d65d2a30f98a7fb31d85d272b7df7cf92524273 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 14:23:07 -0600
Subject: [PATCH 21/33] [target] KAKUTEF7 KAKUTEF7MINIV1 refresh naming fix
(#982)
---
src/main/target/KAKUTEF7/target.h | 2 --
1 file changed, 2 deletions(-)
diff --git a/src/main/target/KAKUTEF7/target.h b/src/main/target/KAKUTEF7/target.h
index 930e60fd09..919d307ae6 100644
--- a/src/main/target/KAKUTEF7/target.h
+++ b/src/main/target/KAKUTEF7/target.h
@@ -25,10 +25,8 @@
//#define USE_TARGET_CONFIG
#if defined(KAKUTEF7MINIV1)
-#define TARGET_BOARD_IDENTIFIER "KF7M"
#define USBD_PRODUCT_STRING "KAKUTEF7MINIV1"
#else
-#define TARGET_BOARD_IDENTIFIER "KTF7"
#define USBD_PRODUCT_STRING "KAKUTEF7"
#endif
From f83f617e525714fdad145ee9b4916d9e1a488ef4 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 15:03:10 -0600
Subject: [PATCH 22/33] [target] MATEKF405SE fix compiler warning and refresh
naming (#983)
---
src/main/target/MATEKF405SE/target.h | 9 ++++++---
1 file changed, 6 insertions(+), 3 deletions(-)
diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h
index 006cbe36cd..5be9894d2b 100644
--- a/src/main/target/MATEKF405SE/target.h
+++ b/src/main/target/MATEKF405SE/target.h
@@ -20,8 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "MKF4"
-#define USBD_PRODUCT_STRING "Matek F405 SE"
+#define TARGET_MANUFACTURER_IDENTIFIER "MTKS"
+#define USBD_PRODUCT_STRING "MATEKF405SE"
+
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
#define LED0_PIN PA14
#define LED1_PIN PA13
@@ -88,7 +91,7 @@
#define BARO_I2C_INSTANCE (I2CDEV_1)
#define USE_I2C_DEVICE_2
-#define I2C_DEVICE (I2CDEV_2)
+#define I2C_DEVICE_2 (I2CDEV_2)
#define I2C2_SCL PB10 // SCL pad
#define I2C2_SDA PB11 // SDA pad
#define BARO_I2C_INSTANCE (I2CDEV_1)
From c70f55a6800eeed43ce17b507b89c2e144067cb4 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 1 Mar 2024 15:10:40 -0600
Subject: [PATCH 23/33] fix compiler warning - convertSpektrumVtxPowerIndex -
unused parameter 'sPower' (#973)
* fix compiler warnings - convertSpektrumVtxPowerIndex - unused parameter 'sPower'
* fix compiler warnings - convertSpektrumVtxPowerIndex sPower; proper gating
---
src/main/io/spektrum_vtx_control.c | 3 +++
1 file changed, 3 insertions(+)
diff --git a/src/main/io/spektrum_vtx_control.c b/src/main/io/spektrum_vtx_control.c
index 61161a30e8..d591359078 100644
--- a/src/main/io/spektrum_vtx_control.c
+++ b/src/main/io/spektrum_vtx_control.c
@@ -113,6 +113,9 @@ const uint8_t vtxBsPi[SPEKTRUM_VTX_POWER_COUNT] = {
#endif // USE_VTX_BEESIGN
uint8_t convertSpektrumVtxPowerIndex(uint8_t sPower) {
+#if !(defined(USE_VTX_RTC6705) || defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP))
+ UNUSED(sPower);
+#endif
uint8_t devicePower = 0;
const vtxDevice_t *vtxDevice = vtxCommonDevice();
switch (vtxCommonGetDeviceType(vtxDevice)) {
From 83dd26939ef0213596606c73bdd8fd3ab20dceeb Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Mon, 4 Mar 2024 13:59:55 -0600
Subject: [PATCH 24/33] [target] MATEKF411SE fix usable timer count (#984)
---
src/main/target/MATEKF411SE/target.h | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h
index 61945caf16..214d4cd2f7 100644
--- a/src/main/target/MATEKF411SE/target.h
+++ b/src/main/target/MATEKF411SE/target.h
@@ -138,5 +138,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
-#define USABLE_TIMER_CHANNEL_COUNT 10
+#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(9)|TIM_N(11) )
From 4e7adab128852a0b54f2761a27e35edb06f410e0 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 6 Mar 2024 10:54:54 -0600
Subject: [PATCH 25/33] [target] ALIENWHOOP fix compile warning and refresh;
add ADC; add MPU9250 (#987)
---
src/main/target/ALIENWHOOP/target.h | 24 ++++++++++++++++++++----
src/main/target/ALIENWHOOP/target.mk | 1 +
2 files changed, 21 insertions(+), 4 deletions(-)
diff --git a/src/main/target/ALIENWHOOP/target.h b/src/main/target/ALIENWHOOP/target.h
index d5b04e3b1e..063672ca1e 100644
--- a/src/main/target/ALIENWHOOP/target.h
+++ b/src/main/target/ALIENWHOOP/target.h
@@ -38,12 +38,17 @@
/* Multi-Arch Support for 168MHz or 216MHz ARM Cortex processors - STM32F405RGT or STM32F7RET
*/
+
+#define TARGET_MANUFACTURER_IDENTIFIER "ALWH"
+
#if defined(ALIENWHOOPF4)
-#define TARGET_BOARD_IDENTIFIER "AWF4"
-#define USBD_PRODUCT_STRING "AlienWhoopF4"
+#define USBD_PRODUCT_STRING "ALIENWHOOPF4"
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
#else
-#define TARGET_BOARD_IDENTIFIER "AWF7"
-#define USBD_PRODUCT_STRING "AlienWhoopF7"
+#define USBD_PRODUCT_STRING "ALIENWHOOPF7"
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2"
#endif
#define USE_TARGET_CONFIG // see config.c for target specific customizations
@@ -125,6 +130,9 @@
// MPU
#define MPU6500_CS_PIN SPI1_NSS_PIN
#define MPU6500_SPI_INSTANCE SPI1
+#define MPU9250_CS_PIN SPI1_NSS_PIN
+#define MPU9250_SPI_INSTANCE SPI1
+
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
// MAG
@@ -136,11 +144,15 @@
// GYRO
#define USE_GYRO
#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_MPU9250
#define GYRO_MPU6500_ALIGN CW0_DEG
+#define GYRO_MPU9250_ALIGN CW0_DEG
// ACC
#define USE_ACC
#define USE_ACC_SPI_MPU6500
+#define USE_ACC_SPI_MPU9250
#define ACC_MPU6500_ALIGN CW0_DEG
+#define ACC_MPU9250_ALIGN CW0_DEG
/* Optional Digital Pressure Sensor (barometer) - Bosch BMP280
* TODO: not implemented on V1 or V2 pcb
@@ -232,6 +244,10 @@
#define TARGET_IO_PORTE 0xffff
#endif
+#define USE_ADC
+#define ADC1_DMA_OPT 1
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
+
/* Timers
*/
#define USABLE_TIMER_CHANNEL_COUNT 5
diff --git a/src/main/target/ALIENWHOOP/target.mk b/src/main/target/ALIENWHOOP/target.mk
index 4d72357939..73c66b293b 100644
--- a/src/main/target/ALIENWHOOP/target.mk
+++ b/src/main/target/ALIENWHOOP/target.mk
@@ -20,6 +20,7 @@ FEATURES += ONBOARDFLASH VCP
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu9250.c \
drivers/barometer/barometer_bmp280.c \
drivers/compass/compass_ak8963.c \
drivers/flash_m25p16.c \
From 3bf72157aa8a79a61a142b5142ffcaa07f745842 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 6 Mar 2024 11:37:45 -0600
Subject: [PATCH 26/33] [target] NBDHMBF41S et al - fix compile warnings and
make config.c usable if desired (#988)
---
src/main/target/NBDHMBF41S/config.c | 102 +++++++++++++++-------------
1 file changed, 54 insertions(+), 48 deletions(-)
diff --git a/src/main/target/NBDHMBF41S/config.c b/src/main/target/NBDHMBF41S/config.c
index 92fe2d8b70..3f85579094 100644
--- a/src/main/target/NBDHMBF41S/config.c
+++ b/src/main/target/NBDHMBF41S/config.c
@@ -17,7 +17,7 @@
*
* If not, see .
*/
-/*
+
#include
#include
#include
@@ -38,7 +38,7 @@
#include "fc/config.h"
#include "fc/controlrate_profile.h"
-#include "fc/core.h"
+#include "fc/fc_core.h"
#include "fc/rc_adjustments.h"
#include "fc/rc_modes.h"
#include "fc/rc_controls.h"
@@ -49,18 +49,19 @@
#include "pg/vcd.h"
#include "pg/rx.h"
-#include "pg/motor.h"
-#include "pg/vtx_table.h"
+//#include "pg/motor.h"
+#include "io/motors.h"
+//#include "pg/vtx_table.h"
#include "rx/rx.h"
#include "rx/cc2500_frsky_common.h"
#include "pg/rx.h"
#include "pg/rx_spi.h"
-#include "pg/rx_spi_cc2500.h"
+#include "drivers/rx/rx_cc2500.h"
#include "pg/vcd.h"
-#include "osd/osd.h"
+#include "io/osd.h"
#include "io/serial.h"
#include "io/vtx.h"
@@ -74,14 +75,14 @@
void targetConfiguration(void)
{
- osdConfigMutable()->item_pos[OSD_CRAFT_NAME] = OSD_POS(9, 10) | OSD_PROFILE_1_FLAG;
- osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(23, 9) | OSD_PROFILE_1_FLAG;
- osdConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(2, 9) | OSD_PROFILE_1_FLAG;
- osdConfigMutable()->item_pos[OSD_FLYMODE] = OSD_POS(17, 9) | OSD_PROFILE_1_FLAG;
- osdConfigMutable()->item_pos[OSD_VTX_CHANNEL] = OSD_POS(9, 9) | OSD_PROFILE_1_FLAG;
- osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(2, 10) | OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_CRAFT_NAME] = OSD_POS(9, 10); //| OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_MAIN_BATT_VOLTAGE] = OSD_POS(23, 9); //| OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_ITEM_TIMER_2] = OSD_POS(2, 9); //| OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_FLYMODE] = OSD_POS(17, 9); //| OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_VTX_CHANNEL] = OSD_POS(9, 9); //| OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_RSSI_VALUE] = OSD_POS(2, 10); //| OSD_PROFILE_1_FLAG;
osdConfigMutable()->item_pos[OSD_WARNINGS] = OSD_POS(9, 10);
- osdConfigMutable()->item_pos[OSD_CURRENT_DRAW] = OSD_POS(22,10) | OSD_PROFILE_1_FLAG;
+ osdConfigMutable()->item_pos[OSD_CURRENT_DRAW] = OSD_POS(22,10); //| OSD_PROFILE_1_FLAG;
batteryConfigMutable()->batteryCapacity = 250;
@@ -113,13 +114,17 @@ void targetConfiguration(void)
strcpy(pilotConfigMutable()->name, "Humming Bird");
gyroConfigMutable()->gyro_lowpass_type = FILTER_PT1;
- gyroConfigMutable()->gyro_lowpass_hz = 200;
+ gyroConfigMutable()->gyro_lowpass_hz[ROLL] = 200;
+ gyroConfigMutable()->gyro_lowpass_hz[PITCH] = 200;
+ gyroConfigMutable()->gyro_lowpass_hz[YAW] = 200;
#ifdef USE_GYRO_LPF2
- gyroConfigMutable()->gyro_lowpass2_hz = 200;
+ gyroConfigMutable()->gyro_lowpass2_hz[ROLL] = 500;
+ gyroConfigMutable()->gyro_lowpass2_hz[PITCH] = 500;
+ gyroConfigMutable()->gyro_lowpass2_hz[YAW] = 500;
#endif
gyroConfigMutable()->yaw_spin_threshold = 1950;
- gyroConfigMutable()->dyn_lpf_gyro_min_hz = 160;
- gyroConfigMutable()->dyn_lpf_gyro_max_hz = 400;
+ gyroConfigMutable()->dyn_notch_min_hz = 160;
+ gyroConfigMutable()->dyn_notch_max_hz = 400;
rxConfigMutable()->mincheck = 1075;
rxConfigMutable()->maxcheck = 1900;
rxConfigMutable()->rc_smoothing_type = RC_SMOOTHING_TYPE_FILTER;
@@ -127,32 +132,34 @@ void targetConfiguration(void)
rxConfigMutable()->rssi_channel = 9;
motorConfigMutable()->digitalIdleOffsetValue = 1000;
motorConfigMutable()->dev.useBurstDshot = true;
- motorConfigMutable()->dev.useDshotTelemetry = false;
+ //motorConfigMutable()->dev.useDshotTelemetry = false;
motorConfigMutable()->motorPoleCount = 12;
motorConfigMutable()->dev.motorPwmProtocol = PWM_TYPE_DSHOT600;
batteryConfigMutable()->batteryCapacity = 300;
- batteryConfigMutable()->vbatmaxcellvoltage = 450;
- batteryConfigMutable()->vbatfullcellvoltage = 400;
- batteryConfigMutable()->vbatmincellvoltage = 290;
- batteryConfigMutable()->vbatwarningcellvoltage = 320;
+ batteryConfigMutable()->vbatmaxcellvoltage = 45;
+ batteryConfigMutable()->vbatfullcellvoltage = 42;
+ batteryConfigMutable()->vbatmincellvoltage = 29;
+ batteryConfigMutable()->vbatwarningcellvoltage = 32;
voltageSensorADCConfigMutable(0)->vbatscale = 110;
mixerConfigMutable()->yaw_motors_reversed = false;
mixerConfigMutable()->crashflip_motor_percent = 0;
imuConfigMutable()->small_angle = 180;
pidConfigMutable()->pid_process_denom = 1;
pidConfigMutable()->runaway_takeoff_prevention = true;
- //osdConfigMutable()->enabledWarnings &= ~(1 << OSD_WARNING_CORE_TEMPERATURE);
+ osdConfigMutable()->enabledWarnings &= ~(1 << OSD_WARNING_CORE_TEMPERATURE);
osdConfigMutable()->cap_alarm = 2200;
pidProfilesMutable(0)->dterm_filter_type = FILTER_PT1;
- pidProfilesMutable(0)->dyn_lpf_dterm_min_hz = 56;
- pidProfilesMutable(0)->dyn_lpf_dterm_max_hz = 136;
- pidProfilesMutable(0)->dterm_lowpass_hz = 150;
- pidProfilesMutable(0)->dterm_lowpass2_hz = 120;
- pidProfilesMutable(0)->dterm_notch_cutoff = 0;
- pidProfilesMutable(0)->vbatPidCompensation = true;
+ //pidProfilesMutable(0)->dyn_lpf_dterm_min_hz = 56;
+ //pidProfilesMutable(0)->dyn_lpf_dterm_max_hz = 136;
+ pidProfilesMutable(0)->dFilter[ROLL].dLpf = 150;
+ pidProfilesMutable(0)->dFilter[PITCH].dLpf = 150;
+ pidProfilesMutable(0)->dFilter[YAW].dLpf = 150;
+ //pidProfilesMutable(0)->dterm_lowpass2_hz = 120;
+ //pidProfilesMutable(0)->dterm_notch_cutoff = 0;
+ //pidProfilesMutable(0)->vbatPidCompensation = true;
pidProfilesMutable(0)->iterm_rotation = true;
- pidProfilesMutable(0)->itermThrottleThreshold = 250;
+ //pidProfilesMutable(0)->itermThrottleThreshold = 250;
pidProfilesMutable(0)->yawRateAccelLimit = 0;
pidProfilesMutable(0)->pidSumLimit = 500;
pidProfilesMutable(0)->pidSumLimitYaw = 400;
@@ -168,16 +175,16 @@ void targetConfiguration(void)
pidProfilesMutable(0)->pid[PID_YAW].I = 55;
pidProfilesMutable(0)->pid[PID_YAW].D = 0;
pidProfilesMutable(0)->pid[PID_YAW].F = 0;
- pidProfilesMutable(0)->pid[PID_LEVEL].P = 70;
- pidProfilesMutable(0)->pid[PID_LEVEL].I = 70;
- pidProfilesMutable(0)->pid[PID_LEVEL].D = 100;
+ //pidProfilesMutable(0)->pid[PID_LEVEL].P = 70;
+ //pidProfilesMutable(0)->pid[PID_LEVEL].I = 70;
+ //pidProfilesMutable(0)->pid[PID_LEVEL].D = 100;
pidProfilesMutable(0)->levelAngleLimit = 85;
pidProfilesMutable(0)->horizon_tilt_effect = 75;
- pidProfilesMutable(0)->d_min[FD_ROLL] = 20;
- pidProfilesMutable(0)->d_min[FD_PITCH] = 18;
- pidProfilesMutable(0)->d_min_gain = 25;
- pidProfilesMutable(0)->d_min_advance = 1;
- pidProfilesMutable(0)->horizon_tilt_expert_mode = false;
+ //pidProfilesMutable(0)->d_min[FD_ROLL] = 20;
+ //pidProfilesMutable(0)->d_min[FD_PITCH] = 18;
+ //pidProfilesMutable(0)->d_min_gain = 25;
+ //pidProfilesMutable(0)->d_min_advance = 1;
+ //pidProfilesMutable(0)->horizon_tilt_expert_mode = false;
controlRateProfilesMutable(0)->rcRates[FD_YAW] = 100;
controlRateProfilesMutable(0)->rates[FD_ROLL] = 73;
@@ -186,25 +193,24 @@ void targetConfiguration(void)
controlRateProfilesMutable(0)->rcExpo[FD_ROLL] = 15;
controlRateProfilesMutable(0)->rcExpo[FD_PITCH] = 15;
controlRateProfilesMutable(0)->rcExpo[FD_YAW] = 15;
- controlRateProfilesMutable(0)->dynThrPID = 65;
+ //controlRateProfilesMutable(0)->dynThrPID = 65;
controlRateProfilesMutable(0)->tpa_breakpoint = 1250;
- ledStripStatusModeConfigMutable()->ledConfigs[0] = DEFINE_LED(7, 7, 8, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
- ledStripStatusModeConfigMutable()->ledConfigs[1] = DEFINE_LED(8, 7, 13, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
- ledStripStatusModeConfigMutable()->ledConfigs[2] = DEFINE_LED(9, 7, 11, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
- ledStripStatusModeConfigMutable()->ledConfigs[3] = DEFINE_LED(10, 7, 4, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
+ ledStripConfigMutable()->ledConfigs[0] = DEFINE_LED(7, 7, 8, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
+ ledStripConfigMutable()->ledConfigs[1] = DEFINE_LED(8, 7, 13, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
+ ledStripConfigMutable()->ledConfigs[2] = DEFINE_LED(9, 7, 11, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
+ ledStripConfigMutable()->ledConfigs[3] = DEFINE_LED(10, 7, 4, 0, LF(COLOR), LO(LARSON_SCANNER) | LO(THROTTLE), 0);
do {
// T8SG
uint8_t defaultTXHopTable[50] = {0,30,60,91,120,150,180,210,5,35,65,95,125,155,185,215,10,40,70,100,130,160,190,221,15,45,75,105,135,165,195,225,20,50,80,110,140,170,200,230,25,55,85,115,145,175,205,0,0,0};
- rxCc2500SpiConfigMutable()->bindOffset = 33;
- rxCc2500SpiConfigMutable()->bindTxId[0] = 198;
- rxCc2500SpiConfigMutable()->bindTxId[1] = 185;
+ rxFrSkySpiConfigMutable()->bindOffset = 33;
+ rxFrSkySpiConfigMutable()->bindTxId[0] = 198;
+ rxFrSkySpiConfigMutable()->bindTxId[1] = 185;
for (uint8_t i = 0; i < 50; i++) {
- rxCc2500SpiConfigMutable()->bindHopData[i] = defaultTXHopTable[i];
+ rxFrSkySpiConfigMutable()->bindHopData[i] = defaultTXHopTable[i];
}
} while (0);
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_MSP;
}
#endif
-*/
From ae97c69c8f06261394847d7e00f8f4a86c3563c1 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 21 Mar 2024 13:52:23 -0500
Subject: [PATCH 27/33] [target] PYRODRONEF7 - fix compiler warnings / update
Timers (#985)
* [target] PYRODRONEF7 - fix / update Timers
---
src/main/target/PYRODRONEF7/target.c | 25 ++++++++++++++++---------
src/main/target/PYRODRONEF7/target.h | 4 ++--
src/main/target/PYRODRONEF7/target.mk | 1 +
3 files changed, 19 insertions(+), 11 deletions(-)
diff --git a/src/main/target/PYRODRONEF7/target.c b/src/main/target/PYRODRONEF7/target.c
index 64eff72d67..79fc418786 100644
--- a/src/main/target/PYRODRONEF7/target.c
+++ b/src/main/target/PYRODRONEF7/target.c
@@ -28,16 +28,23 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// FILO arrangement for motor assignments, Motor 1 starts at 2nd DECLARATION
- DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // USE FOR CAMERA CONTROL
+ DEF_TIM(TIM2, CH2, PB3, TIM_USE_ANY, 0, 0), // pin B03: TIM2 CH2 (AF1) // USE FOR CAMERA CONTROL
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // D1-ST0 MOTOR1
- DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // D1-ST3 MOTOR2
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // D1-ST7 MOTOR3
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // D2-ST2/D2-ST4 MOTOR4
- DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // D1-ST4 MOTOR5
- DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // NONE TIM4_UP_D1-ST6 MOTOR6
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // D2-ST7 MOTOR7
+ DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // pin B06: TIM4 CH1 (AF2) // D1-ST0 MOTOR1
+ DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // pin B07: TIM4 CH2 (AF2) // D1-ST3 MOTOR2
+ DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // pin B08: TIM4 CH3 (AF2) // D1-ST7 MOTOR3
+ DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // pin C08: TIM8 CH3 (AF3) // D2-ST2/D2-ST4 MOTOR4
+ DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0), // pin A01: TIM5 CH2 (AF2) // D1-ST4 MOTOR5
+ DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // pin B09: TIM4 CH4 (AF2) // NONE TIM4_UP_D1-ST6 MOTOR6
+ DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), // pin C09: TIM8 CH4 (AF3) // D2-ST7 MOTOR7
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // D1-ST2 LED/MOTOR5
+ DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // pin B01: TIM3 CH4 (AF2) // D1-ST2 LED/MOTOR5
+
+ DEF_TIM(TIM9, CH2, PA3, TIM_USE_ANY, 0, 0), // pin A03: TIM9 CH2 (AF3)
+ DEF_TIM(TIM1, CH2N, PB0, TIM_USE_ANY, 0, 0), // pin B00: TIM1 CH2N (AF1)
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), // pin A00: TIM5 CH1 (AF2)
+ DEF_TIM(TIM3, CH1, PC6, TIM_USE_ANY, 0, 0), // pin C06: TIM3 CH1 (AF2)
+ DEF_TIM(TIM8, CH2, PC7, TIM_USE_ANY, 0, 0), // pin C07: TIM8 CH2 (AF3)
+ DEF_TIM(TIM3, CH2, PB5, TIM_USE_ANY, 0, 0), // pin B05: TIM3 CH2 (AF2)
};
\ No newline at end of file
diff --git a/src/main/target/PYRODRONEF7/target.h b/src/main/target/PYRODRONEF7/target.h
index 8b8ef34c0e..d1f57146b4 100644
--- a/src/main/target/PYRODRONEF7/target.h
+++ b/src/main/target/PYRODRONEF7/target.h
@@ -132,5 +132,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
-#define USABLE_TIMER_CHANNEL_COUNT 6
-#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) )
+#define USABLE_TIMER_CHANNEL_COUNT 15
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) |TIM_N(5) | TIM_N(8) | TIM_N(9) )
diff --git a/src/main/target/PYRODRONEF7/target.mk b/src/main/target/PYRODRONEF7/target.mk
index 3bae3aba77..6a383ad58a 100644
--- a/src/main/target/PYRODRONEF7/target.mk
+++ b/src/main/target/PYRODRONEF7/target.mk
@@ -9,4 +9,5 @@ TARGET_SRC = \
drivers/light_ws2811strip_hal.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
+ drivers/pinio.c \
drivers/max7456.c
From d743e8e225f86eccbbfa3b76f645bb86e66cb56b Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Wed, 27 Mar 2024 13:58:14 -0500
Subject: [PATCH 28/33] HDZERO - OSD Init/Menu/Stats Centering (#992)
---
src/main/cms/cms.c | 17 +++++++++++++---
src/main/cms/cms_menu_blackbox.c | 2 +-
src/main/io/osd.c | 34 ++++++++++++++++++++------------
src/main/io/osd.h | 4 ++++
src/main/pg/vcd.h | 3 ++-
5 files changed, 42 insertions(+), 18 deletions(-)
diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c
index 3a4730f66f..f5259d23b5 100644
--- a/src/main/cms/cms.c
+++ b/src/main/cms/cms.c
@@ -66,6 +66,7 @@
// For VISIBLE*
#include "io/osd.h"
#include "io/rcdevice_cam.h"
+#include "pg/vcd.h"
#include "rx/rx.h"
@@ -597,9 +598,19 @@ void cmsMenuOpen(void) {
} else {
smallScreen = false;
linesPerMenuItem = 1;
- leftMenuColumn = 2;
+#if defined(USE_HDZERO_OSD)
+ if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30))
+ { leftMenuColumn = HDINDENT + 2; }
+ else
+#endif
+ { leftMenuColumn = SDINDENT + 2; }
#ifdef CMS_OSD_RIGHT_ALIGNED_VALUES
- rightMenuColumn = pCurrentDisplay->cols - 2;
+#if defined(USE_HDZERO_OSD)
+ if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30))
+ { rightMenuColumn = pCurrentDisplay->cols - 2 - HDINDENT; }
+ else
+#endif
+ { rightMenuColumn = pCurrentDisplay->cols - 2; }
#else
rightMenuColumn = pCurrentDisplay->cols - CMS_DRAW_BUFFER_LEN;
#endif
@@ -634,7 +645,7 @@ long cmsMenuExit(displayPort_t *pDisplay, const void *ptr) {
currentCtx.menu = NULL;
if (exitType == CMS_EXIT_SAVEREBOOT) {
displayClearScreen(pDisplay);
- displayWrite(pDisplay, 5, 3, "REBOOTING...");
+ displayWrite(pDisplay, (pCurrentDisplay->cols % 2) - 6, 3, "REBOOTING...");
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
stopMotors();
stopPwmAllMotors();
diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c
index 56adfed277..84f11531c3 100644
--- a/src/main/cms/cms_menu_blackbox.c
+++ b/src/main/cms/cms_menu_blackbox.c
@@ -140,7 +140,7 @@ static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr) {
return 0;
}
displayClearScreen(pDisplay);
- displayWrite(pDisplay, 5, 3, "ERASING FLASH...");
+ displayWrite(pDisplay, (pCurrentDisplay->cols % 2) - 7, 3, "ERASING FLASH...");
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 937b71c694..c13d3da510 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -169,6 +169,8 @@ static escSensorData_t *escDataCombined;
#define AH_SIDEBAR_WIDTH_POS 7
#define AH_SIDEBAR_HEIGHT_POS 3
+static uint8_t leftScreen;
+
static const char compassBar[] = {
SYM_HEADING_W,
SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
@@ -1163,19 +1165,25 @@ void osdInit(displayPort_t *osdDisplayPortToUse) {
armState = ARMING_FLAG(ARMED);
memset(blinkBits, 0, sizeof(blinkBits));
displayClearScreen(osdDisplayPort);
- osdDrawLogo(3, 1);
+#if defined(USE_HDZERO_OSD)
+ if ((vcdProfile()->video_system == VIDEO_SYSTEM_HD) && (pCurrentDisplay->cols > 30))
+ { leftScreen = HDINDENT; }
+ else
+#endif
+ { leftScreen = SDINDENT; }
+ osdDrawLogo(leftScreen + 3, 1);
char string_buffer[30];
tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
- displayWrite(osdDisplayPort, 20, 6, string_buffer);
+ displayWrite(osdDisplayPort, leftScreen + 20, 6, string_buffer);
#ifdef USE_CMS
- displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1);
- displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2);
- displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3);
+ displayWrite(osdDisplayPort, leftScreen + 7, 8, CMS_STARTUP_HELP_TEXT1);
+ displayWrite(osdDisplayPort, leftScreen + 11, 9, CMS_STARTUP_HELP_TEXT2);
+ displayWrite(osdDisplayPort, leftScreen + 11, 10, CMS_STARTUP_HELP_TEXT3);
#endif
#ifdef USE_RTC_TIME
char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE];
if (osdFormatRtcDateTime(&dateTimeBuffer[0])) {
- displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer);
+ displayWrite(osdDisplayPort, leftScreen + 5, 12, dateTimeBuffer);
}
#endif
displayResync(osdDisplayPort);
@@ -1376,9 +1384,9 @@ static void osdGetBlackboxStatusString(char * buff) {
#endif
static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char * value) {
- displayWrite(osdDisplayPort, 2, y, text);
- displayWrite(osdDisplayPort, 20, y, ":");
- displayWrite(osdDisplayPort, 22, y, value);
+ displayWrite(osdDisplayPort, leftScreen + 2, y, text);
+ displayWrite(osdDisplayPort, leftScreen + 20, y, ":");
+ displayWrite(osdDisplayPort, leftScreen + 22, y, value);
}
/*
@@ -1400,7 +1408,7 @@ static void osdShowStats(uint16_t endBatteryVoltage) {
uint8_t top = 2;
char buff[OSD_ELEMENT_BUFFER_LENGTH];
displayClearScreen(osdDisplayPort);
- displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
+ displayWrite(osdDisplayPort, leftScreen + 2, top++, " --- STATS ---");
if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) {
bool success = false;
#ifdef USE_RTC_TIME
@@ -1409,7 +1417,7 @@ static void osdShowStats(uint16_t endBatteryVoltage) {
if (!success) {
tfp_sprintf(buff, "NO RTC");
}
- displayWrite(osdDisplayPort, 2, top++, buff);
+ displayWrite(osdDisplayPort, leftScreen + 2, top++, buff);
}
if (osdStatGetState(OSD_STAT_TIMER_1)) {
osdFormatTimer(buff, false, (OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1]) == OSD_TIMER_SRC_ON ? false : true), OSD_TIMER_1);
@@ -1483,12 +1491,12 @@ static timeDelta_t osdShowArmed(void)
timeDelta_t ret;
displayClearScreen(osdDisplayPort);
if ((osdConfig()->logo_on_arming == OSD_LOGO_ARMING_ON) || ((osdConfig()->logo_on_arming == OSD_LOGO_ARMING_FIRST) && !everArmed)) {
- osdDrawLogo(3, 1);
+ osdDrawLogo(leftScreen + 3, 1);
ret = osdConfig()->logo_on_arming_duration * 1e5;
} else {
ret = (REFRESH_1S / 2);
}
- displayWrite(osdDisplayPort, 12, 7, "ARMED");
+ displayWrite(osdDisplayPort, leftScreen + 12, 7, "ARMED");
everArmed = true;
return ret;
}
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index 886a3080d6..15ffb20cc6 100644
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -22,6 +22,7 @@
#include "common/time.h"
#include "pg/pg.h"
+#include "pg/vcd.h"
#define OSD_NUM_TIMER_TYPES 3
extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
@@ -44,6 +45,9 @@ extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
#define OSD_X(x) ((x & OSD_POSITION_XY_MASK) | ((x & OSD_POSITION_XHD_MASK) >> (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)))
#define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
+#define SDINDENT 0 //Analog leftmost character for OSD Init and Menus
+#define HDINDENT 10 //HD leftmost character for OSD Init and Menus
+
// Timer configuration
// Stored as 15[alarm:8][precision:4][source:4]0
#define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8))
diff --git a/src/main/pg/vcd.h b/src/main/pg/vcd.h
index df3ed8001d..33ff77155a 100644
--- a/src/main/pg/vcd.h
+++ b/src/main/pg/vcd.h
@@ -27,7 +27,8 @@
enum VIDEO_SYSTEMS {
VIDEO_SYSTEM_AUTO = 0,
VIDEO_SYSTEM_PAL,
- VIDEO_SYSTEM_NTSC
+ VIDEO_SYSTEM_NTSC,
+ VIDEO_SYSTEM_HD
};
typedef struct vcdProfile_s {
From 6caf22e106688e816e406063bd27204c30c05b72 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 28 Mar 2024 15:51:52 -0500
Subject: [PATCH 29/33] fix MATEKF405SE MAG_I2C_INSTANCE (#850)
fix MATEKF405SE Baro & Mag I2C
---
src/main/target/MATEKF405SE/target.h | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h
index 5be9894d2b..0af5b9d9fc 100644
--- a/src/main/target/MATEKF405SE/target.h
+++ b/src/main/target/MATEKF405SE/target.h
@@ -85,7 +85,7 @@
#define USE_I2C
// Useful for MATEKF405_OSD, since it does not have the SCL / SDA pads
#define USE_I2C_DEVICE_1
-#define I2C_DEVICE (I2CDEV_1)
+#define I2C_DEVICE_1 (I2CDEV_1)
#define I2C1_SCL PB8 // S4 pad
#define I2C3_SDA PB9 // S6 pad
#define BARO_I2C_INSTANCE (I2CDEV_1)
@@ -94,7 +94,7 @@
#define I2C_DEVICE_2 (I2CDEV_2)
#define I2C2_SCL PB10 // SCL pad
#define I2C2_SDA PB11 // SDA pad
-#define BARO_I2C_INSTANCE (I2CDEV_1)
+#define MAG_I2C_INSTANCE (I2CDEV_2)
#define USE_BARO
#define USE_BARO_BMP280
From 53c6836e9c35e46b6eb2a2b9b5cb4bcd7ebff83a Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 28 Mar 2024 15:55:10 -0500
Subject: [PATCH 30/33] [target] update BETAFPVF411RX adding BMI270 and MPU6500
and flash (#947)
[target] BETAFPVF411RX add BMI270 and MPU6500 and flash
---
src/main/target/BETAFPVF411RX/target.h | 50 ++++++++++++++-----------
src/main/target/BETAFPVF411RX/target.mk | 19 +++++-----
2 files changed, 39 insertions(+), 30 deletions(-)
diff --git a/src/main/target/BETAFPVF411RX/target.h b/src/main/target/BETAFPVF411RX/target.h
index b4cbe47a34..2a68447eda 100644
--- a/src/main/target/BETAFPVF411RX/target.h
+++ b/src/main/target/BETAFPVF411RX/target.h
@@ -38,27 +38,35 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
-#define MPU6000_CS_PIN PA4
-//#define ICM20689_CS_PIN PA4
-#define MPU6000_SPI_INSTANCE SPI1
-//#define ICM20689_SPI_INSTANCE SPI1
-
#define USE_EXTI
#define USE_GYRO_EXTI
#define MPU_INT_EXTI PB6
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
-#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-#define GYRO_MPU6000_ALIGN CW0_DEG_FLIP
-//#define USE_GYRO_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
#define USE_ACC
+#define USE_GYRO
+
#define USE_ACC_SPI_MPU6000
-#define ACC_MPU6000_ALIGN CW0_DEG_FLIP
-//#define USE_ACC_SPI_ICM20689
-//#define ACC_ICM20689_ALIGN CW180_DEG
+#define USE_GYRO_SPI_MPU6000
+#define GYRO_MPU6000_ALIGN CW180_DEG
+#define ACC_MPU6000_ALIGN CW180_DEG
+#define MPU6000_CS_PIN PA4
+#define MPU6000_SPI_INSTANCE SPI1
+
+#define USE_ACC_SPI_MPU6500
+#define USE_GYRO_SPI_MPU6500
+#define ACC_MPU6500_ALIGN CW180_DEG
+#define GYRO_MPU6500_ALIGN CW180_DEG
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+
+#define USE_ACCGYRO_BMI270
+#define USE_SPI_GYRO
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA4
+#define BMI270_SPI_INSTANCE SPI1
// *************** Baro **************************
//#define USE_I2C
@@ -140,17 +148,17 @@
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN PB12
-//#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-//#define USE_FLASHFS
-//#define USE_FLASH_M25P16
-//#define FLASH_CS_PIN PB2
-//#define FLASH_SPI_INSTANCE SPI2
+#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
+#define USE_FLASHFS
+#define USE_FLASH_M25P16
+#define FLASH_CS_PIN PB2
+#define FLASH_SPI_INSTANCE SPI2
// *************** ADC *****************************
#define USE_ADC
#define ADC_INSTANCE ADC1
-#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
-
+//#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0
+#define ADC1_DMA_STREAM DMA2_Stream4 //# ADC 1: DMA2 Stream 4 Channel 0
#define VBAT_ADC_PIN PA1
#define CURRENT_METER_ADC_PIN PB0
//#define RSSI_ADC_PIN PB1
@@ -166,7 +174,7 @@
//#define PINIO2_PIN PA15 // Camera switcher
//#define USE_PINIOBOX
-#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
+#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_AIRMODE | FEATURE_SOFTSERIAL)
#define CURRENT_METER_SCALE_DEFAULT 179
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
diff --git a/src/main/target/BETAFPVF411RX/target.mk b/src/main/target/BETAFPVF411RX/target.mk
index 965b78488e..e9ecda64c7 100644
--- a/src/main/target/BETAFPVF411RX/target.mk
+++ b/src/main/target/BETAFPVF411RX/target.mk
@@ -1,18 +1,19 @@
F411_TARGETS += $(TARGET)
-
-FEATURES += VCP
+FEATURES += VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_mpu6500.c \
+ drivers/accgyro/accgyro_spi_mpu6500.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
drivers/max7456.c \
drivers/rx/rx_cc2500.c \
- rx/cc2500_common.c \
+ rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
- rx/cc2500_frsky_x.c \
- rx/cc2500_redpine.c \
+ rx/cc2500_frsky_x.c \
+ rx/cc2500_redpine.c \
rx/cc2500_sfhss.c\
drivers/rx/rx_a7105.c \
- drivers/light_ws2811strip.c
+ drivers/light_ws2811strip.c
From c787ec20ca495c17ff9115cac4a3551089fdbf91 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Thu, 28 Mar 2024 15:57:06 -0500
Subject: [PATCH 31/33] [target] update IFRC_IFLIGHT_SUCCEX_E_F7 adding BMI270
and ICM20689 (#952)
[target] IFRC_IFLIGHT_SUCCEX_E_F7 add BMI270 and ICM20689
---
.../target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c | 2 +-
.../target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h | 19 ++++++++++++++--
.../target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk | 22 ++++++++++---------
3 files changed, 30 insertions(+), 13 deletions(-)
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c
index f6780a1a41..b8641b75c6 100644
--- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c
+++ b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c
@@ -28,7 +28,7 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0),
+ DEF_TIM(TIM5, CH1, PA0, TIM_USE_ANY, 0, 0), //cam
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h
index 372fc9d935..80fa7fbab1 100644
--- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h
+++ b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h
@@ -51,14 +51,29 @@
#define MPU6000_CS_PIN PA15
#define USE_GYRO
-#define USE_GYRO_SPI_MPU6000
-
#define USE_ACC
+
#define USE_ACC_SPI_MPU6000
+#define USE_GYRO_SPI_MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
+#define USE_GYRO_SPI_ICM20689
+#define USE_ACC_SPI_ICM20689
+#define ACC_ICM20689_ALIGN CW180_DEG
+#define GYRO_ICM20689_ALIGN CW180_DEG
+#define ICM20689_CS_PIN PA15
+#define ICM20689_SPI_INSTANCE SPI1
+
+#define USE_SPI_GYRO
+#define USE_GYRO_EXTI
+#define USE_ACCGYRO_BMI270
+#define ACC_BMI270_ALIGN CW180_DEG
+#define GYRO_BMI270_ALIGN CW180_DEG
+#define BMI270_CS_PIN PA15
+#define BMI270_SPI_INSTANCE SPI1
+
#define USE_VCP
#define USE_UART1
#define USE_UART2
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk
index b2c6c71023..d6804d7af7 100644
--- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk
+++ b/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk
@@ -2,13 +2,15 @@ F7X2RE_TARGETS += $(TARGET)
FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
- drivers/accgyro/accgyro_mpu.c \
- drivers/accgyro/accgyro_spi_mpu6000.c \
- drivers/barometer/barometer_bmp280.c \
- drivers/barometer/barometer_bmp085.c\
- drivers/barometer/barometer_ms5611.c\
- drivers/compass/compass_hmc5883l.c \
- drivers/compass/compass_qmc5883l.c \
- drivers/light_ws2811strip.c \
- drivers/light_ws2811strip_hal.c \
- drivers/max7456.c
+ drivers/accgyro/accgyro_mpu.c \
+ drivers/accgyro/accgyro_spi_mpu6000.c \
+ drivers/accgyro/accgyro_spi_icm20689.c \
+ drivers/accgyro/accgyro_spi_bmi270.c \
+ drivers/barometer/barometer_bmp280.c \
+ drivers/barometer/barometer_bmp085.c\
+ drivers/barometer/barometer_ms5611.c\
+ drivers/compass/compass_hmc5883l.c \
+ drivers/compass/compass_qmc5883l.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_hal.c \
+ drivers/max7456.c
From e82f193ca754895b90da18e8704b8235be512e6f Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Fri, 29 Mar 2024 11:42:50 -0500
Subject: [PATCH 32/33] [targets] fix naming conventions (#993)
* [targets] fix naming conventions; step 1 ; WIP
* [targets] proper ID and fixes for IFLIGHT targets
* [targets] return iflight succex mini
* [targets] fix MAMBAF405US_I2C.mk ifdef
---
.../{DAFP_DARWINF722HD => DARWINF722HD}/config.c | 0
.../{DAFP_DARWINF722HD => DARWINF722HD}/target.c | 0
.../{DAFP_DARWINF722HD => DARWINF722HD}/target.h | 0
.../{DAFP_DARWINF722HD => DARWINF722HD}/target.mk | 0
.../{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.c | 0
.../{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.h | 0
.../{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.mk | 0
.../{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.c | 0
.../{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.h | 0
.../{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.mk | 0
.../{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.c | 0
.../{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.h | 0
.../{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.mk | 0
.../target.c | 0
.../target.h | 0
.../target.mk | 0
src/main/target/IFLIGHT_BLITZ_F405/target.h | 8 +++++---
.../IFLIGHT_F405_TWING_M.mk.bak} | 0
.../target/{IFF4_AIO => IFLIGHT_F405_TWING}/target.c | 0
.../{IFF4_TWIN_G => IFLIGHT_F405_TWING}/target.h | 8 ++++----
.../{IFF4_TWIN_G => IFLIGHT_F405_TWING}/target.mk | 0
.../{IFF4_TWIN_G => IFLIGHT_F411_AIO32}/target.c | 0
.../target/{IFF4_AIO => IFLIGHT_F411_AIO32}/target.h | 7 +++++--
.../target/{IFF4_AIO => IFLIGHT_F411_AIO32}/target.mk | 0
.../target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.c | 0
.../target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.h | 8 ++++++--
.../target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.mk | 0
.../target.c | 0
.../{IFF7_TWIN_G => IFLIGHT_F722_TWING}/target.h | 6 ++++--
.../{IFF7_TWIN_G => IFLIGHT_F722_TWING}/target.mk | 0
.../target.c | 0
.../target.h | 6 ++++--
.../target.mk | 0
src/main/target/IFLIGHT_F745_AIO_V2/target.h | 6 ++++--
.../target/{IFF4_E => IFLIGHT_SUCCEX_E_F4}/target.c | 0
.../target/{IFF4_E => IFLIGHT_SUCCEX_E_F4}/target.h | 10 +++++-----
.../target.mk | 0
.../config.c | 0
.../{IFF7_TWIN_G => IFLIGHT_SUCCEX_E_F7}/target.c | 0
.../target.h | 6 ++++--
.../target.mk | 0
.../target.c | 0
.../target.h | 10 ++++++++--
.../{IFF4_E => IFLIGHT_SUCCEX_MINI_F4}/target.mk | 0
src/main/target/{IFRC_JBF7 => JBF7}/config.c | 0
src/main/target/{IFRC_JBF7 => JBF7}/target.c | 0
src/main/target/{IFRC_JBF7 => JBF7}/target.h | 0
src/main/target/{IFRC_JBF7 => JBF7}/target.mk | 0
.../MAMBAF405US_I2C.mk} | 0
.../target/{DIAT_MAMBAF405US => MAMBAF405US}/config.c | 0
.../target/{DIAT_MAMBAF405US => MAMBAF405US}/target.c | 0
.../target/{DIAT_MAMBAF405US => MAMBAF405US}/target.h | 4 ++--
.../target/{DIAT_MAMBAF405US => MAMBAF405US}/target.mk | 0
.../{DIAT_MAMBAF405_2022B => MAMBAF405_2022B}/target.c | 0
.../{DIAT_MAMBAF405_2022B => MAMBAF405_2022B}/target.h | 0
.../target.mk | 0
.../target/{TEBS_PODRACERAIO => PODRACERAIO}/target.c | 0
.../target/{TEBS_PODRACERAIO => PODRACERAIO}/target.h | 0
.../target/{TEBS_PODRACERAIO => PODRACERAIO}/target.mk | 0
.../{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.c | 0
.../{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.h | 0
.../{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.mk | 0
.../{HENA_TALONF7DJIHD => TALONF7DJIHD}/config.c | 0
.../{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.c | 0
.../{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.h | 0
.../{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.mk | 0
src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/config.c | 0
src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.c | 0
src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.h | 0
src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.mk | 0
.../target/{TMTR_TMOTORF4HD => TMOTORF4HD}/config.c | 0
.../target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.c | 0
.../target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.h | 0
.../target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.mk | 0
src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.c | 0
src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.h | 0
src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.mk | 0
src/main/target/{TMTR_TMPACERF7 => TMPACERF7}/target.c | 0
src/main/target/{TMTR_TMPACERF7 => TMPACERF7}/target.h | 0
.../target/{TMTR_TMPACERF7 => TMPACERF7}/target.mk | 0
src/main/target/{TMTR_TMVELOX => TMVELOX}/config.c | 0
src/main/target/{TMTR_TMVELOX => TMVELOX}/target.c | 0
src/main/target/{TMTR_TMVELOX => TMVELOX}/target.h | 0
src/main/target/{TMTR_TMVELOX => TMVELOX}/target.mk | 0
84 files changed, 51 insertions(+), 28 deletions(-)
rename src/main/target/{DAFP_DARWINF722HD => DARWINF722HD}/config.c (100%)
rename src/main/target/{DAFP_DARWINF722HD => DARWINF722HD}/target.c (100%)
rename src/main/target/{DAFP_DARWINF722HD => DARWINF722HD}/target.h (100%)
rename src/main/target/{DAFP_DARWINF722HD => DARWINF722HD}/target.mk (100%)
rename src/main/target/{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.c (100%)
rename src/main/target/{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.h (100%)
rename src/main/target/{FLWO_FLYWOOF411FR => FLYWOOF411FR}/target.mk (100%)
rename src/main/target/{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.c (100%)
rename src/main/target/{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.h (100%)
rename src/main/target/{FLWO_FLYWOOF411V2 => FLYWOOF411V2}/target.mk (100%)
rename src/main/target/{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.c (100%)
rename src/main/target/{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.h (100%)
rename src/main/target/{TURC_FPVCYCLEF401 => FPVCYCLEF401}/target.mk (100%)
rename src/main/target/{HOWI_HOBBYWING_XROTORF7CONV => HOBBYWING_XROTORF7CONV}/target.c (100%)
rename src/main/target/{HOWI_HOBBYWING_XROTORF7CONV => HOBBYWING_XROTORF7CONV}/target.h (100%)
rename src/main/target/{HOWI_HOBBYWING_XROTORF7CONV => HOBBYWING_XROTORF7CONV}/target.mk (100%)
rename src/main/target/{IFF4_TWIN_G/IFF4_TWIN_G_M.mk => IFLIGHT_F405_TWING/IFLIGHT_F405_TWING_M.mk.bak} (100%)
rename src/main/target/{IFF4_AIO => IFLIGHT_F405_TWING}/target.c (100%)
rename src/main/target/{IFF4_TWIN_G => IFLIGHT_F405_TWING}/target.h (96%)
rename src/main/target/{IFF4_TWIN_G => IFLIGHT_F405_TWING}/target.mk (100%)
rename src/main/target/{IFF4_TWIN_G => IFLIGHT_F411_AIO32}/target.c (100%)
rename src/main/target/{IFF4_AIO => IFLIGHT_F411_AIO32}/target.h (94%)
rename src/main/target/{IFF4_AIO => IFLIGHT_F411_AIO32}/target.mk (100%)
rename src/main/target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.c (100%)
rename src/main/target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.h (96%)
rename src/main/target/{IFF411_PRO => IFLIGHT_F411_PRO}/target.mk (100%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F7 => IFLIGHT_F722_TWING}/target.c (100%)
rename src/main/target/{IFF7_TWIN_G => IFLIGHT_F722_TWING}/target.h (95%)
rename src/main/target/{IFF7_TWIN_G => IFLIGHT_F722_TWING}/target.mk (100%)
rename src/main/target/{IFRC_IFLIGHT_F745_AIO => IFLIGHT_F745_AIO}/target.c (100%)
rename src/main/target/{IFRC_IFLIGHT_F745_AIO => IFLIGHT_F745_AIO}/target.h (96%)
rename src/main/target/{IFRC_IFLIGHT_F745_AIO => IFLIGHT_F745_AIO}/target.mk (100%)
rename src/main/target/{IFF4_E => IFLIGHT_SUCCEX_E_F4}/target.c (100%)
rename src/main/target/{IFF4_E => IFLIGHT_SUCCEX_E_F4}/target.h (95%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F4 => IFLIGHT_SUCCEX_E_F4}/target.mk (100%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F7 => IFLIGHT_SUCCEX_E_F7}/config.c (100%)
rename src/main/target/{IFF7_TWIN_G => IFLIGHT_SUCCEX_E_F7}/target.c (100%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F7 => IFLIGHT_SUCCEX_E_F7}/target.h (95%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F7 => IFLIGHT_SUCCEX_E_F7}/target.mk (100%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F4 => IFLIGHT_SUCCEX_MINI_F4}/target.c (100%)
rename src/main/target/{IFRC_IFLIGHT_SUCCEX_E_F4 => IFLIGHT_SUCCEX_MINI_F4}/target.h (93%)
rename src/main/target/{IFF4_E => IFLIGHT_SUCCEX_MINI_F4}/target.mk (100%)
rename src/main/target/{IFRC_JBF7 => JBF7}/config.c (100%)
rename src/main/target/{IFRC_JBF7 => JBF7}/target.c (100%)
rename src/main/target/{IFRC_JBF7 => JBF7}/target.h (100%)
rename src/main/target/{IFRC_JBF7 => JBF7}/target.mk (100%)
rename src/main/target/{DIAT_MAMBAF405US/DIAT_MAMBAF405US_I2C.mk => MAMBAF405US/MAMBAF405US_I2C.mk} (100%)
rename src/main/target/{DIAT_MAMBAF405US => MAMBAF405US}/config.c (100%)
rename src/main/target/{DIAT_MAMBAF405US => MAMBAF405US}/target.c (100%)
rename src/main/target/{DIAT_MAMBAF405US => MAMBAF405US}/target.h (98%)
rename src/main/target/{DIAT_MAMBAF405US => MAMBAF405US}/target.mk (100%)
rename src/main/target/{DIAT_MAMBAF405_2022B => MAMBAF405_2022B}/target.c (100%)
rename src/main/target/{DIAT_MAMBAF405_2022B => MAMBAF405_2022B}/target.h (100%)
rename src/main/target/{DIAT_MAMBAF405_2022B => MAMBAF405_2022B}/target.mk (100%)
rename src/main/target/{TEBS_PODRACERAIO => PODRACERAIO}/target.c (100%)
rename src/main/target/{TEBS_PODRACERAIO => PODRACERAIO}/target.h (100%)
rename src/main/target/{TEBS_PODRACERAIO => PODRACERAIO}/target.mk (100%)
rename src/main/target/{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.c (100%)
rename src/main/target/{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.h (100%)
rename src/main/target/{SPBE_SPEEDYBEEF7V3 => SPEEDYBEEF7V3}/target.mk (100%)
rename src/main/target/{HENA_TALONF7DJIHD => TALONF7DJIHD}/config.c (100%)
rename src/main/target/{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.c (100%)
rename src/main/target/{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.h (100%)
rename src/main/target/{HENA_TALONF7DJIHD => TALONF7DJIHD}/target.mk (100%)
rename src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/config.c (100%)
rename src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.c (100%)
rename src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.h (100%)
rename src/main/target/{TMTR_TMOTORF4 => TMOTORF4}/target.mk (100%)
rename src/main/target/{TMTR_TMOTORF4HD => TMOTORF4HD}/config.c (100%)
rename src/main/target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.c (100%)
rename src/main/target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.h (100%)
rename src/main/target/{TMTR_TMOTORF4HD => TMOTORF4HD}/target.mk (100%)
rename src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.c (100%)
rename src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.h (100%)
rename src/main/target/{TMTR_TMOTORF7 => TMOTORF7}/target.mk (100%)
rename src/main/target/{TMTR_TMPACERF7 => TMPACERF7}/target.c (100%)
rename src/main/target/{TMTR_TMPACERF7 => TMPACERF7}/target.h (100%)
rename src/main/target/{TMTR_TMPACERF7 => TMPACERF7}/target.mk (100%)
rename src/main/target/{TMTR_TMVELOX => TMVELOX}/config.c (100%)
rename src/main/target/{TMTR_TMVELOX => TMVELOX}/target.c (100%)
rename src/main/target/{TMTR_TMVELOX => TMVELOX}/target.h (100%)
rename src/main/target/{TMTR_TMVELOX => TMVELOX}/target.mk (100%)
diff --git a/src/main/target/DAFP_DARWINF722HD/config.c b/src/main/target/DARWINF722HD/config.c
similarity index 100%
rename from src/main/target/DAFP_DARWINF722HD/config.c
rename to src/main/target/DARWINF722HD/config.c
diff --git a/src/main/target/DAFP_DARWINF722HD/target.c b/src/main/target/DARWINF722HD/target.c
similarity index 100%
rename from src/main/target/DAFP_DARWINF722HD/target.c
rename to src/main/target/DARWINF722HD/target.c
diff --git a/src/main/target/DAFP_DARWINF722HD/target.h b/src/main/target/DARWINF722HD/target.h
similarity index 100%
rename from src/main/target/DAFP_DARWINF722HD/target.h
rename to src/main/target/DARWINF722HD/target.h
diff --git a/src/main/target/DAFP_DARWINF722HD/target.mk b/src/main/target/DARWINF722HD/target.mk
similarity index 100%
rename from src/main/target/DAFP_DARWINF722HD/target.mk
rename to src/main/target/DARWINF722HD/target.mk
diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.c b/src/main/target/FLYWOOF411FR/target.c
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411FR/target.c
rename to src/main/target/FLYWOOF411FR/target.c
diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.h b/src/main/target/FLYWOOF411FR/target.h
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411FR/target.h
rename to src/main/target/FLYWOOF411FR/target.h
diff --git a/src/main/target/FLWO_FLYWOOF411FR/target.mk b/src/main/target/FLYWOOF411FR/target.mk
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411FR/target.mk
rename to src/main/target/FLYWOOF411FR/target.mk
diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.c b/src/main/target/FLYWOOF411V2/target.c
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411V2/target.c
rename to src/main/target/FLYWOOF411V2/target.c
diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.h b/src/main/target/FLYWOOF411V2/target.h
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411V2/target.h
rename to src/main/target/FLYWOOF411V2/target.h
diff --git a/src/main/target/FLWO_FLYWOOF411V2/target.mk b/src/main/target/FLYWOOF411V2/target.mk
similarity index 100%
rename from src/main/target/FLWO_FLYWOOF411V2/target.mk
rename to src/main/target/FLYWOOF411V2/target.mk
diff --git a/src/main/target/TURC_FPVCYCLEF401/target.c b/src/main/target/FPVCYCLEF401/target.c
similarity index 100%
rename from src/main/target/TURC_FPVCYCLEF401/target.c
rename to src/main/target/FPVCYCLEF401/target.c
diff --git a/src/main/target/TURC_FPVCYCLEF401/target.h b/src/main/target/FPVCYCLEF401/target.h
similarity index 100%
rename from src/main/target/TURC_FPVCYCLEF401/target.h
rename to src/main/target/FPVCYCLEF401/target.h
diff --git a/src/main/target/TURC_FPVCYCLEF401/target.mk b/src/main/target/FPVCYCLEF401/target.mk
similarity index 100%
rename from src/main/target/TURC_FPVCYCLEF401/target.mk
rename to src/main/target/FPVCYCLEF401/target.mk
diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.c b/src/main/target/HOBBYWING_XROTORF7CONV/target.c
similarity index 100%
rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.c
rename to src/main/target/HOBBYWING_XROTORF7CONV/target.c
diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.h b/src/main/target/HOBBYWING_XROTORF7CONV/target.h
similarity index 100%
rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.h
rename to src/main/target/HOBBYWING_XROTORF7CONV/target.h
diff --git a/src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.mk b/src/main/target/HOBBYWING_XROTORF7CONV/target.mk
similarity index 100%
rename from src/main/target/HOWI_HOBBYWING_XROTORF7CONV/target.mk
rename to src/main/target/HOBBYWING_XROTORF7CONV/target.mk
diff --git a/src/main/target/IFLIGHT_BLITZ_F405/target.h b/src/main/target/IFLIGHT_BLITZ_F405/target.h
index 45e86da05b..bb0d69a611 100644
--- a/src/main/target/IFLIGHT_BLITZ_F405/target.h
+++ b/src/main/target/IFLIGHT_BLITZ_F405/target.h
@@ -21,9 +21,11 @@
//#define USE_TARGET_CONFIG
-#define TARGET_BOARD_IDENTIFIER "IBF4"
-#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
-#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F405"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_BLITZ_F405"
+
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
#define LED0_PIN PC15
diff --git a/src/main/target/IFF4_TWIN_G/IFF4_TWIN_G_M.mk b/src/main/target/IFLIGHT_F405_TWING/IFLIGHT_F405_TWING_M.mk.bak
similarity index 100%
rename from src/main/target/IFF4_TWIN_G/IFF4_TWIN_G_M.mk
rename to src/main/target/IFLIGHT_F405_TWING/IFLIGHT_F405_TWING_M.mk.bak
diff --git a/src/main/target/IFF4_AIO/target.c b/src/main/target/IFLIGHT_F405_TWING/target.c
similarity index 100%
rename from src/main/target/IFF4_AIO/target.c
rename to src/main/target/IFLIGHT_F405_TWING/target.c
diff --git a/src/main/target/IFF4_TWIN_G/target.h b/src/main/target/IFLIGHT_F405_TWING/target.h
similarity index 96%
rename from src/main/target/IFF4_TWIN_G/target.h
rename to src/main/target/IFLIGHT_F405_TWING/target.h
index 9253ffe9e7..c8a693f7c9 100644
--- a/src/main/target/IFF4_TWIN_G/target.h
+++ b/src/main/target/IFLIGHT_F405_TWING/target.h
@@ -20,12 +20,12 @@
#pragma once
-#if defined(IFF4_TWIN_G_M)
+#if defined(IFLIGHT_F405_TWING_M)
#define TARGET_BOARD_IDENTIFIER "S405"
-#define USBD_PRODUCT_STRING "IFLIGHTF4TWIN_G_mpu6000"
+#define USBD_PRODUCT_STRING "IFLIGHT_F405_TWING_M"
#else
#define TARGET_BOARD_IDENTIFIER "S405"
-#define USBD_PRODUCT_STRING "IFLIGHTF4TWIN_G"
+#define USBD_PRODUCT_STRING "IFLIGHT_F405_TWING"
#endif
#define USE_DSHOT_DMAR
@@ -47,7 +47,7 @@
#define PINIO1_PIN PC14
#define PINIO2_PIN PC15
-#if defined(IFF4_TWIN_G_M)
+#if defined(IFLIGHT_F405_TWING_M)
#define USE_MPU_DATA_READY_SIGNAL
#define USE_EXTI
diff --git a/src/main/target/IFF4_TWIN_G/target.mk b/src/main/target/IFLIGHT_F405_TWING/target.mk
similarity index 100%
rename from src/main/target/IFF4_TWIN_G/target.mk
rename to src/main/target/IFLIGHT_F405_TWING/target.mk
diff --git a/src/main/target/IFF4_TWIN_G/target.c b/src/main/target/IFLIGHT_F411_AIO32/target.c
similarity index 100%
rename from src/main/target/IFF4_TWIN_G/target.c
rename to src/main/target/IFLIGHT_F411_AIO32/target.c
diff --git a/src/main/target/IFF4_AIO/target.h b/src/main/target/IFLIGHT_F411_AIO32/target.h
similarity index 94%
rename from src/main/target/IFF4_AIO/target.h
rename to src/main/target/IFLIGHT_F411_AIO32/target.h
index 0851f4f9e4..057462579d 100644
--- a/src/main/target/IFF4_AIO/target.h
+++ b/src/main/target/IFLIGHT_F411_AIO32/target.h
@@ -20,8 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S411"
-#define USBD_PRODUCT_STRING "IFLIGHT F411 AIO"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_F411_AIO32"
+
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
#define LED0_PIN PB5
diff --git a/src/main/target/IFF4_AIO/target.mk b/src/main/target/IFLIGHT_F411_AIO32/target.mk
similarity index 100%
rename from src/main/target/IFF4_AIO/target.mk
rename to src/main/target/IFLIGHT_F411_AIO32/target.mk
diff --git a/src/main/target/IFF411_PRO/target.c b/src/main/target/IFLIGHT_F411_PRO/target.c
similarity index 100%
rename from src/main/target/IFF411_PRO/target.c
rename to src/main/target/IFLIGHT_F411_PRO/target.c
diff --git a/src/main/target/IFF411_PRO/target.h b/src/main/target/IFLIGHT_F411_PRO/target.h
similarity index 96%
rename from src/main/target/IFF411_PRO/target.h
rename to src/main/target/IFLIGHT_F411_PRO/target.h
index d84e8ed6f4..2539723608 100644
--- a/src/main/target/IFF411_PRO/target.h
+++ b/src/main/target/IFLIGHT_F411_PRO/target.h
@@ -19,8 +19,12 @@
*/
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S411"
-#define USBD_PRODUCT_STRING "IFLIGHT F411 PRO"
+
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_F411_PRO"
+
+#define FC_TARGET_MCU STM32F411 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S411" // generic ID
#define ENABLE_DSHOT_DMAR true
diff --git a/src/main/target/IFF411_PRO/target.mk b/src/main/target/IFLIGHT_F411_PRO/target.mk
similarity index 100%
rename from src/main/target/IFF411_PRO/target.mk
rename to src/main/target/IFLIGHT_F411_PRO/target.mk
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c b/src/main/target/IFLIGHT_F722_TWING/target.c
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.c
rename to src/main/target/IFLIGHT_F722_TWING/target.c
diff --git a/src/main/target/IFF7_TWIN_G/target.h b/src/main/target/IFLIGHT_F722_TWING/target.h
similarity index 95%
rename from src/main/target/IFF7_TWIN_G/target.h
rename to src/main/target/IFLIGHT_F722_TWING/target.h
index dcaf56de6f..535a4b68b0 100644
--- a/src/main/target/IFF7_TWIN_G/target.h
+++ b/src/main/target/IFLIGHT_F722_TWING/target.h
@@ -20,9 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X2"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_F722_TWING"
-#define USBD_PRODUCT_STRING "IFLIGHT F7 TWIN G"
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
#define USE_DUAL_GYRO
diff --git a/src/main/target/IFF7_TWIN_G/target.mk b/src/main/target/IFLIGHT_F722_TWING/target.mk
similarity index 100%
rename from src/main/target/IFF7_TWIN_G/target.mk
rename to src/main/target/IFLIGHT_F722_TWING/target.mk
diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.c b/src/main/target/IFLIGHT_F745_AIO/target.c
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.c
rename to src/main/target/IFLIGHT_F745_AIO/target.c
diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.h b/src/main/target/IFLIGHT_F745_AIO/target.h
similarity index 96%
rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.h
rename to src/main/target/IFLIGHT_F745_AIO/target.h
index 0cf4b6b8b7..c32ed746ed 100644
--- a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.h
+++ b/src/main/target/IFLIGHT_F745_AIO/target.h
@@ -20,10 +20,12 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "IFRC"
-
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
#define USBD_PRODUCT_STRING "IFLIGHT_F745_AIO"
+#define FC_TARGET_MCU STM32F745 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+
#define LED0_PIN PC13
#define USE_BEEPER
diff --git a/src/main/target/IFRC_IFLIGHT_F745_AIO/target.mk b/src/main/target/IFLIGHT_F745_AIO/target.mk
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_F745_AIO/target.mk
rename to src/main/target/IFLIGHT_F745_AIO/target.mk
diff --git a/src/main/target/IFLIGHT_F745_AIO_V2/target.h b/src/main/target/IFLIGHT_F745_AIO_V2/target.h
index e771a75672..e9a9e73836 100644
--- a/src/main/target/IFLIGHT_F745_AIO_V2/target.h
+++ b/src/main/target/IFLIGHT_F745_AIO_V2/target.h
@@ -20,10 +20,12 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "IFRC"
-
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
#define USBD_PRODUCT_STRING "IFLIGHT_F745_AIO_V2"
+#define FC_TARGET_MCU STM32F745 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S745" // generic ID
+
#define ENABLE_DSHOT_DMAR true
#define LED0_PIN PC13
diff --git a/src/main/target/IFF4_E/target.c b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.c
similarity index 100%
rename from src/main/target/IFF4_E/target.c
rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.c
diff --git a/src/main/target/IFF4_E/target.h b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.h
similarity index 95%
rename from src/main/target/IFF4_E/target.h
rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.h
index fb0ea6a4eb..a52e5907db 100644
--- a/src/main/target/IFF4_E/target.h
+++ b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.h
@@ -20,8 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "IFRC"
-#define USBD_PRODUCT_STRING "IFLIGHT SUCCEX E F4"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F4"
+
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
#define LED0_PIN PB5
@@ -105,9 +108,6 @@
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
-#define USE_BARO
-#define USE_BARO_BMP280
-
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.mk b/src/main/target/IFLIGHT_SUCCEX_E_F4/target.mk
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.mk
rename to src/main/target/IFLIGHT_SUCCEX_E_F4/target.mk
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/config.c b/src/main/target/IFLIGHT_SUCCEX_E_F7/config.c
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/config.c
rename to src/main/target/IFLIGHT_SUCCEX_E_F7/config.c
diff --git a/src/main/target/IFF7_TWIN_G/target.c b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.c
similarity index 100%
rename from src/main/target/IFF7_TWIN_G/target.c
rename to src/main/target/IFLIGHT_SUCCEX_E_F7/target.c
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.h
similarity index 95%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h
rename to src/main/target/IFLIGHT_SUCCEX_E_F7/target.h
index 80fa7fbab1..4a93895a28 100644
--- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.h
+++ b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.h
@@ -20,9 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "S7X2"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F7"
-#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_E_F7"
+#define FC_TARGET_MCU STM32F7X2 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S7X2" // generic ID
#define ENABLE_DSHOT_DMAR true
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk b/src/main/target/IFLIGHT_SUCCEX_E_F7/target.mk
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F7/target.mk
rename to src/main/target/IFLIGHT_SUCCEX_E_F7/target.mk
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.c b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.c
similarity index 100%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.c
rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.c
diff --git a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h
similarity index 93%
rename from src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h
rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h
index 634e216822..5042c44db7 100644
--- a/src/main/target/IFRC_IFLIGHT_SUCCEX_E_F4/target.h
+++ b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.h
@@ -20,8 +20,11 @@
#pragma once
-#define TARGET_BOARD_IDENTIFIER "IFRC"
-#define USBD_PRODUCT_STRING "IFLIGHT SUCCEX E F4"
+#define TARGET_MANUFACTURER_IDENTIFIER "IFRC"
+#define USBD_PRODUCT_STRING "IFLIGHT_SUCCEX_MINI_F4"
+
+#define FC_TARGET_MCU STM32F405 // not used in EmuF
+#define TARGET_BOARD_IDENTIFIER "S405" // generic ID
#define LED0_PIN PB5
@@ -105,6 +108,9 @@
#define SPI3_MISO_PIN PC11
#define SPI3_MOSI_PIN PC12
+#define USE_BARO
+#define USE_BARO_BMP280
+
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
diff --git a/src/main/target/IFF4_E/target.mk b/src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.mk
similarity index 100%
rename from src/main/target/IFF4_E/target.mk
rename to src/main/target/IFLIGHT_SUCCEX_MINI_F4/target.mk
diff --git a/src/main/target/IFRC_JBF7/config.c b/src/main/target/JBF7/config.c
similarity index 100%
rename from src/main/target/IFRC_JBF7/config.c
rename to src/main/target/JBF7/config.c
diff --git a/src/main/target/IFRC_JBF7/target.c b/src/main/target/JBF7/target.c
similarity index 100%
rename from src/main/target/IFRC_JBF7/target.c
rename to src/main/target/JBF7/target.c
diff --git a/src/main/target/IFRC_JBF7/target.h b/src/main/target/JBF7/target.h
similarity index 100%
rename from src/main/target/IFRC_JBF7/target.h
rename to src/main/target/JBF7/target.h
diff --git a/src/main/target/IFRC_JBF7/target.mk b/src/main/target/JBF7/target.mk
similarity index 100%
rename from src/main/target/IFRC_JBF7/target.mk
rename to src/main/target/JBF7/target.mk
diff --git a/src/main/target/DIAT_MAMBAF405US/DIAT_MAMBAF405US_I2C.mk b/src/main/target/MAMBAF405US/MAMBAF405US_I2C.mk
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405US/DIAT_MAMBAF405US_I2C.mk
rename to src/main/target/MAMBAF405US/MAMBAF405US_I2C.mk
diff --git a/src/main/target/DIAT_MAMBAF405US/config.c b/src/main/target/MAMBAF405US/config.c
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405US/config.c
rename to src/main/target/MAMBAF405US/config.c
diff --git a/src/main/target/DIAT_MAMBAF405US/target.c b/src/main/target/MAMBAF405US/target.c
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405US/target.c
rename to src/main/target/MAMBAF405US/target.c
diff --git a/src/main/target/DIAT_MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h
similarity index 98%
rename from src/main/target/DIAT_MAMBAF405US/target.h
rename to src/main/target/MAMBAF405US/target.h
index d2ffbb529c..8dcd92d716 100644
--- a/src/main/target/DIAT_MAMBAF405US/target.h
+++ b/src/main/target/MAMBAF405US/target.h
@@ -20,7 +20,7 @@
#pragma once
-#if defined(DIAT_MAMBAF405US_I2C)
+#if defined(MAMBAF405US_I2C)
#define TARGET_BOARD_IDENTIFIER "S405"
#define USBD_PRODUCT_STRING "MAMBAF405US I2C"
#else
@@ -79,7 +79,7 @@
#define USE_I2C
#define USE_I2C_DEVICE_2
#define I2C_DEVICE (I2CDEV_2)
-#if defined(DIAT_MAMBAF405US_I2C)
+#if defined(MAMBAF405US_I2C)
#define I2C2_SCL PB8 // SCL pad PB10, shared with UART3TX
#define I2C2_SDA PB9 // SDA pad PB11, shared with UART3RX
#else
diff --git a/src/main/target/DIAT_MAMBAF405US/target.mk b/src/main/target/MAMBAF405US/target.mk
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405US/target.mk
rename to src/main/target/MAMBAF405US/target.mk
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.c b/src/main/target/MAMBAF405_2022B/target.c
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405_2022B/target.c
rename to src/main/target/MAMBAF405_2022B/target.c
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.h b/src/main/target/MAMBAF405_2022B/target.h
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405_2022B/target.h
rename to src/main/target/MAMBAF405_2022B/target.h
diff --git a/src/main/target/DIAT_MAMBAF405_2022B/target.mk b/src/main/target/MAMBAF405_2022B/target.mk
similarity index 100%
rename from src/main/target/DIAT_MAMBAF405_2022B/target.mk
rename to src/main/target/MAMBAF405_2022B/target.mk
diff --git a/src/main/target/TEBS_PODRACERAIO/target.c b/src/main/target/PODRACERAIO/target.c
similarity index 100%
rename from src/main/target/TEBS_PODRACERAIO/target.c
rename to src/main/target/PODRACERAIO/target.c
diff --git a/src/main/target/TEBS_PODRACERAIO/target.h b/src/main/target/PODRACERAIO/target.h
similarity index 100%
rename from src/main/target/TEBS_PODRACERAIO/target.h
rename to src/main/target/PODRACERAIO/target.h
diff --git a/src/main/target/TEBS_PODRACERAIO/target.mk b/src/main/target/PODRACERAIO/target.mk
similarity index 100%
rename from src/main/target/TEBS_PODRACERAIO/target.mk
rename to src/main/target/PODRACERAIO/target.mk
diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.c b/src/main/target/SPEEDYBEEF7V3/target.c
similarity index 100%
rename from src/main/target/SPBE_SPEEDYBEEF7V3/target.c
rename to src/main/target/SPEEDYBEEF7V3/target.c
diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.h b/src/main/target/SPEEDYBEEF7V3/target.h
similarity index 100%
rename from src/main/target/SPBE_SPEEDYBEEF7V3/target.h
rename to src/main/target/SPEEDYBEEF7V3/target.h
diff --git a/src/main/target/SPBE_SPEEDYBEEF7V3/target.mk b/src/main/target/SPEEDYBEEF7V3/target.mk
similarity index 100%
rename from src/main/target/SPBE_SPEEDYBEEF7V3/target.mk
rename to src/main/target/SPEEDYBEEF7V3/target.mk
diff --git a/src/main/target/HENA_TALONF7DJIHD/config.c b/src/main/target/TALONF7DJIHD/config.c
similarity index 100%
rename from src/main/target/HENA_TALONF7DJIHD/config.c
rename to src/main/target/TALONF7DJIHD/config.c
diff --git a/src/main/target/HENA_TALONF7DJIHD/target.c b/src/main/target/TALONF7DJIHD/target.c
similarity index 100%
rename from src/main/target/HENA_TALONF7DJIHD/target.c
rename to src/main/target/TALONF7DJIHD/target.c
diff --git a/src/main/target/HENA_TALONF7DJIHD/target.h b/src/main/target/TALONF7DJIHD/target.h
similarity index 100%
rename from src/main/target/HENA_TALONF7DJIHD/target.h
rename to src/main/target/TALONF7DJIHD/target.h
diff --git a/src/main/target/HENA_TALONF7DJIHD/target.mk b/src/main/target/TALONF7DJIHD/target.mk
similarity index 100%
rename from src/main/target/HENA_TALONF7DJIHD/target.mk
rename to src/main/target/TALONF7DJIHD/target.mk
diff --git a/src/main/target/TMTR_TMOTORF4/config.c b/src/main/target/TMOTORF4/config.c
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4/config.c
rename to src/main/target/TMOTORF4/config.c
diff --git a/src/main/target/TMTR_TMOTORF4/target.c b/src/main/target/TMOTORF4/target.c
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4/target.c
rename to src/main/target/TMOTORF4/target.c
diff --git a/src/main/target/TMTR_TMOTORF4/target.h b/src/main/target/TMOTORF4/target.h
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4/target.h
rename to src/main/target/TMOTORF4/target.h
diff --git a/src/main/target/TMTR_TMOTORF4/target.mk b/src/main/target/TMOTORF4/target.mk
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4/target.mk
rename to src/main/target/TMOTORF4/target.mk
diff --git a/src/main/target/TMTR_TMOTORF4HD/config.c b/src/main/target/TMOTORF4HD/config.c
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4HD/config.c
rename to src/main/target/TMOTORF4HD/config.c
diff --git a/src/main/target/TMTR_TMOTORF4HD/target.c b/src/main/target/TMOTORF4HD/target.c
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4HD/target.c
rename to src/main/target/TMOTORF4HD/target.c
diff --git a/src/main/target/TMTR_TMOTORF4HD/target.h b/src/main/target/TMOTORF4HD/target.h
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4HD/target.h
rename to src/main/target/TMOTORF4HD/target.h
diff --git a/src/main/target/TMTR_TMOTORF4HD/target.mk b/src/main/target/TMOTORF4HD/target.mk
similarity index 100%
rename from src/main/target/TMTR_TMOTORF4HD/target.mk
rename to src/main/target/TMOTORF4HD/target.mk
diff --git a/src/main/target/TMTR_TMOTORF7/target.c b/src/main/target/TMOTORF7/target.c
similarity index 100%
rename from src/main/target/TMTR_TMOTORF7/target.c
rename to src/main/target/TMOTORF7/target.c
diff --git a/src/main/target/TMTR_TMOTORF7/target.h b/src/main/target/TMOTORF7/target.h
similarity index 100%
rename from src/main/target/TMTR_TMOTORF7/target.h
rename to src/main/target/TMOTORF7/target.h
diff --git a/src/main/target/TMTR_TMOTORF7/target.mk b/src/main/target/TMOTORF7/target.mk
similarity index 100%
rename from src/main/target/TMTR_TMOTORF7/target.mk
rename to src/main/target/TMOTORF7/target.mk
diff --git a/src/main/target/TMTR_TMPACERF7/target.c b/src/main/target/TMPACERF7/target.c
similarity index 100%
rename from src/main/target/TMTR_TMPACERF7/target.c
rename to src/main/target/TMPACERF7/target.c
diff --git a/src/main/target/TMTR_TMPACERF7/target.h b/src/main/target/TMPACERF7/target.h
similarity index 100%
rename from src/main/target/TMTR_TMPACERF7/target.h
rename to src/main/target/TMPACERF7/target.h
diff --git a/src/main/target/TMTR_TMPACERF7/target.mk b/src/main/target/TMPACERF7/target.mk
similarity index 100%
rename from src/main/target/TMTR_TMPACERF7/target.mk
rename to src/main/target/TMPACERF7/target.mk
diff --git a/src/main/target/TMTR_TMVELOX/config.c b/src/main/target/TMVELOX/config.c
similarity index 100%
rename from src/main/target/TMTR_TMVELOX/config.c
rename to src/main/target/TMVELOX/config.c
diff --git a/src/main/target/TMTR_TMVELOX/target.c b/src/main/target/TMVELOX/target.c
similarity index 100%
rename from src/main/target/TMTR_TMVELOX/target.c
rename to src/main/target/TMVELOX/target.c
diff --git a/src/main/target/TMTR_TMVELOX/target.h b/src/main/target/TMVELOX/target.h
similarity index 100%
rename from src/main/target/TMTR_TMVELOX/target.h
rename to src/main/target/TMVELOX/target.h
diff --git a/src/main/target/TMTR_TMVELOX/target.mk b/src/main/target/TMVELOX/target.mk
similarity index 100%
rename from src/main/target/TMTR_TMVELOX/target.mk
rename to src/main/target/TMVELOX/target.mk
From 1259124a095f187862eef46c29e5f9461087b5c3 Mon Sep 17 00:00:00 2001
From: nerdCopter <56646290+nerdCopter@users.noreply.github.com>
Date: Tue, 2 Apr 2024 11:00:28 -0500
Subject: [PATCH 33/33] default PID Denom 2 for F411 (#994)
* default pid denom 2 only for F411 (and unused F3)
---
src/main/flight/pid.c | 8 +++-----
1 file changed, 3 insertions(+), 5 deletions(-)
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index be511b02f7..e5e7601ab6 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -84,12 +84,10 @@ extern bool linearThrustEnabled;
PG_REGISTER_WITH_RESET_TEMPLATE(pidConfig_t, pidConfig, PG_PID_CONFIG, 2);
-#ifdef STM32F10X
-#define PID_PROCESS_DENOM_DEFAULT 1
-#elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270)
-#define PID_PROCESS_DENOM_DEFAULT 1
-#else
+#if defined(STM32F3) || defined(STM32F411xE)
#define PID_PROCESS_DENOM_DEFAULT 2
+#else
+#define PID_PROCESS_DENOM_DEFAULT 1
#endif
#ifndef DEFAULT_PIDS_ROLL