mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Fix VTX low power disarm when USE_VTX_RTC6705 is defined
Affected all unified targets as USE_VTX_RTC6705 must be defined to allow supporting that VTX option. Would cause the low power index settings for RTC6705 to override the settings for other VTX type and set the vtxtable power level index to 2 instead of 1.
This commit is contained in:
parent
d1d9875208
commit
0bd808d1dc
2 changed files with 28 additions and 2 deletions
|
@ -49,6 +49,8 @@
|
|||
#define VTX_TABLE_DEFAULT_CHANNEL 1
|
||||
#define VTX_TABLE_DEFAULT_FREQ 5740
|
||||
#define VTX_TABLE_DEFAULT_PITMODE_FREQ 0
|
||||
#define VTX_TABLE_LOW_POWER_INDEX 1
|
||||
|
||||
#ifdef USE_VTX_RTC6705
|
||||
#define VTX_TABLE_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER_INDEX
|
||||
#else
|
||||
|
|
|
@ -31,6 +31,9 @@
|
|||
#include "common/time.h"
|
||||
|
||||
#include "drivers/vtx_common.h"
|
||||
#if defined(USE_VTX_RTC6705)
|
||||
#include "drivers/vtx_rtc6705.h"
|
||||
#endif
|
||||
#include "drivers/vtx_table.h"
|
||||
|
||||
#include "fc/config.h"
|
||||
|
@ -109,6 +112,27 @@ 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)
|
||||
{
|
||||
vtxSettingsConfig_t settings = {
|
||||
|
@ -124,14 +148,14 @@ STATIC_UNIT_TESTED vtxSettingsConfig_t vtxGetSettings(void)
|
|||
if (IS_RC_MODE_ACTIVE(BOXVTXPITMODE) && settings.pitModeFreq) {
|
||||
settings.band = 0;
|
||||
settings.freq = settings.pitModeFreq;
|
||||
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||
settings.power = vtxGetMinimumPowerIndex();
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!ARMING_FLAG(ARMED) && !failsafeIsActive() &&
|
||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_ALWAYS ||
|
||||
(settings.lowPowerDisarm == VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM && !ARMING_FLAG(WAS_EVER_ARMED)))) {
|
||||
settings.power = VTX_TABLE_DEFAULT_POWER;
|
||||
settings.power = vtxGetMinimumPowerIndex();
|
||||
}
|
||||
|
||||
return settings;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue