1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 23:35:34 +03:00

Fix IRC tramp for both protocol varients.

Prevent IRC tramp from briefly entering pitmode at startup.
Backout of PR #10166, ensuring pitmode can be correctly set from OSD and MSP.
Add CLI option to allow non-conforming tramp implementations to work with betaflight.
This commit is contained in:
Phil Greenland 2020-11-12 22:20:53 +00:00
parent 42dd70da35
commit 73f72ea9a3
6 changed files with 47 additions and 29 deletions

View file

@ -283,6 +283,7 @@ 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_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_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_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_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_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 | | `vtx_power` | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | 0 | 3 | 1 | Master | UINT8 |

View file

@ -1464,6 +1464,9 @@ const clivalue_t valueTable[] = {
#if defined(USE_VTX_CONTROL) && defined(USE_VTX_COMMON) #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) }, { "vtx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_VTX_CONFIG, offsetof(vtxConfig_t, halfDuplex) },
#endif #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 // PG_VTX_IO
#ifdef USE_VTX_RTC6705 #ifdef USE_VTX_RTC6705

View file

@ -185,11 +185,16 @@ static bool vtxProcessPower(vtxDevice_t *vtxDevice)
static bool vtxProcessPitMode(vtxDevice_t *vtxDevice) static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
{ {
static bool prevPmSwitchState = false;
unsigned vtxStatus; unsigned vtxStatus;
if (vtxCommonGetStatus(vtxDevice, &vtxStatus)) { if (!ARMING_FLAG(ARMED) && vtxCommonGetStatus(vtxDevice, &vtxStatus)) {
bool currPmSwitchState = IS_RC_MODE_ACTIVE(BOXVTXPITMODE); bool currPmSwitchState = IS_RC_MODE_ACTIVE(BOXVTXPITMODE);
if (currPmSwitchState != prevPmSwitchState) {
prevPmSwitchState = currPmSwitchState;
if (currPmSwitchState) { if (currPmSwitchState) {
if (!ARMING_FLAG(ARMED)) {
#if defined(VTX_SETTINGS_FREQCMD) #if defined(VTX_SETTINGS_FREQCMD)
if (vtxSettingsConfig()->pitModeFreq) { if (vtxSettingsConfig()->pitModeFreq) {
return false; return false;
@ -200,7 +205,6 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
return true; return true;
} }
}
} else { } else {
if (vtxStatus & VTX_STATUS_PIT_MODE) { if (vtxStatus & VTX_STATUS_PIT_MODE) {
vtxCommonSetPitMode(vtxDevice, false); vtxCommonSetPitMode(vtxDevice, false);
@ -209,6 +213,7 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice)
} }
} }
} }
}
return false; return false;
} }

View file

@ -41,6 +41,7 @@ typedef struct vtxChannelActivationCondition_s {
typedef struct vtxConfig_s { typedef struct vtxConfig_s {
vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT]; vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
uint8_t halfDuplex; uint8_t halfDuplex;
uint8_t trampPitModeInverted;
} vtxConfig_t; } vtxConfig_t;
PG_DECLARE(vtxConfig_t, vtxConfig); PG_DECLARE(vtxConfig_t, vtxConfig);

View file

@ -918,8 +918,6 @@ static void vtxSASetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff) static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
{ {
static bool lastOnOff = false;
if (!vtxSAIsReady(vtxDevice) || saDevice.version < 2) { if (!vtxSAIsReady(vtxDevice) || saDevice.version < 2) {
return; return;
} }
@ -929,12 +927,6 @@ static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
return; return;
} }
// Only issue pit mode commands on status change
if (lastOnOff == onoff) {
return;
}
lastOnOff = onoff;
if (saDevice.version >= 3 && !saDevice.willBootIntoPitMode) { if (saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
if (onoff) { if (onoff) {
// enable pitmode using SET_POWER command with 0 dbm. // enable pitmode using SET_POWER command with 0 dbm.

View file

@ -94,6 +94,7 @@ typedef enum {
TRAMP_STATUS_ONLINE_CONFIG TRAMP_STATUS_ONLINE_CONFIG
} trampStatus_e; } trampStatus_e;
// Module state
static trampStatus_e trampStatus = TRAMP_STATUS_OFFLINE; static trampStatus_e trampStatus = TRAMP_STATUS_OFFLINE;
// Device limits, read from device during init // Device limits, read from device during init
@ -105,20 +106,20 @@ static uint32_t trampRFPowerMax;
static uint32_t trampCurFreq = 0; static uint32_t trampCurFreq = 0;
static uint16_t trampCurConfPower = 0; // Configured power static uint16_t trampCurConfPower = 0; // Configured power
static uint16_t trampCurActPower = 0; // Actual power static uint16_t trampCurActPower = 0; // Actual power
static uint8_t trampCurPitMode = 0; static uint8_t trampCurPitMode = 0; // Expect to startup out of pitmode
static int16_t trampCurTemp = 0; static int16_t trampCurTemp = 0;
static uint8_t trampCurControlMode = 0; static uint8_t trampCurControlMode = 0;
// Device configuration, desired state of device // Device configuration, desired state of device
static uint32_t trampConfFreq = 0; static uint32_t trampConfFreq = 0;
static uint16_t trampConfPower = 0; static uint16_t trampConfPower = 0;
static uint8_t trampConfPitMode = 0; static uint8_t trampConfPitMode = 0; // Initially configured out of pitmode
// Last device configuration, last desired state of device - used to reset // Last device configuration, last desired state of device - used to reset
// retry count // retry count
static uint32_t trampLastConfFreq = 0; static uint32_t trampLastConfFreq = 0;
static uint16_t trampLastConfPower = 0; static uint16_t trampLastConfPower = 0;
static uint8_t trampLastConfPitMode = 0; static uint8_t trampLastConfPitMode = 0; // Mirror trampConfPitMode
// Retry count // Retry count
static uint8_t trampRetryCount = TRAMP_MAX_RETRIES; static uint8_t trampRetryCount = TRAMP_MAX_RETRIES;
@ -210,7 +211,13 @@ static char trampHandleResponse(void)
trampCurFreq = freq; trampCurFreq = freq;
trampCurConfPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8); trampCurConfPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
trampCurControlMode = trampRespBuffer[6]; // Currently only used for race lock 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); trampCurActPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
// Init config with current status if not set // Init config with current status if not set
@ -325,7 +332,7 @@ static void trampQuery(uint8_t cmd)
static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs) static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
{ {
UNUSED(vtxDevice); UNUSED(vtxDevice);
uint8_t configUpdateRequired = 0; bool configUpdateRequired = false;
// Read response from device // Read response from device
const char replyCode = trampReceive(); const char replyCode = trampReceive();
@ -374,19 +381,19 @@ static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
trampSendCommand('F', trampConfFreq); trampSendCommand('F', trampConfFreq);
// Set flag // Set flag
configUpdateRequired = 1; configUpdateRequired = true;
} else if (!trampVtxRaceLockEnabled() && (trampConfPower != trampCurConfPower)) { } else if (!trampVtxRaceLockEnabled() && (trampConfPower != trampCurConfPower)) {
// Power can be and needs to be updated, issue request // Power can be and needs to be updated, issue request
trampSendCommand('P', trampConfPower); trampSendCommand('P', trampConfPower);
// Set flag // Set flag
configUpdateRequired = 1; configUpdateRequired = true;
} else if (trampConfPitMode != trampCurPitMode) { } else if (trampConfPitMode != trampCurPitMode) {
// Pit mode needs to be updated, issue request // Pit mode needs to be updated, issue request
trampSendCommand('I', trampConfPitMode); trampSendCommand('I', trampConfPitMode ? 0 : 1);
// Set flag // Set flag
configUpdateRequired = 1; configUpdateRequired = true;
} }
if (configUpdateRequired) { if (configUpdateRequired) {
@ -464,7 +471,14 @@ static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
DEBUG_SET(DEBUG_VTX_TRAMP, 0, trampStatus); DEBUG_SET(DEBUG_VTX_TRAMP, 0, trampStatus);
DEBUG_SET(DEBUG_VTX_TRAMP, 1, replyCode); DEBUG_SET(DEBUG_VTX_TRAMP, 1, replyCode);
DEBUG_SET(DEBUG_VTX_TRAMP, 2, configUpdateRequired); DEBUG_SET(DEBUG_VTX_TRAMP, 2, ((trampConfPitMode << 14) & 0xC000) |
((trampCurPitMode << 12) & 0x3000) |
((trampConfPower << 8) & 0x0F00) |
((trampCurConfPower << 4) & 0x00F0) |
((trampConfFreq != trampCurFreq) ? 0x0008 : 0x0000) |
((trampConfPower != trampCurConfPower) ? 0x0004 : 0x0000) |
((trampConfPitMode != trampCurPitMode) ? 0x0002 : 0x0000) |
(configUpdateRequired ? 0x0001 : 0x0000));
DEBUG_SET(DEBUG_VTX_TRAMP, 3, trampRetryCount); DEBUG_SET(DEBUG_VTX_TRAMP, 3, trampRetryCount);
#ifdef USE_CMS #ifdef USE_CMS
@ -515,7 +529,7 @@ static void vtxTrampSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
{ {
UNUSED(vtxDevice); UNUSED(vtxDevice);
trampConfPitMode = onoff ? 0 : 1; // note inverted values trampConfPitMode = onoff;
if (trampConfPitMode != trampLastConfPitMode) { if (trampConfPitMode != trampLastConfPitMode) {
// Requested pitmode changed, reset retry count // Requested pitmode changed, reset retry count
trampRetryCount = TRAMP_MAX_RETRIES; trampRetryCount = TRAMP_MAX_RETRIES;
@ -602,8 +616,10 @@ static bool vtxTrampGetStatus(const vtxDevice_t *vtxDevice, unsigned *status)
return false; return false;
} }
// Return pitmode from latest query response // Mirror configued pit mode state rather than use current pitmode as we
*status = (trampCurPitMode ? 0 : VTX_STATUS_PIT_MODE); // should, otherwise the logic in vtxProcessPitMode may not get us to the
// correct state if pitmode is toggled quickly
*status = (trampConfPitMode ? VTX_STATUS_PIT_MODE : 0);
// Check VTX is not locked // Check VTX is not locked
*status |= ((trampCurControlMode & TRAMP_CONTROL_RACE_LOCK) ? VTX_STATUS_LOCKED : 0); *status |= ((trampCurControlMode & TRAMP_CONTROL_RACE_LOCK) ? VTX_STATUS_LOCKED : 0);