Skip to content

Commit

Permalink
Added Spektrum SRXL2 support. (#5791)
Browse files Browse the repository at this point in the history
This consists of various files/changes brought over from betaflight with modifications to operate in the current state of inav.
It also includes files/changes that were not a part of the betaflight SRXL2 merge, as the previous bidi srxl implementation was not yet implemented either, and SRXL2 has some dependencies on the Spektrum telemetry structuring from those files.
  • Loading branch information
MiguelFAlvarez authored Oct 23, 2020
1 parent ca97a8e commit a88bab5
Show file tree
Hide file tree
Showing 17 changed files with 1,957 additions and 46 deletions.
6 changes: 6 additions & 0 deletions src/main/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -401,6 +401,8 @@ main_sources(COMMON_SRC
rx/sbus_channels.h
rx/spektrum.c
rx/spektrum.h
rx/srxl2.c
rx/srxl2.h
rx/sumd.c
rx/sumd.h
rx/sumh.c
Expand Down Expand Up @@ -486,6 +488,8 @@ main_sources(COMMON_SRC
io/displayport_msp.h
io/displayport_oled.c
io/displayport_oled.h
io/displayport_srxl.c
io/displayport_srxl.h
io/displayport_hott.c
io/displayport_hott.h
io/flashfs.c
Expand Down Expand Up @@ -547,6 +551,8 @@ main_sources(COMMON_SRC

telemetry/crsf.c
telemetry/crsf.h
telemetry/srxl.c
telemetry/srxl.h
telemetry/frsky.c
telemetry/frsky.h
telemetry/frsky_d.c
Expand Down
33 changes: 33 additions & 0 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,7 @@ extern uint8_t __config_end;
#include "rx/rx.h"
#include "rx/spektrum.h"
#include "rx/eleres.h"
#include "rx/srxl2.h"

#include "scheduler/scheduler.h"

Expand Down Expand Up @@ -2578,6 +2579,35 @@ static void cliEleresBind(char *cmdline)
}
#endif // USE_RX_ELERES

#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
void cliRxBind(char *cmdline){
UNUSED(cmdline);
if (rxConfig()->receiverType == RX_TYPE_SERIAL) {
switch (rxConfig()->serialrx_provider) {
default:
cliPrint("Not supported.");
break;
#if defined(USE_SERIALRX_SRXL2)
case SERIALRX_SRXL2:
srxl2Bind();
cliPrint("Binding SRXL2 receiver...");
break;
#endif
}
}
#if defined(USE_RX_SPI)
else if (rxConfig()->receiverType == RX_TYPE_SPI) {
switch (rxConfig()->rx_spi_protocol) {
default:
cliPrint("Not supported.");
break;
}

}
#endif
}
#endif

static void cliExit(char *cmdline)
{
UNUSED(cmdline);
Expand Down Expand Up @@ -3465,6 +3495,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
"\t<+|->[name]", cliBeeper),
#endif
#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
CLI_COMMAND_DEF("bind_rx", "initiate binding for RX SPI or SRXL2", NULL, cliRxBind),
#endif
#if defined(USE_BOOTLOG)
CLI_COMMAND_DEF("bootlog", "show boot events", NULL, cliBootlog),
#endif
Expand Down
6 changes: 6 additions & 0 deletions src/main/fc/fc_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@
#include "io/displayport_frsky_osd.h"
#include "io/displayport_msp.h"
#include "io/displayport_max7456.h"
#include "io/displayport_srxl.h"
#include "io/flashfs.h"
#include "io/gps.h"
#include "io/ledstrip.h"
Expand Down Expand Up @@ -573,6 +574,11 @@ void init(void)
uavInterconnectBusInit();
#endif

#if defined(USE_CMS) && defined(USE_SPEKTRUM_CMS_TELEMETRY) && defined(USE_TELEMETRY_SRXL)
// Register the srxl Textgen telemetry sensor as a displayport device
cmsDisplayPortRegister(displayPortSrxlInit());
#endif

#ifdef USE_GPS
if (feature(FEATURE_GPS)) {
gpsInit();
Expand Down
11 changes: 10 additions & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ tables:
values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UIB"]
enum: rxReceiverType_e
- name: serial_rx
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2"]
values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2"]
- name: rx_spi_protocol
values: ["V202_250K", "V202_1M", "SYMA_X", "SYMA_X5C", "CX10", "CX10A", "H8_3D", "INAV", "ELERES"]
enum: rx_spi_protocol_e
Expand Down Expand Up @@ -144,6 +144,8 @@ tables:
- name: tristate
enum: tristate_e
values: ["AUTO", "ON", "OFF"]
- name: off_on
values: ["OFF", "ON"]

groups:
- name: PG_GYRO_CONFIG
Expand Down Expand Up @@ -567,6 +569,13 @@ groups:
condition: USE_SPEKTRUM_BIND
min: SPEKTRUM_SAT_BIND_DISABLED
max: SPEKTRUM_SAT_BIND_MAX
- name: srxl2_unit_id
condition: USE_SERIALRX_SRXL2
min: 0
max: 15
- name: srxl2_baud_fast
condition: USE_SERIALRX_SRXL2
table: off_on
- name: rx_min_usec
description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc."
default_value: "885"
Expand Down
152 changes: 152 additions & 0 deletions src/main/io/displayport_srxl.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,152 @@
/*
* 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 <stdbool.h>
#include <stdint.h>
#include <string.h>

#include "platform.h"
#if defined (USE_SPEKTRUM_CMS_TELEMETRY) && defined (USE_CMS) && defined(USE_TELEMETRY_SRXL)

#include "common/utils.h"

#include "drivers/display.h"
#include "cms/cms.h"

#include "telemetry/srxl.h"

displayPort_t srxlDisplayPort;

static int srxlDrawScreen(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}

static int srxlScreenSize(const displayPort_t *displayPort)
{
return displayPort->rows * displayPort->cols;
}

static int srxlWriteChar(displayPort_t *displayPort, uint8_t col, uint8_t row, uint16_t c, textAttributes_t attr)
{
return (spektrumTmTextGenPutChar(col, row, c));
UNUSED(displayPort);
UNUSED(attr);
}


static int srxlWriteString(displayPort_t *displayPort, uint8_t col, uint8_t row, const char *s, textAttributes_t attr)
{
while (*s) {
srxlWriteChar(displayPort, col++, row, *(s++), attr);
}
return 0;
}

static int srxlClearScreen(displayPort_t *displayPort)
{
textAttributes_t attr = 0;
for (int row = 0; row < SPEKTRUM_SRXL_TEXTGEN_BUFFER_ROWS; row++) {
for (int col= 0; col < SPEKTRUM_SRXL_TEXTGEN_BUFFER_COLS; col++) {
srxlWriteChar(displayPort, col, row, ' ', attr);
}
}
srxlWriteString(displayPort, 1, 0, "INAV", attr);

if (displayPort->grabCount == 0) {
srxlWriteString(displayPort, 0, 2, CMS_STARTUP_HELP_TEXT1, attr);
srxlWriteString(displayPort, 2, 3, CMS_STARTUP_HELP_TEXT2, attr);
srxlWriteString(displayPort, 2, 4, CMS_STARTUP_HELP_TEXT3, attr);
}
return 0;
}

static bool srxlIsTransferInProgress(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return false;
}

/*
static bool srxlIsSynced(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return true;
}
*/

static int srxlHeartbeat(displayPort_t *displayPort)
{
UNUSED(displayPort);
return 0;
}

static void srxlResync(displayPort_t *displayPort)
{
UNUSED(displayPort);
}

static uint32_t srxlTxBytesFree(const displayPort_t *displayPort)
{
UNUSED(displayPort);
return UINT32_MAX;
}

static int srxlGrab(displayPort_t *displayPort)
{
return displayPort->grabCount = 1;
}

static int srxlRelease(displayPort_t *displayPort)
{
int cnt = displayPort->grabCount = 0;
srxlClearScreen(displayPort);
return cnt;
}

static const displayPortVTable_t srxlVTable = {
.grab = srxlGrab,
.release = srxlRelease,
.clearScreen = srxlClearScreen,
.drawScreen = srxlDrawScreen,
.screenSize = srxlScreenSize,
.writeString = srxlWriteString,
.writeChar = srxlWriteChar,
.isTransferInProgress = srxlIsTransferInProgress,
.heartbeat = srxlHeartbeat,
.resync = srxlResync,
//.isSynced = srxlIsSynced,
.txBytesFree = srxlTxBytesFree,
//.layerSupported = NULL,
//.layerSelect = NULL,
//.layerCopy = NULL,
};

displayPort_t *displayPortSrxlInit(void)
{
srxlDisplayPort.device = NULL;
displayInit(&srxlDisplayPort, &srxlVTable);
srxlDisplayPort.rows = SPEKTRUM_SRXL_TEXTGEN_BUFFER_ROWS;
srxlDisplayPort.cols = SPEKTRUM_SRXL_TEXTGEN_BUFFER_COLS;
return &srxlDisplayPort;
}

#endif
25 changes: 25 additions & 0 deletions src/main/io/displayport_srxl.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/*
* 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

displayPort_t *displayPortSrxlInit(void);

extern displayPort_t srxlDisplayPort;
17 changes: 14 additions & 3 deletions src/main/rx/rx.c
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@
#include "rx/rx_spi.h"
#include "rx/sbus.h"
#include "rx/spektrum.h"
#include "rx/srxl2.h"
#include "rx/sumd.h"
#include "rx/sumh.h"
#include "rx/uib_rx.h"
Expand Down Expand Up @@ -91,6 +92,7 @@ static bool mspOverrideDataProcessingRequired = false;
static bool rxSignalReceived = false;
static bool rxFlightChannelsValid = false;
static bool rxIsInFailsafeMode = true;
static uint8_t rxChannelCount;

static timeUs_t rxNextUpdateAtUs = 0;
static timeUs_t needRxSignalBefore = 0;
Expand Down Expand Up @@ -141,6 +143,8 @@ PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
.mspOverrideChannels = 15,
#endif
.rssi_source = RSSI_SOURCE_AUTO,
.srxl2_unit_id = 1,
.srxl2_baud_fast = 1,
);

void resetAllRxChannelRangeConfigurations(void)
Expand Down Expand Up @@ -187,6 +191,11 @@ bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
{
bool enabled = false;
switch (rxConfig->serialrx_provider) {
#ifdef USE_SERIALRX_SRXL2
case SERIALRX_SRXL2:
enabled = srxl2RxInit(rxConfig, rxRuntimeConfig);
break;
#endif
#ifdef USE_SERIALRX_SPEKTRUM
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
Expand Down Expand Up @@ -347,6 +356,8 @@ void rxInit(void)
mspOverrideInit();
}
#endif

rxChannelCount = MIN(MAX_SUPPORTED_RC_CHANNEL_COUNT, rxRuntimeConfig.channelCount);
}

void rxUpdateRSSISource(void)
Expand Down Expand Up @@ -516,7 +527,7 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
rxFlightChannelsValid = true;

// Read and process channel data
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
for (int channel = 0; channel < rxChannelCount; channel++) {
const uint8_t rawChannel = calculateChannelRemapping(rxConfig()->rcmap, REMAPPABLE_CHANNEL_COUNT, channel);

// sample the channel
Expand Down Expand Up @@ -549,11 +560,11 @@ bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
// If receiver is in failsafe (not receiving signal or sending invalid channel values) - last good input values are retained
if (rxFlightChannelsValid && rxSignalReceived) {
if (rxRuntimeConfig.requireFiltering) {
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
for (int channel = 0; channel < rxChannelCount; channel++) {
rcChannels[channel].data = applyChannelFiltering(channel, rcStaging[channel]);
}
} else {
for (int channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
for (int channel = 0; channel < rxChannelCount; channel++) {
rcChannels[channel].data = rcStaging[channel];
}
}
Expand Down
3 changes: 3 additions & 0 deletions src/main/rx/rx.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ typedef enum {
SERIALRX_FPORT = 10,
SERIALRX_SBUS_FAST = 11,
SERIALRX_FPORT2 = 12,
SERIALRX_SRXL2 = 13,
} rxSerialReceiverType_e;

#define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 16
Expand Down Expand Up @@ -128,6 +129,8 @@ typedef struct rxConfig_s {
uint8_t rcFilterFrequency; // RC filter cutoff frequency (smoothness vs response sharpness)
uint16_t mspOverrideChannels; // Channels to override with MSP RC when BOXMSPRCOVERRIDE is active
uint8_t rssi_source;
uint8_t srxl2_unit_id;
uint8_t srxl2_baud_fast;
} rxConfig_t;

PG_DECLARE(rxConfig_t, rxConfig);
Expand Down
Loading

0 comments on commit a88bab5

Please sign in to comment.