diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 4eead02a73..9aa53934ac 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -351,8 +351,6 @@ main_sources(COMMON_SRC io/beeper.c io/beeper.h - io/esc_serialshot.c - io/esc_serialshot.h io/servo_sbus.c io/servo_sbus.h io/frsky_osd.c diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index aa2619b104..c8aeb8eb0f 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -67,16 +67,13 @@ static const char * pwmInitErrorMsg[] = { }; static const motorProtocolProperties_t motorProtocolProperties[] = { - [PWM_TYPE_STANDARD] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false }, - [PWM_TYPE_ONESHOT125] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false }, - [PWM_TYPE_ONESHOT42] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false }, - [PWM_TYPE_MULTISHOT] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false }, - [PWM_TYPE_BRUSHED] = { .usesHwTimer = true, .isDSHOT = false, .isSerialShot = false }, - [PWM_TYPE_DSHOT150] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false }, - [PWM_TYPE_DSHOT300] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false }, - [PWM_TYPE_DSHOT600] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false }, - [PWM_TYPE_DSHOT1200] = { .usesHwTimer = true, .isDSHOT = true, .isSerialShot = false }, - [PWM_TYPE_SERIALSHOT] = { .usesHwTimer = false, .isDSHOT = false, .isSerialShot = true }, + [PWM_TYPE_STANDARD] = { .usesHwTimer = true, .isDSHOT = false }, + [PWM_TYPE_ONESHOT125] = { .usesHwTimer = true, .isDSHOT = false }, + [PWM_TYPE_MULTISHOT] = { .usesHwTimer = true, .isDSHOT = false }, + [PWM_TYPE_BRUSHED] = { .usesHwTimer = true, .isDSHOT = false }, + [PWM_TYPE_DSHOT150] = { .usesHwTimer = true, .isDSHOT = true }, + [PWM_TYPE_DSHOT300] = { .usesHwTimer = true, .isDSHOT = true }, + [PWM_TYPE_DSHOT600] = { .usesHwTimer = true, .isDSHOT = true }, }; pwmInitError_e getPwmInitError(void) diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 7efbf39431..51ec456a77 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -39,14 +39,11 @@ typedef enum { PWM_TYPE_STANDARD = 0, PWM_TYPE_ONESHOT125, - PWM_TYPE_ONESHOT42, PWM_TYPE_MULTISHOT, PWM_TYPE_BRUSHED, PWM_TYPE_DSHOT150, PWM_TYPE_DSHOT300, PWM_TYPE_DSHOT600, - PWM_TYPE_DSHOT1200, - PWM_TYPE_SERIALSHOT, } motorPwmProtocolTypes_e; typedef enum { @@ -73,7 +70,6 @@ typedef struct rangefinderIOConfig_s { typedef struct { bool usesHwTimer; bool isDSHOT; - bool isSerialShot; } motorProtocolProperties_t; bool pwmMotorAndServoInit(void); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 20429e07cb..37f0bda43f 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -37,7 +37,6 @@ FILE_COMPILE_FOR_SPEED #include "drivers/io_pca9685.h" #include "io/pwmdriver_i2c.h" -#include "io/esc_serialshot.h" #include "io/servo_sbus.h" #include "sensors/esc_sensor.h" @@ -50,7 +49,6 @@ FILE_COMPILE_FOR_SPEED #define MULTISHOT_20US_MULT (MULTISHOT_TIMER_HZ * 20 / 1000000.0f / 1000.0f) #ifdef USE_DSHOT -#define MOTOR_DSHOT1200_HZ 24000000 #define MOTOR_DSHOT600_HZ 12000000 #define MOTOR_DSHOT300_HZ 6000000 #define MOTOR_DSHOT150_HZ 3000000 @@ -100,7 +98,7 @@ static pwmWriteFuncPtr motorWritePtr = NULL; // Function to write val static pwmOutputPort_t * servos[MAX_SERVOS]; static pwmWriteFuncPtr servoWritePtr = NULL; // Function to write value to motors -#if defined(USE_DSHOT) || defined(USE_SERIALSHOT) +#if defined(USE_DSHOT) static timeUs_t digitalMotorUpdateIntervalUs = 0; static timeUs_t digitalMotorLastUpdateUs; #endif @@ -245,8 +243,6 @@ static pwmOutputPort_t * motorConfigPwm(const timerHardware_t *timerHardware, fl uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType) { switch (pwmProtocolType) { - case(PWM_TYPE_DSHOT1200): - return MOTOR_DSHOT1200_HZ; case(PWM_TYPE_DSHOT600): return MOTOR_DSHOT600_HZ; case(PWM_TYPE_DSHOT300): @@ -304,7 +300,7 @@ static uint16_t prepareDshotPacket(const uint16_t value, bool requestTelemetry) } #endif -#if defined(USE_DSHOT) || defined(USE_SERIALSHOT) +#if defined(USE_DSHOT) static void motorConfigDigitalUpdateInterval(uint16_t motorPwmRateHz) { digitalMotorUpdateIntervalUs = 1000000 / motorPwmRateHz; @@ -325,14 +321,9 @@ bool isMotorProtocolDshot(void) return getMotorProtocolProperties(initMotorProtocol)->isDSHOT; } -bool isMotorProtocolSerialShot(void) -{ - return getMotorProtocolProperties(initMotorProtocol)->isSerialShot; -} - bool isMotorProtocolDigital(void) { - return isMotorProtocolDshot() || isMotorProtocolSerialShot(); + return isMotorProtocolDshot(); } void pwmRequestMotorTelemetry(int motorIndex) @@ -441,16 +432,6 @@ void pwmCompleteMotorUpdate(void) { } } #endif - -#ifdef USE_SERIALSHOT - if (isMotorProtocolSerialShot()) { - for (int index = 0; index < motorCount; index++) { - serialshotUpdateMotor(index, motors[index].value); - } - - serialshotSendUpdate(); - } -#endif } #else // digital motor protocol @@ -481,13 +462,11 @@ void pwmMotorPreconfigure(void) case PWM_TYPE_STANDARD: case PWM_TYPE_BRUSHED: case PWM_TYPE_ONESHOT125: - case PWM_TYPE_ONESHOT42: case PWM_TYPE_MULTISHOT: motorWritePtr = pwmWriteStandard; break; #ifdef USE_DSHOT - case PWM_TYPE_DSHOT1200: case PWM_TYPE_DSHOT600: case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT150: @@ -495,15 +474,6 @@ void pwmMotorPreconfigure(void) motorWritePtr = pwmWriteDigital; break; #endif - -#ifdef USE_SERIALSHOT - case PWM_TYPE_SERIALSHOT: - // Kick off SerialShot driver initalization - serialshotInitialize(); - motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate); - motorWritePtr = pwmWriteDigital; - break; -#endif } } @@ -518,16 +488,11 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bo motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput); break; - case PWM_TYPE_ONESHOT42: - motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 42e-6f, 42e-6f, motorConfig()->motorPwmRate, enableOutput); - break; - case PWM_TYPE_MULTISHOT: motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorConfig()->motorPwmRate, enableOutput); break; #ifdef USE_DSHOT - case PWM_TYPE_DSHOT1200: case PWM_TYPE_DSHOT600: case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT150: diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 1fbafc3165..2bea10ec0f 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -265,9 +265,6 @@ void validateAndFixConfig(void) case PWM_TYPE_ONESHOT125: // Limited to 3900 Hz motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 3900); break; - case PWM_TYPE_ONESHOT42: // 2-8 kHz - motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 8000); - break; case PWM_TYPE_MULTISHOT: // 2-16 kHz motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 16000); break; @@ -287,14 +284,6 @@ void validateAndFixConfig(void) case PWM_TYPE_DSHOT600: motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000); break; - case PWM_TYPE_DSHOT1200: - motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 32000); - break; -#endif -#ifdef USE_SERIALSHOT - case PWM_TYPE_SERIALSHOT: // 2-4 kHz - motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 4000); - break; #endif } #endif diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e8647223e0..1e254edd13 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -35,7 +35,7 @@ tables: - name: blackbox_device values: ["SERIAL", "SPIFLASH", "SDCARD"] - name: motor_pwm_protocol - values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "SERIALSHOT"] + values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"] - name: servo_protocol values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"] - name: failsafe_procedure diff --git a/src/main/io/esc_serialshot.c b/src/main/io/esc_serialshot.c deleted file mode 100644 index 29fe5d5232..0000000000 --- a/src/main/io/esc_serialshot.c +++ /dev/null @@ -1,116 +0,0 @@ -/* - * 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 - -#include "platform.h" - -#include "build/build_config.h" -#include "build/debug.h" - -#include "common/maths.h" -#include "common/crc.h" - -#include "io/serial.h" -#include "io/esc_serialshot.h" - -#if defined(USE_SERIALSHOT) - -#define SERIALSHOT_UART_BAUD 921600 -#define SERIALSHOT_PKT_DEFAULT_HEADER (0x00) // Default header (motors 1-4, regular 4-in-1 ESC) - - -typedef struct __attribute__((packed)) { - uint8_t hdr; // Header/version marker - uint8_t motorData[6]; // 12 bit per motor - uint8_t crc; // CRC8/DVB-T of hdr & motorData -} serialShortPacket_t; - - -static serialShortPacket_t txPkt; -static uint16_t motorValues[4]; -static serialPort_t * escPort = NULL; -static serialPortConfig_t * portConfig; - -bool serialshotInitialize(void) -{ - // Avoid double initialization - if (escPort) { - return true; - } - - portConfig = findSerialPortConfig(FUNCTION_ESCSERIAL); - if (!portConfig) { - return false; - } - - escPort = openSerialPort(portConfig->identifier, FUNCTION_ESCSERIAL, NULL, NULL, SERIALSHOT_UART_BAUD, MODE_RXTX, SERIAL_NOT_INVERTED | SERIAL_UNIDIR); - if (!escPort) { - return false; - } - - return true; -} - -void serialshotUpdateMotor(int index, uint16_t value) -{ - if (index < 0 || index > 3) { - return; - } - - motorValues[index] = value; -} - -void serialshotSendUpdate(void) -{ - // Check if the port is initialized - if (!escPort) { - return; - } - - // Skip update if previous one is not yet fully sent - // This helps to avoid buffer overflow and evenyually the data corruption - if (!isSerialTransmitBufferEmpty(escPort)) { - return; - } - - txPkt.hdr = SERIALSHOT_PKT_DEFAULT_HEADER; - - txPkt.motorData[0] = motorValues[0] & 0x00FF; - txPkt.motorData[1] = motorValues[1] & 0x00FF; - txPkt.motorData[2] = motorValues[2] & 0x00FF; - txPkt.motorData[3] = motorValues[3] & 0x00FF; - txPkt.motorData[4] = (((motorValues[0] & 0xF00) >> 8) << 0) | (((motorValues[1] & 0xF00) >> 8) << 4); - txPkt.motorData[5] = (((motorValues[2] & 0xF00) >> 8) << 0) | (((motorValues[3] & 0xF00) >> 8) << 4); - - txPkt.crc = crc8_dvb_s2(0x00, txPkt.hdr); - txPkt.crc = crc8_dvb_s2_update(txPkt.crc, txPkt.motorData, sizeof(txPkt.motorData)); - - serialWriteBuf(escPort, (const uint8_t *)&txPkt, sizeof(txPkt)); -} - -#endif diff --git a/src/main/io/esc_serialshot.h b/src/main/io/esc_serialshot.h deleted file mode 100644 index c915cc9f4f..0000000000 --- a/src/main/io/esc_serialshot.h +++ /dev/null @@ -1,29 +0,0 @@ -/* - * 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 - -bool serialshotInitialize(void); -void serialshotUpdateMotor(int index, uint16_t value); -void serialshotSendUpdate(void); diff --git a/src/main/target/BETAFPVF722/target.h b/src/main/target/BETAFPVF722/target.h index 4342800797..85c709edab 100755 --- a/src/main/target/BETAFPVF722/target.h +++ b/src/main/target/BETAFPVF722/target.h @@ -163,4 +163,3 @@ // ESC-related features #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT diff --git a/src/main/target/DALRCF722DUAL/target.h b/src/main/target/DALRCF722DUAL/target.h index 2ff18eeccb..ad863e2e0a 100644 --- a/src/main/target/DALRCF722DUAL/target.h +++ b/src/main/target/DALRCF722DUAL/target.h @@ -138,7 +138,6 @@ #define MAX_PWM_OUTPUT_PORTS 6 #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h index f949cbf4f6..22229390b0 100644 --- a/src/main/target/FLYWOOF411/target.h +++ b/src/main/target/FLYWOOF411/target.h @@ -165,7 +165,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FRSKY_ROVERF7/target.h b/src/main/target/FRSKY_ROVERF7/target.h index f729d2bd60..ef6334ca60 100755 --- a/src/main/target/FRSKY_ROVERF7/target.h +++ b/src/main/target/FRSKY_ROVERF7/target.h @@ -150,4 +150,3 @@ #define MAX_PWM_OUTPUT_PORTS 5 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h index a2453b1e61..456c68cb2e 100644 --- a/src/main/target/HGLRCF722/target.h +++ b/src/main/target/HGLRCF722/target.h @@ -175,6 +175,5 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/KAKUTEF4/target.h b/src/main/target/KAKUTEF4/target.h index 28e94d1e7f..7c3843b047 100755 --- a/src/main/target/KAKUTEF4/target.h +++ b/src/main/target/KAKUTEF4/target.h @@ -171,7 +171,6 @@ #define TARGET_IO_PORTD (BIT(2)) #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR #ifdef KAKUTEF4V2 diff --git a/src/main/target/KAKUTEF7MINIV3/target.h b/src/main/target/KAKUTEF7MINIV3/target.h index 6e7188f9f7..8914f81af1 100644 --- a/src/main/target/KAKUTEF7MINIV3/target.h +++ b/src/main/target/KAKUTEF7MINIV3/target.h @@ -160,7 +160,6 @@ #define MAX_PWM_OUTPUT_PORTS 6 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define USE_RANGEFINDER #define RANGEFINDER_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MAMBAF405US/target.h b/src/main/target/MAMBAF405US/target.h index ae1eb7bb33..d0cbc97389 100644 --- a/src/main/target/MAMBAF405US/target.h +++ b/src/main/target/MAMBAF405US/target.h @@ -191,7 +191,6 @@ // ESC-related features #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/MAMBAF722/target.h b/src/main/target/MAMBAF722/target.h index 3efdde2835..5f4b9035ae 100644 --- a/src/main/target/MAMBAF722/target.h +++ b/src/main/target/MAMBAF722/target.h @@ -193,7 +193,6 @@ // ESC-related features #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR #define USE_SERIAL_4WAY_BLHELI_INTERFACE diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index c3dd007b4d..1f14337212 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -199,7 +199,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define MAX_PWM_OUTPUT_PORTS 6 diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index b73c6013c7..124dcbd0a2 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -160,7 +160,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 8bb3e933ef..0cb067d99e 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -163,7 +163,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define USE_SERIAL_4WAY_BLHELI_INTERFACE #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index b1b657e424..47f0d3508c 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -157,6 +157,5 @@ #define MAX_PWM_OUTPUT_PORTS 7 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define BNO055_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index 83d7d669cb..8edf1e7755 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -170,5 +170,4 @@ #define MAX_PWM_OUTPUT_PORTS 10 #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 6f62d53406..e55e379131 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -191,7 +191,6 @@ #define MAX_PWM_OUTPUT_PORTS 8 #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR #define BNO055_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index 593cab78a4..ea3414f2c6 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -229,4 +229,3 @@ #define MAX_PWM_OUTPUT_PORTS 16 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT diff --git a/src/main/target/MATEKH743/target.h b/src/main/target/MATEKH743/target.h index 84449f9f33..126ce22d18 100644 --- a/src/main/target/MATEKH743/target.h +++ b/src/main/target/MATEKH743/target.h @@ -205,5 +205,4 @@ #define MAX_PWM_OUTPUT_PORTS 15 #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT diff --git a/src/main/target/OMNIBUSF7NXT/target.h b/src/main/target/OMNIBUSF7NXT/target.h index de7da72927..4396302717 100644 --- a/src/main/target/OMNIBUSF7NXT/target.h +++ b/src/main/target/OMNIBUSF7NXT/target.h @@ -169,7 +169,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT // Number of available PWM outputs #define MAX_PWM_OUTPUT_PORTS 6 diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index f8a3c7264c..4f4befce66 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -31,7 +31,6 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT // MPU6000 interrupts #define USE_EXTI diff --git a/src/main/target/RUSH_BLADE_F7/target.h b/src/main/target/RUSH_BLADE_F7/target.h index 1a701ed987..fb9c522642 100644 --- a/src/main/target/RUSH_BLADE_F7/target.h +++ b/src/main/target/RUSH_BLADE_F7/target.h @@ -142,5 +142,4 @@ #define MAX_PWM_OUTPUT_PORTS 10 #define USE_DSHOT -#define USE_SERIALSHOT #define USE_ESC_SENSOR diff --git a/src/main/target/SKYSTARSF405HD/target.h b/src/main/target/SKYSTARSF405HD/target.h index d6c562aa0b..a23dc48e89 100644 --- a/src/main/target/SKYSTARSF405HD/target.h +++ b/src/main/target/SKYSTARSF405HD/target.h @@ -161,6 +161,5 @@ #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT #define MAX_PWM_OUTPUT_PORTS 4 diff --git a/src/main/target/ZEEZF7/target.h b/src/main/target/ZEEZF7/target.h index 5ad4f85e6e..c01f4ede4d 100755 --- a/src/main/target/ZEEZF7/target.h +++ b/src/main/target/ZEEZF7/target.h @@ -231,4 +231,3 @@ #endif #define USE_DSHOT #define USE_ESC_SENSOR -#define USE_SERIALSHOT