mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
[VTX] Revert "Fix VTX low power disarm ..." in preparation for #8939
This reverts commit 0bd808d1dc
.
This commit is contained in:
parent
e4aafa0ab5
commit
f9be9d85f4
2 changed files with 2 additions and 28 deletions
|
@ -49,8 +49,6 @@
|
||||||
#define VTX_TABLE_DEFAULT_CHANNEL 1
|
#define VTX_TABLE_DEFAULT_CHANNEL 1
|
||||||
#define VTX_TABLE_DEFAULT_FREQ 5740
|
#define VTX_TABLE_DEFAULT_FREQ 5740
|
||||||
#define VTX_TABLE_DEFAULT_PITMODE_FREQ 0
|
#define VTX_TABLE_DEFAULT_PITMODE_FREQ 0
|
||||||
#define VTX_TABLE_LOW_POWER_INDEX 1
|
|
||||||
|
|
||||||
#ifdef USE_VTX_RTC6705
|
#ifdef USE_VTX_RTC6705
|
||||||
#define VTX_TABLE_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER_INDEX
|
#define VTX_TABLE_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER_INDEX
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -31,9 +31,6 @@
|
||||||
#include "common/time.h"
|
#include "common/time.h"
|
||||||
|
|
||||||
#include "drivers/vtx_common.h"
|
#include "drivers/vtx_common.h"
|
||||||
#if defined(USE_VTX_RTC6705)
|
|
||||||
#include "drivers/vtx_rtc6705.h"
|
|
||||||
#endif
|
|
||||||
#include "drivers/vtx_table.h"
|
#include "drivers/vtx_table.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
|
@ -112,27 +109,6 @@ void vtxInit(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Once refactoring for RTC6705 to handle pit mode properly and remove the requirement
|
|
||||||
// for having a 0 value in the vtxtable power levels is completed then this function will
|
|
||||||
// no longer be required and the VTX_TABLE_LOW_POWER_INDEX value can always be used.
|
|
||||||
static uint8_t vtxGetMinimumPowerIndex(void)
|
|
||||||
{
|
|
||||||
const vtxDevice_t *vtxDevice = vtxCommonDevice();
|
|
||||||
vtxDevType_e vtxType = VTXDEV_UNKNOWN;
|
|
||||||
if (vtxDevice) {
|
|
||||||
vtxType = vtxCommonGetDeviceType(vtxDevice);
|
|
||||||
}
|
|
||||||
switch (vtxType) {
|
|
||||||
#if defined(USE_VTX_RTC6705)
|
|
||||||
case VTXDEV_RTC6705:
|
|
||||||
// special handling for rtc6705 which has the low power setting in index 2
|
|
||||||
return VTX_RTC6705_DEFAULT_POWER_INDEX;
|
|
||||||
#endif
|
|
||||||
default:
|
|
||||||
return VTX_TABLE_LOW_POWER_INDEX;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
||||||
{
|
{
|
||||||
vtxSettingsConfig_t settings = {
|
vtxSettingsConfig_t settings = {
|
||||||
|
@ -148,14 +124,14 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
||||||
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
||||||
settings.band = 0;
|
settings.band = 0;
|
||||||
settings.freq = settings.pitModeFreq;
|
settings.freq = settings.pitModeFreq;
|
||||||
settings.power = vtxGetMinimumPowerIndex();
|
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
||||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
||||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM && !ARMING_FLAG(WAS_EVER_ARMED)))) {
|
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM && !ARMING_FLAG(WAS_EVER_ARMED)))) {
|
||||||
settings.power = vtxGetMinimumPowerIndex();
|
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||||
}
|
}
|
||||||
|
|
||||||
return settings;
|
return settings;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue