mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Review updates. Remove new CLI option in anticipation of fix from Mateksys.
This commit is contained in:
parent
73f72ea9a3
commit
e1eba3fdda
4 changed files with 1 additions and 12 deletions
|
@ -283,7 +283,6 @@ Click on a variable to jump to the relevant documentation page.
|
|||
| `vtx_channel` | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | 1 | 8 | 1 | Master | UINT8 |
|
||||
| `vtx_freq` | Set the VTX frequency using raw MHz. This parameter is ignored unless `vtx_band` is 0. | 0 | 5900 | 5740 | Master | UINT16 |
|
||||
| `vtx_halfduplex` | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | OFF | ON | ON | Master | UINT8 |
|
||||
| `vtx_tramp_pitmode_inverted` | Invert tramp pitmode status returned from device. May be required for some VTX's which don't implement the tramp protocol correctly (Matek are a known example). | OFF | ON | ON | Master | UINT8 |
|
||||
| `vtx_low_power_disarm` | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | | | OFF | Master | UINT8 |
|
||||
| `vtx_pit_mode_freq` | Frequency to use (in MHz) when the VTX is in pit mode. | 0 | 5900 | 0 | Master | UINT16 |
|
||||
| `vtx_power` | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | 0 | 3 | 1 | Master | UINT8 |
|
||||
|
|
|
@ -1464,9 +1464,6 @@ const clivalue_t valueTable[] = {
|
|||
#if defined(USE_VTX_CONTROL) && defined(USE_VTX_COMMON)
|
||||
{ "vtx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_VTX_CONFIG, offsetof(vtxConfig_t, halfDuplex) },
|
||||
#endif
|
||||
#ifdef USE_VTX_TRAMP
|
||||
{ "vtx_tramp_pitmode_inverted", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_VTX_CONFIG, offsetof(vtxConfig_t, trampPitModeInverted) },
|
||||
#endif
|
||||
|
||||
// PG_VTX_IO
|
||||
#ifdef USE_VTX_RTC6705
|
||||
|
|
|
@ -41,7 +41,6 @@ typedef struct vtxChannelActivationCondition_s {
|
|||
typedef struct vtxConfig_s {
|
||||
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
|
||||
uint8_t halfDuplex;
|
||||
uint8_t trampPitModeInverted;
|
||||
} vtxConfig_t;
|
||||
|
||||
PG_DECLARE(vtxConfig_t, vtxConfig);
|
||||
|
|
|
@ -211,13 +211,7 @@ static char trampHandleResponse(void)
|
|||
trampCurFreq = freq;
|
||||
trampCurConfPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
|
||||
trampCurControlMode = trampRespBuffer[6]; // Currently only used for race lock
|
||||
if (vtxConfig()->trampPitModeInverted) {
|
||||
// Invert pitmode (for devices which don't implement protocol correctly)
|
||||
trampCurPitMode = !trampRespBuffer[7];
|
||||
} else {
|
||||
// Use official pitmode value
|
||||
trampCurPitMode = trampRespBuffer[7];
|
||||
}
|
||||
trampCurPitMode = trampRespBuffer[7];
|
||||
trampCurActPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
|
||||
|
||||
// Init config with current status if not set
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue