From 9e7dcaa64e85081e7db7603b337f090d1deda2f9 Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 24 Jan 2024 19:02:38 +0100 Subject: [PATCH 1/2] Initial submission. * [x] Msp messages * [ ] Use table info in msp_vtx.{c,h} --- src/main/CMakeLists.txt | 2 + src/main/config/parameter_group_ids.h | 3 +- src/main/fc/fc_msp.c | 131 ++++++++++++++++++++ src/main/io/vtx_msp.c | 12 +- src/main/io/vtx_msp.h | 15 +-- src/main/io/vtx_table.c | 164 ++++++++++++++++++++++++++ src/main/io/vtx_table.h | 93 +++++++++++++++ src/main/msp/msp_protocol.h | 3 + src/main/target/common.h | 1 + 9 files changed, 404 insertions(+), 20 deletions(-) create mode 100644 src/main/io/vtx_table.c create mode 100644 src/main/io/vtx_table.h diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index db4b1f57d1b..a6eaed06baa 100755 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -543,6 +543,8 @@ main_sources(COMMON_SRC io/vtx_control.h io/vtx_msp.c io/vtx_msp.h + io/vtx_table.c + io/vtx_table.h navigation/navigation.c navigation/navigation.h diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index eb5a07ddfb3..9e1e53f1f3f 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -123,7 +123,8 @@ #define PG_EZ_TUNE 1033 #define PG_LEDPIN_CONFIG 1034 #define PG_OSD_JOYSTICK_CONFIG 1035 -#define PG_INAV_END PG_OSD_JOYSTICK_CONFIG +#define PG_VTX_TABLE_CONFIG 1036 +#define PG_INAV_END PG_VTX_TABLE_CONFIG // OSD configuration (subject to change) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index be4d621549c..ddb82f58339 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -94,6 +94,7 @@ #include "io/serial_4way.h" #include "io/vtx.h" #include "io/vtx_string.h" +#include "io/vtx_table.h" #include "io/gps_private.h" //for MSP_SIMULATOR #include "msp/msp.h" @@ -1466,6 +1467,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF #endif break; + case MSP_NAME: { const char *name = systemConfig()->craftName; @@ -2617,6 +2619,81 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif +#ifdef USE_VTX_TABLE + case MSP_SET_VTXTABLE_BAND: + { + char bandName[VTX_TABLE_BAND_NAME_LENGTH + 1]; + memset(bandName, 0, VTX_TABLE_BAND_NAME_LENGTH + 1); + uint16_t frequencies[VTX_TABLE_MAX_CHANNELS]; + const uint8_t band = sbufReadU8(src); + const uint8_t bandNameLength = sbufReadU8(src); + for (int i = 0; i < bandNameLength; i++) { + const char nameChar = sbufReadU8(src); + if (i < VTX_TABLE_BAND_NAME_LENGTH) { + bandName[i] = toupper(nameChar); + } + } + const char bandLetter = toupper(sbufReadU8(src)); + const bool isFactoryBand = (bool)sbufReadU8(src); + const uint8_t channelCount = sbufReadU8(src); + for (int i = 0; i < channelCount; i++) { + const uint16_t frequency = sbufReadU16(src); + if (i < vtxTableConfig()->channels) { + frequencies[i] = frequency; + } + } + + if (band > 0 && band <= vtxTableConfig()->bands) { + vtxTableStrncpyWithPad(vtxTableConfigMutable()->bandNames[band - 1], bandName, VTX_TABLE_BAND_NAME_LENGTH); + vtxTableConfigMutable()->bandLetters[band - 1] = bandLetter; + vtxTableConfigMutable()->isFactoryBand[band - 1] = isFactoryBand; + for (int i = 0; i < vtxTableConfig()->channels; i++) { + vtxTableConfigMutable()->frequency[band - 1][i] = frequencies[i]; + } + // If this is the currently selected band then reset the frequency + if (band == vtxSettingsConfig()->band) { + uint16_t newChannel = 0; + if (vtxSettingsConfig()->channel > 0 && vtxSettingsConfig()->channel <= vtxTableConfig()->channels) { + newChannel = vtxSettingsConfig()->channel; + } + vtxSettingsConfigMutable()->channel = newChannel; + vtxCommonSetBandAndChannel(vtxCommonDevice(), band, newChannel); + } + //vtxTableNeedsInit = true; // reinintialize vtxtable after eeprom write + } else { + return MSP_RESULT_ERROR; + } + //setMspVtxDeviceStatusReady(srcDesc); + } + break; + + case MSP_SET_VTXTABLE_POWERLEVEL: + { + char powerLevelLabel[VTX_TABLE_POWER_LABEL_LENGTH + 1]; + memset(powerLevelLabel, 0, VTX_TABLE_POWER_LABEL_LENGTH + 1); + const uint8_t powerLevel = sbufReadU8(src); + const uint16_t powerValue = sbufReadU16(src); + const uint8_t powerLevelLabelLength = sbufReadU8(src); + for (int i = 0; i < powerLevelLabelLength; i++) { + const char labelChar = sbufReadU8(src); + if (i < VTX_TABLE_POWER_LABEL_LENGTH) { + powerLevelLabel[i] = toupper(labelChar); + } + } + + if (powerLevel > 0 && powerLevel <= vtxTableConfig()->powerLevels) { + vtxTableConfigMutable()->powerValues[powerLevel - 1] = powerValue; + vtxTableStrncpyWithPad(vtxTableConfigMutable()->powerLabels[powerLevel - 1], powerLevelLabel, VTX_TABLE_POWER_LABEL_LENGTH); + //vtxTableNeedsInit = true; // reinintialize vtxtable after eeprom write + vtxCommonSetPowerByIndex(vtxCommonDevice(), powerLevel - 1); + } else { + return MSP_RESULT_ERROR; + } + //setMspVtxDeviceStatusReady(srcDesc); + } + break; +#endif + #ifdef USE_FLASHFS case MSP_DATAFLASH_ERASE: flashfsEraseCompletely(); @@ -3857,6 +3934,60 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu } break; #endif + +#ifdef USE_VTX_TABLE + case MSP_VTXTABLE_BAND: + { + const uint8_t band = sbufBytesRemaining(src) ? sbufReadU8(src) : 0; + if (band > 0 && band <= VTX_TABLE_MAX_BANDS) { + sbufWriteU8(dst, band); // band number (same as request) + sbufWriteU8(dst, + VTX_TABLE_BAND_NAME_LENGTH); // band name length + for (int i = 0; i < VTX_TABLE_BAND_NAME_LENGTH; + i++) { // band name bytes + sbufWriteU8(dst, vtxTableConfig()->bandNames[band - 1][i]); + } + sbufWriteU8( + dst, + vtxTableConfig()->bandLetters[band - 1]); // band letter + sbufWriteU8( + dst, + vtxTableConfig() + ->isFactoryBand[band - 1]); // CUSTOM = 0; FACTORY = 1 + sbufWriteU8( + dst, + vtxTableConfig() + ->channels); // number of channel frequencies to follow + for (int i = 0; i < vtxTableConfig()->channels; + i++) { // the frequency for each channel + sbufWriteU16(dst, vtxTableConfig()->frequency[band - 1][i]); + } + *ret = MSP_RESULT_ACK; + } else { + *ret = MSP_RESULT_ERROR; + } + //setMspVtxDeviceStatusReady(srcDesc); + } + break; + case MSP_VTXTABLE_POWERLEVEL: + { + const uint8_t powerLevel = sbufBytesRemaining(src) ? sbufReadU8(src) : 0; + if (powerLevel > 0 && powerLevel <= VTX_TABLE_MAX_POWER_LEVELS) { + sbufWriteU8(dst, powerLevel); // powerLevel number (same as request) + sbufWriteU16(dst, vtxTableConfig()->powerValues[powerLevel - 1]); + sbufWriteU8(dst, VTX_TABLE_POWER_LABEL_LENGTH); // powerLevel label length + for (int i = 0; i < VTX_TABLE_POWER_LABEL_LENGTH; i++) { // powerlevel label bytes + sbufWriteU8(dst, vtxTableConfig()->powerLabels[powerLevel - 1][i]); + } + *ret = MSP_RESULT_ACK; + } else { + *ret = MSP_RESULT_ERROR; + } + //setMspVtxDeviceStatusReady(srcDesc); + } + break; +#endif + default: // Not handled diff --git a/src/main/io/vtx_msp.c b/src/main/io/vtx_msp.c index 696918e5705..d0036918572 100644 --- a/src/main/io/vtx_msp.c +++ b/src/main/io/vtx_msp.c @@ -78,15 +78,15 @@ static bool prevLowPowerDisarmedState = false; static const vtxVTable_t mspVTable; // forward static vtxDevice_t vtxMsp = { .vTable = &mspVTable, - .capability.bandCount = VTX_MSP_TABLE_MAX_BANDS, - .capability.channelCount = VTX_MSP_TABLE_MAX_CHANNELS, - .capability.powerCount = VTX_MSP_TABLE_MAX_POWER_LEVELS, + .capability.bandCount = VTX_TABLE_MAX_BANDS, + .capability.channelCount = VTX_TABLE_MAX_CHANNELS, + .capability.powerCount = VTX_TABLE_MAX_POWER_LEVELS, .capability.bandNames = (char **)vtx58BandNames, .capability.channelNames = (char **)vtx58ChannelNames, .capability.powerNames = (char**)saPowerNames - }; + STATIC_UNIT_TESTED mspVtxStatus_e mspVtxStatus = MSP_VTX_STATUS_OFFLINE; static uint8_t mspVtxPortIdentifier = 255; @@ -328,7 +328,7 @@ static void vtxMspSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index) LOG_DEBUG(VTX, "msp SetPowerByIndex\r\n"); UNUSED(vtxDevice); - if (index > 0 && (index < VTX_MSP_TABLE_MAX_POWER_LEVELS)) + if (index > 0 && (index < VTX_TABLE_MAX_POWER_LEVELS)) { if (index != mspConfPowerIndex) { @@ -386,7 +386,7 @@ static bool vtxMspGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex) uint8_t power = isLowPowerDisarmed() ? 1 : vtxSettingsConfig()->power; // Special case, power not set - if (power > VTX_MSP_TABLE_MAX_POWER_LEVELS) { + if (power > VTX_TABLE_MAX_POWER_LEVELS) { *pIndex = 0; //LOG_DEBUG(VTX, "msp GetPowerIndex: %u\r\n", *pIndex); return true; diff --git a/src/main/io/vtx_msp.h b/src/main/io/vtx_msp.h index 30ca245fed3..5703e6583b7 100644 --- a/src/main/io/vtx_msp.h +++ b/src/main/io/vtx_msp.h @@ -27,25 +27,14 @@ #include "msp/msp_protocol.h" #include "msp/msp_serial.h" +#include "io/vtx_table.h" + typedef enum { // Offline - device hasn't responded yet MSP_VTX_STATUS_OFFLINE = 0, MSP_VTX_STATUS_READY, } mspVtxStatus_e; -typedef struct mspPowerTable_s { - int mW; // rfpower - int16_t dbi; // valueV1 -} mspPowerTable_t; - -#define VTX_MSP_TABLE_MAX_BANDS 5 // default freq table has 5 bands -#define VTX_MSP_TABLE_MAX_CHANNELS 8 // and eight channels -#define VTX_MSP_TABLE_MAX_POWER_LEVELS 5 //max of VTX_TRAMP_POWER_COUNT, VTX_SMARTAUDIO_POWER_COUNT and VTX_RTC6705_POWER_COUNT -#define VTX_MSP_TABLE_CHANNEL_NAME_LENGTH 1 -#define VTX_MSP_TABLE_BAND_NAME_LENGTH 8 -#define VTX_MSP_TABLE_POWER_LABEL_LENGTH 3 - - bool vtxMspInit(void); void setMspVtxDeviceStatusReady(const int descriptor); void prepareMspFrame(uint8_t *mspFrame); diff --git a/src/main/io/vtx_table.c b/src/main/io/vtx_table.c new file mode 100644 index 00000000000..7f34f9cd65f --- /dev/null +++ b/src/main/io/vtx_table.c @@ -0,0 +1,164 @@ +/* + * This file is part of INAV + * + * INAV 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. + * + * INAV is 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 "build/debug.h" + +#include "common/printf.h" + +#include "io/vtx_table.h" + +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" + +#ifdef USE_VTX_TABLE + +// vtxtable band 1 BOSCAM_A A FACTORY 5865 5845 5825 5805 5785 5765 5745 5725 +// vtxtable band 2 BOSCAM_B B FACTORY 5733 5752 5771 5790 5809 5828 5847 5866 +// vtxtable band 3 BOSCAM_E E FACTORY 5705 5685 5665 5645 5885 5905 5925 5945 +// vtxtable band 4 FATSHARK F FACTORY 5740 5760 5780 5800 5820 5840 5860 5880 +// vtxtable band 5 RACEBAND R FACTORY 5658 5695 5732 5769 5806 5843 5880 5917 +// vtxtable band 6 LOWBAND L FACTORY 5333 5373 5413 5453 5493 5533 5573 5613 + +uint8_t mspConfMaxBands = VTX_TABLE_MAX_BANDS; +uint8_t mspConfMaxPowerLevels = VTX_TABLE_MAX_POWER_LEVELS; +/* +mspBandTable_t bandTable[VTX_TABLE_MAX_BANDS] = { + { "BOSCAM_A", "A", true, { 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725 } }, + { "BOSCAM_B", "B", true, { 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866 } }, + { "BOSCAM_E", "C", true, { 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945 } }, + { "FATSHARK", "F", true, { 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880 } }, + { "RACEBAND", "R", true, { 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917 } }, + { "LOWBAND ", "L", true, { 5333, 5373, 5413, 5453, 5493, 5533, 5573, 5613 } }, +}; + +mspPowerTable_t powerTable[VTX_MSP_TABLE_MAX_POWER_LEVELS] = { + { "0", 0 }, + { "1", 1 }, + { "2", 2 }, + { "3", 3 }, + { "4", 4 }, +}; +*/ + +PG_REGISTER_WITH_RESET_FN(vtxTableConfig_t, vtxTableConfig, PG_VTX_TABLE_CONFIG, 0); + +// Prune a band to "channels" +void vtxTableConfigClearChannels(vtxTableConfig_t *config, int band, int channels) +{ + for (int channel = channels; channel < VTX_TABLE_MAX_CHANNELS; channel++) { + config->frequency[band][channel] = 0; + } +} + +// Clear a channel name for "channel" +void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel) +{ + tfp_sprintf(config->channelNames[channel], "%d", channel + 1); +} + +void vtxTableConfigClearBand(vtxTableConfig_t *config, int band) +{ + vtxTableConfigClearChannels(config, band, 0); + for (int channel = 0; channel < VTX_TABLE_MAX_CHANNELS; channel++) { + vtxTableConfigClearChannelNames(config, channel); + } + char tempbuf[6]; + tfp_sprintf(tempbuf, "BAND%d", band + 1); + vtxTableStrncpyWithPad(config->bandNames[band], tempbuf, VTX_TABLE_BAND_NAME_LENGTH); + config->bandLetters[band] = '1' + band; + config->isFactoryBand[band] = false; +} + +void vtxTableConfigClearPowerValues(vtxTableConfig_t *config, int start) +{ + for (int i = start; i < VTX_TABLE_MAX_POWER_LEVELS; i++) { + config->powerValues[i] = 0; + } +} + +void vtxTableConfigClearPowerLabels(vtxTableConfig_t *config, int start) +{ + for (int i = start; i < VTX_TABLE_MAX_POWER_LEVELS; i++) { + char tempbuf[4]; + tfp_sprintf(tempbuf, "LV%d", i); + vtxTableStrncpyWithPad(config->powerLabels[i], tempbuf, VTX_TABLE_POWER_LABEL_LENGTH); + } +} + +void pgResetFn_vtxTableConfig(vtxTableConfig_t *config) +{ + // Clear band names, letters and frequency values + + config->bands = 0; + config->channels = 0; + + for (int band = 0; band < VTX_TABLE_MAX_BANDS; band++) { + vtxTableConfigClearBand(config, band); + } + + // Clear power values and labels + + config->powerLevels = 0; + vtxTableConfigClearPowerValues(config, 0); + vtxTableConfigClearPowerLabels(config, 0); +} + +void vtxTableStrncpyWithPad(char *dst, const char *src, int length) +{ + char c; + + while (length && (c = *src++)) { + *dst++ = c; + length--; + } + + while (length--) { + *dst++ = ' '; + } + + *dst = 0; +} + + +uint8_t vtxTableGetMaxBands(void) +{ + return mspConfMaxBands; +} + +uint8_t vtxTableGetMaxPowerLevels(void) +{ + return mspConfMaxPowerLevels; +} + +void vtxTableSetMaxBands(uint8_t bands) +{ + mspConfMaxBands = bands; +} + +void vtxTableSetMaxPowerLevels(uint8_t powerLevels) +{ + mspConfMaxPowerLevels = powerLevels; +} + + + +#endif \ No newline at end of file diff --git a/src/main/io/vtx_table.h b/src/main/io/vtx_table.h new file mode 100644 index 00000000000..9769c890ed2 --- /dev/null +++ b/src/main/io/vtx_table.h @@ -0,0 +1,93 @@ +/* + * This file is part of INAV + * + * INAV 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. + * + * INAV is 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 + + +#include + +#include "platform.h" + +//#include "cms/cms_menu_vtx_msp.h" +#include "common/crc.h" +#include "common/log.h" +#include "config/feature.h" + +//#include "drivers/vtx_common.h" +//#include "drivers/vtx_table.h" + +#include "fc/runtime_config.h" + + +#include "build/build_config.h" + +#include "msp/msp_protocol.h" +#include "msp/msp_serial.h" + + +#ifdef USE_VTX_TABLE + +#define VTX_TABLE_MAX_BANDS 6 // default freq table has 5 bands +#define VTX_TABLE_MAX_CHANNELS 8 // and eight channels +#define VTX_TABLE_MAX_POWER_LEVELS 5 //max of VTX_TRAMP_POWER_COUNT, VTX_SMARTAUDIO_POWER_COUNT and VTX_RTC6705_POWER_COUNT +#define VTX_TABLE_CHANNEL_NAME_LENGTH 1 +#define VTX_TABLE_BAND_NAME_LENGTH 8 +#define VTX_TABLE_POWER_LABEL_LENGTH 3 + +#define VTX_BAND_UNUSED 0 +#define VTX_POWER_UNUSED 0 + +typedef struct vtxTableConfig_s { + uint8_t bands; + uint8_t channels; + uint16_t frequency[VTX_TABLE_MAX_BANDS][VTX_TABLE_MAX_CHANNELS]; + char bandNames[VTX_TABLE_MAX_BANDS][VTX_TABLE_BAND_NAME_LENGTH + 1]; + char bandLetters[VTX_TABLE_MAX_BANDS]; + char channelNames[VTX_TABLE_MAX_CHANNELS][VTX_TABLE_CHANNEL_NAME_LENGTH + 1]; + bool isFactoryBand[VTX_TABLE_MAX_BANDS]; + + uint8_t powerLevels; + uint16_t powerValues[VTX_TABLE_MAX_POWER_LEVELS]; + char powerLabels[VTX_TABLE_MAX_POWER_LEVELS][VTX_TABLE_POWER_LABEL_LENGTH + 1]; +} vtxTableConfig_t; + +struct vtxTableConfig_s; +PG_DECLARE(struct vtxTableConfig_s, vtxTableConfig); + +extern uint8_t mspConfMaxBands; +extern uint8_t mspConfMaxPowerLevels; + +uint8_t vtxTableGetMaxBands(void); +uint8_t vtxTableGetMaxPowerLevels(void); + +void vtxTableSetMaxBands(uint8_t bands); +void vtxTableSetMaxPowerLevels(uint8_t powersLevels); + +void vtxTableConfigClearChannels(vtxTableConfig_t *config, int band, int channels); +void vtxTableConfigClearChannelNames(vtxTableConfig_t *config, int channel); +void vtxTableConfigClearBand(vtxTableConfig_t *config, int band); +void vtxTableConfigClearPowerValues(vtxTableConfig_t *config, int start); +void vtxTableConfigClearPowerLabels(vtxTableConfig_t *config, int start); +void vtxTableStrncpyWithPad(char *dst, const char *src, int length); + + +void pgResetFn_vtxTableConfig(vtxTableConfig_t *config); + +#endif \ No newline at end of file diff --git a/src/main/msp/msp_protocol.h b/src/main/msp/msp_protocol.h index b44037f2f88..0d7ba599ebf 100644 --- a/src/main/msp/msp_protocol.h +++ b/src/main/msp/msp_protocol.h @@ -282,6 +282,9 @@ #define MSP_SET_SENSOR_ALIGNMENT 220 //in message set the orientation of the acc,gyro,mag #define MSP_SET_LED_STRIP_MODECOLOR 221 //in message Set LED strip mode_color settings +#define MSP_SET_VTXTABLE_BAND 227 //in message set vtxTable band/channel data (one band at a time) +#define MSP_SET_VTXTABLE_POWERLEVEL 228 //in message set vtxTable powerLevel data (one powerLevel at a time) + // #define MSP_BIND 240 //in message no param // #define MSP_ALARMS 242 diff --git a/src/main/target/common.h b/src/main/target/common.h index f01b596bdac..7cc86f3cea2 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -168,6 +168,7 @@ #define USE_VTX_SMARTAUDIO #define USE_VTX_TRAMP #define USE_VTX_MSP +#define USE_VTX_TABLE #define USE_PROGRAMMING_FRAMEWORK #define USE_CLI_BATCH From 3c47a4008216bbe20d85cd76dc46ad2ed132dbeb Mon Sep 17 00:00:00 2001 From: Marcelo Bezerra <23555060+mmosca@users.noreply.github.com> Date: Wed, 24 Jan 2024 19:07:07 +0100 Subject: [PATCH 2/2] update file headers --- src/main/io/vtx_table.c | 2 +- src/main/io/vtx_table.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/vtx_table.c b/src/main/io/vtx_table.c index 7f34f9cd65f..649f42aad56 100644 --- a/src/main/io/vtx_table.c +++ b/src/main/io/vtx_table.c @@ -1,5 +1,5 @@ /* - * This file is part of INAV + * This file is part of BetaFlight and INAV * * INAV is free software. You can redistribute * this software and/or modify this software under the terms of the diff --git a/src/main/io/vtx_table.h b/src/main/io/vtx_table.h index 9769c890ed2..b734c3e3814 100644 --- a/src/main/io/vtx_table.h +++ b/src/main/io/vtx_table.h @@ -1,5 +1,5 @@ /* - * This file is part of INAV + * This file is part of BetaFlight and INAV * * INAV is free software. You can redistribute * this software and/or modify this software under the terms of the