Skip to content

Commit

Permalink
Do not go into failsafe when the correct roll/pitch/yaw/throttle are …
Browse files Browse the repository at this point in the history
…sent via MSP_OVERRIDE (betaflight#13380)

* Override failsafe when MSP_OVERRIDE active

Fixes betaflight#13374

Set `rxSignalReceived = true` If MSP_OVERRIDE is active, so that it can be checked later. Otherwise, MSP controls are not considered in failsafe checks.

* Do override only if BOXMOODEOVERRIDE box is active as well

* Update msp.h

* Update msp.c

* Make sure that failsafe works when there is no signal from MSP

* Introduce rxMspOverrideFrameStatus to make a clear separation from rxMspFrameStatus

* Update src/main/rx/msp.c

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* add msp_override_failsafe

* Update src/main/pg/rx.h

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* Update src/main/rx/rx.c

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

---------

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
  • Loading branch information
yrik and haslinghuis committed Mar 8, 2024
1 parent 5920727 commit 7fe82ab
Show file tree
Hide file tree
Showing 5 changed files with 27 additions and 0 deletions.
1 change: 1 addition & 0 deletions src/main/cli/settings.c
Expand Up @@ -793,6 +793,7 @@ const clivalue_t valueTable[] = {
{ "serialrx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, halfDuplex) },
#if defined(USE_RX_MSP_OVERRIDE)
{ "msp_override_channels_mask", VAR_UINT32 | MASTER_VALUE, .config.u32Max = (1 << MAX_SUPPORTED_RC_CHANNEL_COUNT) - 1, PG_RX_CONFIG, offsetof(rxConfig_t, msp_override_channels_mask)},
{ "msp_override_failsafe", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, msp_override_failsafe)},
#endif
#ifdef USE_RX_SPI
{ "rx_spi_protocol", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_SPI }, PG_RX_SPI_CONFIG, offsetof(rxSpiConfig_t, rx_spi_protocol) },
Expand Down
1 change: 1 addition & 0 deletions src/main/pg/rx.h
Expand Up @@ -62,6 +62,7 @@ typedef struct rxConfig_s {
uint8_t sbus_baud_fast; // Select SBus fast baud rate
uint8_t crsf_use_rx_snr; // Use RX SNR (in dB) instead of RSSI dBm for CRSF
uint32_t msp_override_channels_mask; // Channels to override when the MSP override mode is enabled
uint8_t msp_override_failsafe; // if false then extra RC link is always required in msp_override mode, true - allows control via msp_override without extra RC link (autonomous use case)
uint8_t crsf_use_negotiated_baud; // Use negotiated baud rate for CRSF V3
} rxConfig_t;

Expand Down
14 changes: 14 additions & 0 deletions src/main/rx/msp.c
Expand Up @@ -35,6 +35,7 @@

static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static bool rxMspFrameDone = false;
static bool rxMspOverrideFrameDone = false;

float rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
Expand All @@ -57,6 +58,7 @@ void rxMspFrameReceive(uint16_t *frame, int channelCount)
}

rxMspFrameDone = true;
rxMspOverrideFrameDone = true;
}

static uint8_t rxMspFrameStatus(rxRuntimeState_t *rxRuntimeState)
Expand All @@ -71,6 +73,18 @@ static uint8_t rxMspFrameStatus(rxRuntimeState_t *rxRuntimeState)
return RX_FRAME_COMPLETE;
}

#if defined(USE_RX_MSP_OVERRIDE)
uint8_t rxMspOverrideFrameStatus(void)
{
if (!rxMspOverrideFrameDone) {
return RX_FRAME_PENDING;
}

rxMspOverrideFrameDone = false;
return RX_FRAME_COMPLETE;
}
#endif

void rxMspInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
Expand Down
1 change: 1 addition & 0 deletions src/main/rx/msp.h
Expand Up @@ -25,3 +25,4 @@ struct rxRuntimeState_s;
float rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan);
void rxMspInit(const struct rxConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState);
void rxMspFrameReceive(uint16_t *frame, int channelCount);
uint8_t rxMspOverrideFrameStatus();
10 changes: 10 additions & 0 deletions src/main/rx/rx.c
Expand Up @@ -534,6 +534,16 @@ FAST_CODE_NOINLINE void rxFrameCheck(timeUs_t currentTimeUs, timeDelta_t current
}
}

#if defined(USE_RX_MSP_OVERRIDE)
if (IS_RC_MODE_ACTIVE(BOXMSPOVERRIDE) && rxConfig()->msp_override_channels_mask && rxConfig()->msp_override_failsafe) {
if (rxMspOverrideFrameStatus() & RX_FRAME_COMPLETE) {
rxSignalReceived = true;
rxDataProcessingRequired = true;
needRxSignalBefore = currentTimeUs + needRxSignalMaxDelayUs;
}
}
#endif

DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 0, rxSignalReceived);
}

Expand Down

0 comments on commit 7fe82ab

Please sign in to comment.