Add MSP override mode

The MSP override mode allows for use of MSP togehter with
another RX feature like SBUS. When enabling the MSP override
mode all channels from the `msp_override_channels` bitmask
will be overwritten by data comming from MSP instead of the
main RX.
This commit is contained in:
Birk Tjelmeland 2020-06-14 14:56:04 +02:00
parent 94cd650472
commit aa5066e443
13 changed files with 101 additions and 2 deletions

View File

@ -124,6 +124,7 @@ COMMON_SRC = \
rx/sumh.c \
rx/xbus.c \
rx/fport.c \
rx/msp_override.c \
sensors/acceleration.c \
sensors/boardalignment.c \
sensors/compass.c \

View File

@ -757,6 +757,9 @@ const clivalue_t valueTable[] = {
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_min_usec) },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
{ "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)},
#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) },
{ "rx_spi_bus", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, SPIDEV_COUNT }, PG_RX_SPI_CONFIG, offsetof(rxSpiConfig_t, spibus) },

View File

@ -596,6 +596,14 @@ static void validateAndFixConfig(void)
}
}
}
#if defined(USE_RX_MSP_OVERRIDE)
for (int i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
const modeActivationCondition_t *mac = modeActivationConditions(i);
if (mac->modeId == BOXMSPOVERRIDE && ((1 << (mac->auxChannelIndex) & (rxConfig()->msp_override_channels_mask)))) {
rxConfigMutable()->msp_override_channels_mask &= ~(1 << (mac->auxChannelIndex + NON_AUX_CHANNEL_COUNT));
}
}
#endif
}
void validateAndFixGyroConfig(void)

View File

@ -74,6 +74,7 @@ typedef enum {
BOXACROTRAINER,
BOXVTXCONTROLDISABLE,
BOXLAUNCHCONTROL,
BOXMSPOVERRIDE,
CHECKBOX_ITEM_COUNT
} boxId_e;

View File

@ -97,6 +97,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT] = {
{ BOXACROTRAINER, "ACRO TRAINER", 47 },
{ BOXVTXCONTROLDISABLE, "DISABLE VTX CONTROL", 48},
{ BOXLAUNCHCONTROL, "LAUNCH CONTROL", 49 },
{ BOXMSPOVERRIDE, "MSP OVERRIDE", 50},
};
// mask of enabled IDs, calculated on startup based on enabled features. boxId_e is used as bit index

View File

@ -73,6 +73,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
.srxl2_baud_fast = true,
.sbus_baud_fast = false,
.crsf_use_rx_snr = false,
.msp_override_channels_mask = 0,
);
#ifdef RX_CHANNELS_TAER

View File

@ -66,6 +66,8 @@ typedef struct rxConfig_s {
uint8_t srxl2_baud_fast; // Select Spektrum SRXL2 fast baud rate
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
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);

View File

@ -36,7 +36,7 @@
static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
uint16_t rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeState);
return mspFrame[chan];

View File

@ -22,5 +22,6 @@
struct rxConfig_s;
struct rxRuntimeState_s;
uint16_t 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);

View File

@ -0,0 +1,44 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#if defined(USE_RX_MSP_OVERRIDE)
#include "rx/msp_override.h"
#include "rx/msp.h"
#include "fc/rc_modes.h"
#include "common/maths.h"
uint16_t rxMspOverrideReadRawRc(const rxRuntimeState_t *rxRuntimeState, const rxConfig_t *rxConfig, uint8_t chan)
{
uint16_t rxSample = (rxRuntimeState->rcReadRawFn)(rxRuntimeState, chan);
uint16_t overrideSample = rxMspReadRawRC(rxRuntimeState, chan);
bool override = (1 << chan) & rxConfig->msp_override_channels_mask;
if (IS_RC_MODE_ACTIVE(BOXMSPOVERRIDE) && override) {
return overrideSample;
} else {
return rxSample;
}
}
#endif

View File

@ -0,0 +1,27 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "rx/rx.h"
#include "pg/rx.h"
uint16_t rxMspOverrideReadRawRc(const rxRuntimeState_t *rxRuntimeState, const rxConfig_t *rxConfig, uint8_t chan);

View File

@ -67,6 +67,7 @@
#include "rx/crsf.h"
#include "rx/rx_spi.h"
#include "rx/targetcustomserial.h"
#include "rx/msp_override.h"
const char rcChannelLetters[] = "AERT12345678abcdefgh";
@ -591,7 +592,15 @@ static void readRxChannelsApplyRanges(void)
const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel;
// sample the channel
uint16_t sample = rxRuntimeState.rcReadRawFn(&rxRuntimeState, rawChannel);
uint16_t sample;
#if defined(USE_RX_MSP_OVERRIDE)
if (rxConfig()->msp_override_channels_mask) {
sample = rxMspOverrideReadRawRc(&rxRuntimeState, rxConfig(), rawChannel);
} else
#endif
{
sample = rxRuntimeState.rcReadRawFn(&rxRuntimeState, rawChannel);
}
// apply the rx calibration
if (channel < NON_AUX_CHANNEL_COUNT) {

View File

@ -368,4 +368,5 @@
#define USE_INTERPOLATED_SP
#define USE_CUSTOM_BOX_NAMES
#define USE_BATTERY_VOLTAGE_SAG_COMPENSATION
#define USE_RX_MSP_OVERRIDE
#endif