mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
[VTX] RTC6705 power down is now controlled by pitmode rather than powervalue (#8939)
This commit is contained in:
parent
f9be9d85f4
commit
f7c0a87c09
9 changed files with 56 additions and 47 deletions
|
@ -278,9 +278,9 @@ vtxtable band 2 BOSCAM_B B CUSTOM 5733 5752 5771 5790 5809 5828 5847 5866
|
||||||
vtxtable band 3 BOSCAM_E E CUSTOM 5705 5685 5665 5645 5885 5905 5925 5945
|
vtxtable band 3 BOSCAM_E E CUSTOM 5705 5685 5665 5645 5885 5905 5925 5945
|
||||||
vtxtable band 4 FATSHARK F CUSTOM 5740 5760 5780 5800 5820 5840 5860 5880
|
vtxtable band 4 FATSHARK F CUSTOM 5740 5760 5780 5800 5820 5840 5860 5880
|
||||||
vtxtable band 5 RACEBAND R CUSTOM 5658 5695 5732 5769 5806 5843 5880 5917
|
vtxtable band 5 RACEBAND R CUSTOM 5658 5695 5732 5769 5806 5843 5880 5917
|
||||||
vtxtable powerlevels 3
|
vtxtable powerlevels 2
|
||||||
vtxtable powervalues 0 1 2
|
vtxtable powervalues 1 2
|
||||||
vtxtable powerlabels OFF MIN MAX
|
vtxtable powerlabels MIN MAX
|
||||||
```
|
```
|
||||||
|
|
||||||
### Pitmode
|
### Pitmode
|
||||||
|
|
|
@ -43,15 +43,28 @@
|
||||||
static uint8_t cmsx_vtxBand;
|
static uint8_t cmsx_vtxBand;
|
||||||
static uint8_t cmsx_vtxChannel;
|
static uint8_t cmsx_vtxChannel;
|
||||||
static uint8_t cmsx_vtxPower;
|
static uint8_t cmsx_vtxPower;
|
||||||
|
static uint8_t cmsx_vtxPit;
|
||||||
|
|
||||||
static OSD_TAB_t entryVtxBand;
|
static OSD_TAB_t entryVtxBand;
|
||||||
static OSD_TAB_t entryVtxChannel;
|
static OSD_TAB_t entryVtxChannel;
|
||||||
static OSD_TAB_t entryVtxPower;
|
static OSD_TAB_t entryVtxPower;
|
||||||
|
static const char * const cmsxCmsPitNames[] = {
|
||||||
|
"---",
|
||||||
|
"OFF",
|
||||||
|
"ON ",
|
||||||
|
};
|
||||||
|
static OSD_TAB_t entryVtxPit = {&cmsx_vtxPit, 2, cmsxCmsPitNames};
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigRead(void)
|
static void cmsx_Vtx_ConfigRead(void)
|
||||||
{
|
{
|
||||||
vtxCommonGetBandAndChannel(vtxCommonDevice(), &cmsx_vtxBand, &cmsx_vtxChannel);
|
vtxCommonGetBandAndChannel(vtxCommonDevice(), &cmsx_vtxBand, &cmsx_vtxChannel);
|
||||||
vtxCommonGetPowerIndex(vtxCommonDevice(), &cmsx_vtxPower);
|
vtxCommonGetPowerIndex(vtxCommonDevice(), &cmsx_vtxPower);
|
||||||
|
unsigned status;
|
||||||
|
if(vtxCommonGetStatus(vtxCommonDevice(), &status)){
|
||||||
|
cmsx_vtxPit = status & VTX_STATUS_PIT_MODE ? 2 : 1;
|
||||||
|
} else {
|
||||||
|
cmsx_vtxPit = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cmsx_Vtx_ConfigWriteback(void)
|
static void cmsx_Vtx_ConfigWriteback(void)
|
||||||
|
@ -88,6 +101,7 @@ static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
||||||
{
|
{
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
|
vtxCommonSetPitMode(vtxCommonDevice(), cmsx_vtxPit);
|
||||||
cmsx_Vtx_ConfigWriteback();
|
cmsx_Vtx_ConfigWriteback();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -123,11 +137,22 @@ static long cmsx_Vtx_onPowerChange(displayPort_t *pDisp, const void *self)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static long cmsx_Vtx_onPitChange(displayPort_t *pDisp, const void *self)
|
||||||
|
{
|
||||||
|
UNUSED(pDisp);
|
||||||
|
UNUSED(self);
|
||||||
|
if (cmsx_vtxPit == 0) {
|
||||||
|
cmsx_vtxPit = 1;
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
static const OSD_Entry cmsx_menuVtxEntries[] = {
|
||||||
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
||||||
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand, 0},
|
{"BAND", OME_TAB, cmsx_Vtx_onBandChange, &entryVtxBand, 0},
|
||||||
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel, 0},
|
{"CHANNEL", OME_TAB, cmsx_Vtx_onChanChange, &entryVtxChannel, 0},
|
||||||
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower, 0},
|
{"POWER", OME_TAB, cmsx_Vtx_onPowerChange, &entryVtxPower, 0},
|
||||||
|
{"PIT", OME_TAB, cmsx_Vtx_onPitChange, &entryVtxPit, 0},
|
||||||
{"BACK", OME_Back, NULL, NULL, 0},
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
{NULL, OME_END, NULL, NULL, 0}
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
};
|
};
|
||||||
|
|
|
@ -62,10 +62,9 @@ typedef enum {
|
||||||
#define VTX_COMMON_BAND_FS 4
|
#define VTX_COMMON_BAND_FS 4
|
||||||
#define VTX_COMMON_BAND_RACE 5
|
#define VTX_COMMON_BAND_RACE 5
|
||||||
|
|
||||||
// RTC6705 RF Power index "---", 25 or 200 mW
|
// RTC6705 RF Power index 25 or 200 mW
|
||||||
#define VTX_6705_POWER_OFF 1
|
#define VTX_6705_POWER_25 1
|
||||||
#define VTX_6705_POWER_25 2
|
#define VTX_6705_POWER_200 2
|
||||||
#define VTX_6705_POWER_200 3
|
|
||||||
|
|
||||||
// SmartAudio "---", 25, 200, 500, 800 mW
|
// SmartAudio "---", 25, 200, 500, 800 mW
|
||||||
#define VTX_SA_POWER_OFF 1 //1 goes to min power whereas 0 doesnt do anything (illegal index).
|
#define VTX_SA_POWER_OFF 1 //1 goes to min power whereas 0 doesnt do anything (illegal index).
|
||||||
|
|
|
@ -187,6 +187,7 @@ void rtc6705SetFrequency(uint16_t frequency)
|
||||||
|
|
||||||
void rtc6705SetRFPower(uint8_t rf_power)
|
void rtc6705SetRFPower(uint8_t rf_power)
|
||||||
{
|
{
|
||||||
|
rf_power = constrain(rf_power, 1, 2);
|
||||||
#if defined(USE_VTX_RTC6705_SOFTSPI)
|
#if defined(USE_VTX_RTC6705_SOFTSPI)
|
||||||
if (!busdev) {
|
if (!busdev) {
|
||||||
rtc6705SoftSpiSetRFPower(rf_power);
|
rtc6705SoftSpiSetRFPower(rf_power);
|
||||||
|
@ -195,8 +196,6 @@ void rtc6705SetRFPower(uint8_t rf_power)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
rf_power = constrain(rf_power, VTX_RTC6705_MIN_POWER_VALUE, VTX_RTC6705_POWER_COUNT - 1);
|
|
||||||
|
|
||||||
uint32_t val_hex = RTC6705_RW_CONTROL_BIT; // write
|
uint32_t val_hex = RTC6705_RW_CONTROL_BIT; // write
|
||||||
val_hex |= RTC6705_ADDRESS; // address
|
val_hex |= RTC6705_ADDRESS; // address
|
||||||
const uint32_t data = rf_power > 1 ? PA_CONTROL_DEFAULT : (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK));
|
const uint32_t data = rf_power > 1 ? PA_CONTROL_DEFAULT : (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK));
|
||||||
|
|
|
@ -31,14 +31,7 @@
|
||||||
|
|
||||||
#include "pg/vtx_io.h"
|
#include "pg/vtx_io.h"
|
||||||
|
|
||||||
#define VTX_RTC6705_POWER_COUNT 3
|
#define VTX_RTC6705_POWER_COUNT 2
|
||||||
#define VTX_RTC6705_DEFAULT_POWER_INDEX 2
|
|
||||||
|
|
||||||
#if defined(RTC6705_POWER_PIN)
|
|
||||||
#define VTX_RTC6705_MIN_POWER_VALUE 0
|
|
||||||
#else
|
|
||||||
#define VTX_RTC6705_MIN_POWER_VALUE 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define VTX_RTC6705_FREQ_MIN 5600
|
#define VTX_RTC6705_FREQ_MIN 5600
|
||||||
#define VTX_RTC6705_FREQ_MAX 5950
|
#define VTX_RTC6705_FREQ_MAX 5950
|
||||||
|
|
|
@ -49,11 +49,7 @@
|
||||||
#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
|
||||||
#ifdef USE_VTX_RTC6705
|
#define VTX_TABLE_DEFAULT_POWER 1 //1-based indexing. 0 means unknown and 1 is the lowest actual power mode
|
||||||
#define VTX_TABLE_DEFAULT_POWER VTX_RTC6705_DEFAULT_POWER_INDEX
|
|
||||||
#else
|
|
||||||
#define VTX_TABLE_DEFAULT_POWER 1 //lowest actual power mode
|
|
||||||
#endif
|
|
||||||
|
|
||||||
struct vtxTableConfig_s;
|
struct vtxTableConfig_s;
|
||||||
void vtxTableInit(void);
|
void vtxTableInit(void);
|
||||||
|
|
|
@ -69,12 +69,12 @@ const uint8_t vtxTrampPi[SPEKTRUM_VTX_POWER_COUNT] = {
|
||||||
VTX_TRAMP_POWER_200 // Manual - - - -
|
VTX_TRAMP_POWER_200 // Manual - - - -
|
||||||
};
|
};
|
||||||
#endif // USE_VTX_TRAMP
|
#endif // USE_VTX_TRAMP
|
||||||
|
//todo: enable pit mode where appropriate, for all protcols
|
||||||
#ifdef USE_VTX_RTC6705
|
#ifdef USE_VTX_RTC6705
|
||||||
// RTC6705 "---", 25 or 200 mW
|
// RTC6705 "---", 25 or 200 mW
|
||||||
const uint8_t vtxRTC6705Pi[SPEKTRUM_VTX_POWER_COUNT] = {
|
const uint8_t vtxRTC6705Pi[SPEKTRUM_VTX_POWER_COUNT] = {
|
||||||
VTX_6705_POWER_OFF, // Off
|
VTX_6705_POWER_25, // Off
|
||||||
VTX_6705_POWER_OFF, // 1 - 14mW
|
VTX_6705_POWER_25, // 1 - 14mW
|
||||||
VTX_6705_POWER_25, // 15 - 25mW
|
VTX_6705_POWER_25, // 15 - 25mW
|
||||||
VTX_6705_POWER_25, // 26 - 99mW
|
VTX_6705_POWER_25, // 26 - 99mW
|
||||||
VTX_6705_POWER_200, // 100 - 299mW
|
VTX_6705_POWER_200, // 100 - 299mW
|
||||||
|
|
|
@ -180,7 +180,7 @@ void vtxCyclePower(const uint8_t powerStep)
|
||||||
|
|
||||||
int newPower = power + powerStep;
|
int newPower = power + powerStep;
|
||||||
if (newPower >= vtxTablePowerLevels) {
|
if (newPower >= vtxTablePowerLevels) {
|
||||||
newPower = 0;
|
newPower = 1;
|
||||||
} else if (newPower < 0) {
|
} else if (newPower < 0) {
|
||||||
newPower = vtxTablePowerLevels;
|
newPower = vtxTablePowerLevels;
|
||||||
}
|
}
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
|
|
||||||
#if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE)
|
#if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE)
|
||||||
const char *rtc6705PowerNames[VTX_RTC6705_POWER_COUNT + 1] = {
|
const char *rtc6705PowerNames[VTX_RTC6705_POWER_COUNT + 1] = {
|
||||||
"---", "OFF", "MIN", "MAX"
|
"---", "MIN", "MAX"
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -56,6 +56,7 @@ static vtxDevice_t vtxRTC6705 = {
|
||||||
|
|
||||||
static uint16_t rtc6705Frequency;
|
static uint16_t rtc6705Frequency;
|
||||||
static int8_t rtc6705PowerIndex;
|
static int8_t rtc6705PowerIndex;
|
||||||
|
static bool rtc6705PitModeActive;
|
||||||
|
|
||||||
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
static void vtxRTC6705SetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel);
|
||||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency);
|
||||||
|
@ -147,14 +148,19 @@ static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
if (!vtxCommonLookupPowerValue(vtxDevice, index, &newPowerValue)) {
|
if (!vtxCommonLookupPowerValue(vtxDevice, index, &newPowerValue)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint16_t currentPowerValue = 0;
|
|
||||||
vtxCommonLookupPowerValue(vtxDevice, rtc6705PowerIndex, ¤tPowerValue);
|
|
||||||
#ifdef RTC6705_POWER_PIN
|
|
||||||
if (newPowerValue == 0) {
|
|
||||||
// power device off
|
|
||||||
if (currentPowerValue > 0) {
|
|
||||||
// on, power it off
|
|
||||||
rtc6705PowerIndex = index;
|
rtc6705PowerIndex = index;
|
||||||
|
rtc6705SetRFPower(newPowerValue);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void vtxRTC6705SetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
||||||
|
{
|
||||||
|
UNUSED(vtxDevice);
|
||||||
|
#ifdef RTC6705_POWER_PIN
|
||||||
|
if (onoff) {
|
||||||
|
// power device off
|
||||||
|
if (!rtc6705PitModeActive) {
|
||||||
|
// on, power it off
|
||||||
|
rtc6705PitModeActive = onoff;
|
||||||
rtc6705Disable();
|
rtc6705Disable();
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
|
@ -162,27 +168,18 @@ static void vtxRTC6705SetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// change rf power and maybe turn the device on first
|
// change rf power and maybe turn the device on first
|
||||||
if (currentPowerValue == 0) {
|
if (rtc6705PitModeActive) {
|
||||||
// if it's powered down, power it up, wait and configure channel, band and power.
|
// if it's powered down, power it up, wait and configure channel, band and power.
|
||||||
rtc6705PowerIndex = index;
|
rtc6705PitModeActive = onoff;
|
||||||
vtxRTC6705EnableAndConfigure(vtxDevice);
|
vtxRTC6705EnableAndConfigure(vtxDevice);
|
||||||
return;
|
return;
|
||||||
} else {
|
} else {
|
||||||
// if it's powered up, just set the rf power
|
//already on
|
||||||
rtc6705PowerIndex = index;
|
|
||||||
rtc6705SetRFPower(newPowerValue);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
rtc6705PowerIndex = index;
|
|
||||||
rtc6705SetRFPower(MAX(newPowerValue, VTX_RTC6705_MIN_POWER_VALUE);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
static void vtxRTC6705SetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
|
|
||||||
{
|
|
||||||
UNUSED(vtxDevice);
|
|
||||||
UNUSED(onoff);
|
UNUSED(onoff);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
static void vtxRTC6705SetFrequency(vtxDevice_t *vtxDevice, uint16_t frequency)
|
||||||
|
@ -222,8 +219,8 @@ static bool vtxRTC6705GetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFrequency
|
||||||
static bool vtxRTC6705GetStatus(const vtxDevice_t *vtxDevice, unsigned *status)
|
static bool vtxRTC6705GetStatus(const vtxDevice_t *vtxDevice, unsigned *status)
|
||||||
{
|
{
|
||||||
UNUSED(vtxDevice);
|
UNUSED(vtxDevice);
|
||||||
UNUSED(status);
|
*status = rtc6705PitModeActive ? VTX_STATUS_PIT_MODE : 0;
|
||||||
return false;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint8_t vtxRTC6705GetPowerLevels(const vtxDevice_t *vtxDevice, uint16_t *levels, uint16_t *powers)
|
static uint8_t vtxRTC6705GetPowerLevels(const vtxDevice_t *vtxDevice, uint16_t *levels, uint16_t *powers)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue