Redpine fast and slow protocols for cc2500

This commit is contained in:
brycedjohnson 2019-12-25 22:05:03 -07:00 committed by Bryce Johnson
parent bbdc1bd586
commit 97c8952921
15 changed files with 620 additions and 8 deletions

View File

@ -255,7 +255,8 @@ static const char * const lookupTableRxSpi[] = {
"KN",
"SFHSS",
"SPEKTRUM",
"FRSKY_X_LBT"
"FRSKY_X_LBT",
"REDPINE"
};
#endif

View File

@ -0,0 +1,541 @@
/*
* 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 <string.h>
#include "platform.h"
#ifdef USE_RX_REDPINE_SPI
#include "cc2500_redpine.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "common/maths.h"
#include "common/utils.h"
#include "config/config.h"
#include "config/feature.h"
#include "drivers/adc.h"
#include "drivers/io.h"
#include "drivers/io_def.h"
#include "drivers/io_types.h"
#include "drivers/resource.h"
#include "drivers/rx/rx_cc2500.h"
#include "drivers/rx/rx_spi.h"
#include "drivers/system.h"
#include "drivers/time.h"
#include "fc/runtime_config.h"
#include "io/vtx.h"
#include "pg/rx.h"
#include "pg/rx_spi.h"
#include "pg/rx_spi_cc2500.h"
#include "rx/cc2500_common.h"
#include "rx/rx_spi_common.h"
#include "sensors/battery.h"
enum {
STATE_INIT = 0,
STATE_BIND,
STATE_BIND_TUNING1,
STATE_BIND_TUNING2,
STATE_BIND_TUNING3,
STATE_BIND_COMPLETE,
STATE_STARTING,
STATE_UPDATE,
STATE_DATA,
STATE_TELEMETRY,
STATE_RESUME,
};
bool redpineFast = true;
#define VTX_STATUS_FRAME 1
#define SCALE_REDPINE(channelValue) ((2 * channelValue + 2452) / 3)
#define SWITCH_REDPINE_SPEED_US 2000000
#define DEFAULT_PACKET_TIME_US 50000
#define REDPINE_HOP_CHANNELS 49
#define BIND_TUNE_STEP 2
static uint8_t calData[255][3];
static timeMs_t start_time;
static uint8_t protocolState;
static uint32_t missingPackets;
static timeDelta_t timeoutUs;
static timeMs_t timeTunedMs;
static int8_t bindOffset_max = 0;
static int8_t bindOffset_min = 0;
static void initialise(void);
static void initBindTuneRx(void);
static bool tuneRx1(uint8_t *packet);
static bool tuneRx2(uint8_t *packet);
static bool tuneRx3(uint8_t *packet);
static void nextChannel();
static bool redpineRxPacketBind(uint8_t *packet);
static bool isRedpineFast(void);
static void initialise()
{
cc2500Reset();
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
cc2500WriteReg(CC2500_03_FIFOTHR, 0x07);
cc2500WriteReg(CC2500_06_PKTLEN, REDPINE_PACKET_SIZE);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0C);
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05);
cc2500WriteReg(CC2500_09_ADDR, 0x00);
if (isRedpineFast()) {
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A);
cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
cc2500WriteReg(CC2500_0D_FREQ2, 0x5D);
cc2500WriteReg(CC2500_0E_FREQ1, 0x93);
cc2500WriteReg(CC2500_0F_FREQ0, 0xB1);
cc2500WriteReg(CC2500_10_MDMCFG4, 0x2D);
cc2500WriteReg(CC2500_11_MDMCFG3, 0x3B);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x73);
cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
cc2500WriteReg(CC2500_14_MDMCFG0, 0x56);
cc2500WriteReg(CC2500_15_DEVIATN, 0x00);
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
cc2500WriteReg(CC2500_18_MCSM0, 0x08);
cc2500WriteReg(CC2500_19_FOCCFG, 0x1D);
cc2500WriteReg(CC2500_1A_BSCFG, 0x1C);
cc2500WriteReg(CC2500_1B_AGCCTRL2, 0xC7);
cc2500WriteReg(CC2500_1C_AGCCTRL1, 0x00);
cc2500WriteReg(CC2500_1D_AGCCTRL0, 0xB0);
cc2500WriteReg(CC2500_21_FREND1, 0xB6);
cc2500WriteReg(CC2500_22_FREND0, 0x10);
cc2500WriteReg(CC2500_23_FSCAL3, 0xEA);
cc2500WriteReg(CC2500_24_FSCAL2, 0x0A);
cc2500WriteReg(CC2500_25_FSCAL1, 0x00);
cc2500WriteReg(CC2500_26_FSCAL0, 0x11);
cc2500WriteReg(CC2500_29_FSTEST, 0x59);
cc2500WriteReg(CC2500_2C_TEST2, 0x88);
cc2500WriteReg(CC2500_2D_TEST1, 0x31);
cc2500WriteReg(CC2500_2E_TEST0, 0x0B);
cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
} else {
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x06);
cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
cc2500WriteReg(CC2500_0D_FREQ2, 0x5D);
cc2500WriteReg(CC2500_0E_FREQ1, 0x93);
cc2500WriteReg(CC2500_0F_FREQ0, 0xB1);
cc2500WriteReg(CC2500_10_MDMCFG4, 0x78);
cc2500WriteReg(CC2500_11_MDMCFG3, 0x93);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x03);
cc2500WriteReg(CC2500_13_MDMCFG1, 0x22);
cc2500WriteReg(CC2500_14_MDMCFG0, 0xF8);
cc2500WriteReg(CC2500_15_DEVIATN, 0x44);
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
cc2500WriteReg(CC2500_18_MCSM0, 0x08);
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
cc2500WriteReg(CC2500_1A_BSCFG, 0x6C);
cc2500WriteReg(CC2500_1B_AGCCTRL2, 0x43);
cc2500WriteReg(CC2500_1C_AGCCTRL1, 0x40);
cc2500WriteReg(CC2500_1D_AGCCTRL0, 0x91);
cc2500WriteReg(CC2500_21_FREND1, 0x56);
cc2500WriteReg(CC2500_22_FREND0, 0x10);
cc2500WriteReg(CC2500_23_FSCAL3, 0xA9);
cc2500WriteReg(CC2500_24_FSCAL2, 0x0A);
cc2500WriteReg(CC2500_25_FSCAL1, 0x00);
cc2500WriteReg(CC2500_26_FSCAL0, 0x11);
cc2500WriteReg(CC2500_29_FSTEST, 0x59);
cc2500WriteReg(CC2500_2C_TEST2, 0x88);
cc2500WriteReg(CC2500_2D_TEST1, 0x31);
cc2500WriteReg(CC2500_2E_TEST0, 0x0B);
cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
}
for (unsigned c = 0; c < 0xFF; c++) { // calibrate all channels
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_0A_CHANNR, c);
cc2500Strobe(CC2500_SCAL);
delayMicroseconds(900); //
calData[c][0] = cc2500ReadReg(CC2500_23_FSCAL3);
calData[c][1] = cc2500ReadReg(CC2500_24_FSCAL2);
calData[c][2] = cc2500ReadReg(CC2500_25_FSCAL1);
}
}
rx_spi_received_e redpineSpiDataReceived(uint8_t *packet)
{
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
switch (protocolState) {
case STATE_INIT:
if ((millis() - start_time) > 10) {
initialise();
protocolState = STATE_BIND;
}
break;
case STATE_BIND:
if (rxSpiCheckBindRequested(true) || rxCc2500SpiConfig()->autoBind) {
redpineFast = true;
initialise();
rxSpiLedOn();
initBindTuneRx();
protocolState = STATE_BIND_TUNING1;
} else {
protocolState = STATE_STARTING;
}
break;
case STATE_BIND_TUNING1:
if (tuneRx1(packet)) {
protocolState = STATE_BIND_TUNING2;
}
break;
case STATE_BIND_TUNING2:
if (tuneRx2(packet)) {
protocolState = STATE_BIND_TUNING3;
}
break;
case STATE_BIND_TUNING3:
if (tuneRx3(packet)) {
if (((int16_t)bindOffset_max - (int16_t)bindOffset_min) <= 10) {
initBindTuneRx();
protocolState = STATE_BIND_TUNING1; // retry
} else {
rxCc2500SpiConfigMutable()->bindOffset = ((int16_t)bindOffset_max + (int16_t)bindOffset_min) / 2;
protocolState = STATE_BIND_COMPLETE;
cc2500Strobe(CC2500_SIDLE);
for (uint8_t i = 0; i < REDPINE_HOP_CHANNELS; i++) {
if (rxCc2500SpiConfigMutable()->bindHopData[i] == 0) {
protocolState = STATE_BIND_TUNING1; // retry
break;
}
}
}
}
break;
case STATE_BIND_COMPLETE:
if (!rxCc2500SpiConfig()->autoBind) {
writeEEPROM();
} else {
uint8_t ctr = 80;
while (ctr--) {
rxSpiLedToggle();
delay(50);
}
}
ret = RX_SPI_RECEIVED_BIND;
protocolState = STATE_STARTING;
break;
default:
ret = redpineHandlePacket(packet, &protocolState);
break;
}
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 3, protocolState);
return ret;
}
static void initBindTuneRx(void)
{
timeTunedMs = millis();
bindOffset_min = -64;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 1, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0C);
cc2500WriteReg(CC2500_18_MCSM0, 0x8);
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]);
cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]);
cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]);
cc2500WriteReg(CC2500_0A_CHANNR, 0);
cc2500Strobe(CC2500_SFRX);
cc2500Strobe(CC2500_SRX);
for (uint8_t i = 0; i < REDPINE_HOP_CHANNELS; i++) {
rxCc2500SpiConfigMutable()->bindHopData[i] = 0;
}
}
static bool tuneRx1(uint8_t *packet)
{
if (bindOffset_min >= 126) {
bindOffset_min = -126;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 1, bindOffset_min);
}
if ((millis() - timeTunedMs) > 220) { // 220ms
timeTunedMs = millis();
bindOffset_min += BIND_TUNE_STEP << 3;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 1, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
cc2500Strobe(CC2500_SRX);
}
if (redpineRxPacketBind(packet)) {
bindOffset_max = bindOffset_min;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 2, bindOffset_max);
cc2500Strobe(CC2500_SRX);
timeTunedMs = millis();
return true;
}
return false;
}
static bool tuneRx2(uint8_t *packet)
{
rxSpiLedBlink(100);
if (((millis() - timeTunedMs) > 880) || bindOffset_max > (126 - BIND_TUNE_STEP)) { // 220ms *4
timeTunedMs = millis();
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
cc2500Strobe(CC2500_SRX);
return true;
}
if (redpineRxPacketBind(packet)) {
timeTunedMs = millis();
bindOffset_max += BIND_TUNE_STEP;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 2, bindOffset_max);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_max);
}
return false;
}
static bool tuneRx3(uint8_t *packet)
{
rxSpiLedBlink(100);
if (((millis() - timeTunedMs) > 880) || bindOffset_min < (-126 + BIND_TUNE_STEP)) { // 220ms *4
return true;
}
if (redpineRxPacketBind(packet)) {
timeTunedMs = millis();
bindOffset_min -= BIND_TUNE_STEP;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 1, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
}
return false;
}
static bool redpineRxPacketBind(uint8_t *packet)
{
if (rxSpiGetExtiState()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen != REDPINE_PACKET_SIZE_W_ADDONS) {
cc2500Strobe(CC2500_SFRX);
} else {
cc2500ReadFifo(packet, ccLen);
if (packet[1] == 0x03 && packet[2] == 0x01) {
rxCc2500SpiConfigMutable()->bindTxId[0] = packet[3];
rxCc2500SpiConfigMutable()->bindTxId[1] = packet[4];
for (uint8_t n = 0; n < 5; n++) {
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
}
return true;
}
}
}
return false;
}
static void nextChannel(void)
{
static uint8_t channr = 0;
channr += 1;
while (channr >= REDPINE_HOP_CHANNELS) {
channr -= REDPINE_HOP_CHANNELS;
}
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3, calData[rxCc2500SpiConfig()->bindHopData[channr]][0]);
cc2500WriteReg(CC2500_24_FSCAL2, calData[rxCc2500SpiConfig()->bindHopData[channr]][1]);
cc2500WriteReg(CC2500_25_FSCAL1, calData[rxCc2500SpiConfig()->bindHopData[channr]][2]);
cc2500WriteReg(CC2500_0A_CHANNR, rxCc2500SpiConfig()->bindHopData[channr]);
}
static bool isRedpineFast(void)
{
return (redpineFast);
}
void switchRedpineMode(void)
{
redpineFast = !redpineFast;
}
#define CHANNEL_START 3
void redpineSetRcData(uint16_t *rcData, const uint8_t *packet)
{
if (packet[CHANNEL_START] == VTX_STATUS_FRAME && packet[CHANNEL_START + 1] == 0) {
if (!ARMING_FLAG(ARMED)) {
vtxSettingsConfigMutable()->band = packet[5] + 1;
vtxSettingsConfigMutable()->channel = packet[6];
vtxSettingsConfigMutable()->power = packet[7];
saveConfigAndNotify();
}
} else {
uint16_t channelValue;
// 4 stick channels (11-bit)
channelValue = (uint16_t)((packet[CHANNEL_START + 1] << 8) & 0x700) | packet[CHANNEL_START];
rcData[0] = SCALE_REDPINE(channelValue);
channelValue = (uint16_t)((packet[CHANNEL_START + 2] << 4) & 0x7F0) | ((packet[CHANNEL_START + 1] >> 4) & 0xF);
rcData[1] = SCALE_REDPINE(channelValue);
channelValue = (uint16_t)((packet[CHANNEL_START + 4] << 8) & 0x700) | packet[CHANNEL_START + 3];
rcData[2] = SCALE_REDPINE(channelValue);
channelValue = (uint16_t)((packet[CHANNEL_START + 5] << 4) & 0x7F0) | ((packet[CHANNEL_START + 4] >> 4) & 0xF);
rcData[3] = SCALE_REDPINE(channelValue);
// 12 1-bit aux channels - first 4 are interleaved with stick channels
rcData[4] = (packet[CHANNEL_START + 1] & 0x08) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[5] = (packet[CHANNEL_START + 2] & 0x80) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[6] = (packet[CHANNEL_START + 4] & 0x08) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[7] = (packet[CHANNEL_START + 5] & 0x80) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[8] = (packet[CHANNEL_START + 6] & 0x01) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[9] = (packet[CHANNEL_START + 6] & 0x02) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[10] = (packet[CHANNEL_START + 6] & 0x04) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[11] = (packet[CHANNEL_START + 6] & 0x08) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[12] = (packet[CHANNEL_START + 6] & 0x10) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[13] = (packet[CHANNEL_START + 6] & 0x20) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[14] = (packet[CHANNEL_START + 6] & 0x40) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
rcData[15] = (packet[CHANNEL_START + 6] & 0x80) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
}
}
rx_spi_received_e redpineHandlePacket(uint8_t *const packet, uint8_t *const protocolState)
{
static int32_t looptime = DEFAULT_PACKET_TIME_US;
static timeUs_t packetTimerUs;
static timeUs_t totalTimerUs;
static timeUs_t protocolTimerUs;
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
switch (*protocolState) {
case STATE_STARTING:
*protocolState = STATE_UPDATE;
nextChannel();
cc2500Strobe(CC2500_SRX);
#ifdef USE_RX_CC2500_SPI_PA_LNA
cc2500TxDisable();
#endif // USE_RX_CC2500_SPI_PA_LNA
protocolTimerUs = micros();
break;
case STATE_UPDATE:
packetTimerUs = 0;
totalTimerUs = micros();
*protocolState = STATE_DATA;
if (rxSpiCheckBindRequested(false)) {
packetTimerUs = 0;
missingPackets = 0;
*protocolState = STATE_INIT;
break;
}
FALLTHROUGH;
// here FS code could be
case STATE_DATA:
if (rxSpiGetExtiState()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen == REDPINE_PACKET_SIZE_W_ADDONS) {
cc2500ReadFifo(packet, ccLen);
if ((packet[1] == rxCc2500SpiConfig()->bindTxId[0]) && (packet[2] == rxCc2500SpiConfig()->bindTxId[1])) {
if (isRedpineFast()) {
looptime = packet[CHANNEL_START + 7] * 100;
} else {
looptime = packet[CHANNEL_START + 7] * 1000;
}
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 0, looptime);
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 1, packet[ccLen - 2]);
packetTimerUs = micros() + looptime / 8; // add a buffer on the packet time incase tx and rx clocks are different
totalTimerUs = micros();
protocolTimerUs = micros();
missingPackets = 0;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 2, missingPackets);
rxSpiLedOn();
cc2500setRssiDbm(packet[ccLen - 2]);
ret = RX_SPI_RECEIVED_DATA;
nextChannel();
cc2500Strobe(CC2500_SRX);
}
} else {
cc2500Strobe(CC2500_SFRX);
}
}
if (cmpTimeUs(micros(), totalTimerUs) > 50 * looptime) {
// out of sync with packets - do a complete resysnc
rxSpiLedToggle();
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
nextChannel();
cc2500Strobe(CC2500_SRX);
*protocolState = STATE_UPDATE;
} else if ((cmpTimeUs(micros(), packetTimerUs) > looptime) && packetTimerUs) {
// missed a packet
packetTimerUs = micros();
nextChannel();
cc2500Strobe(CC2500_SRX);
missingPackets++;
DEBUG_SET(DEBUG_RX_FRSKY_SPI, 2, missingPackets);
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
if (missingPackets >= 2) {
cc2500switchAntennae();
}
#endif
} else if (cmpTimeUs(micros(), protocolTimerUs) > SWITCH_REDPINE_SPEED_US) {
switchRedpineMode();
looptime = DEFAULT_PACKET_TIME_US;
protocolTimerUs = micros();
*protocolState = STATE_INIT;
}
break;
}
return ret;
}
bool redpineSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState, rxSpiExtiConfig_t *extiConfig)
{
UNUSED(extiConfig);
rxSpiCommonIOInit(rxSpiConfig);
if (!cc2500SpiInit()) {
return false;
}
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_REDPINE;
missingPackets = 0;
timeoutUs = 50;
start_time = millis();
protocolState = STATE_INIT;
return true;
}
#endif

View File

@ -0,0 +1,33 @@
/*
* 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 "rx/rx_spi.h"
#define RC_CHANNEL_COUNT_REDPINE 16
#define REDPINE_PACKET_SIZE 11
#define REDPINE_PACKET_SIZE_W_ADDONS (REDPINE_PACKET_SIZE + 2)
void redpineSetRcData(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e redpineHandlePacket(uint8_t *const packet, uint8_t *const protocolState);
rx_spi_received_e redpineSpiDataReceived(uint8_t *packet);
bool redpineSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState, rxSpiExtiConfig_t *extiConfig);

View File

@ -60,6 +60,9 @@ static bool doRxBind(bool doBind)
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
#endif
#if defined(USE_RX_REDPINE_SPI)
case RX_SPI_REDPINE:
#endif
#endif // USE_RX_FRSKY_SPI
#ifdef USE_RX_SFHSS_SPI
case RX_SPI_SFHSS:

View File

@ -41,6 +41,7 @@
#include "rx/rx_spi.h"
#include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_redpine.h"
#include "rx/nrf24_cx10.h"
#include "rx/nrf24_syma.h"
#include "rx/nrf24_v202.h"
@ -135,13 +136,20 @@ STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
#if defined(USE_RX_FRSKY_SPI_X)
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
#endif
protocolInit = frSkySpiInit;
protocolDataReceived = frSkySpiDataReceived;
protocolSetRcDataFromPayload = frSkySpiSetRcData;
protocolProcessFrame = frSkySpiProcessFrame;
break;
#endif
#if defined(USE_RX_REDPINE_SPI)
case RX_SPI_REDPINE:
protocolInit = redpineSpiInit;
protocolDataReceived = redpineSpiDataReceived;
protocolSetRcDataFromPayload = redpineSetRcData;
break;
#endif
#endif // USE_RX_FRSKY_SPI
#ifdef USE_RX_FLYSKY
case RX_SPI_A7105_FLYSKY:

View File

@ -45,6 +45,7 @@ typedef enum {
RX_SPI_SFHSS,
RX_SPI_CYRF6936_DSM,
RX_SPI_FRSKY_X_LBT,
RX_SPI_REDPINE,
RX_SPI_PROTOCOL_COUNT
} rx_spi_protocol_e;

View File

@ -130,10 +130,12 @@
#define USE_RX_SPI
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
#define USE_RX_FRSKY_SPI_TELEMETRY
#define USE_RX_SFHSS_SPI
#define USE_RX_REDPINE_SPI
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY
#define RX_SPI_INSTANCE SPI2
#define RX_NSS_PIN SPI2_NSS_PIN
#define RX_SPI_EXTI_PIN PA8

View File

@ -21,6 +21,7 @@ TARGET_SRC += \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c
rx/cc2500_sfhss.c \
rx/cc2500_redpine.c
endif
endif

View File

@ -114,6 +114,7 @@
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define USE_RX_REDPINE_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY
@ -133,6 +134,7 @@
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define USE_RX_REDPINE_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY
#endif

View File

@ -10,9 +10,12 @@ TARGET_SRC = \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c
rx/cc2500_sfhss.c \
rx/cc2500_redpine.c
ifeq ($(TARGET), CRAZYBEEF4FS)
TARGET_SRC += \
drivers/rx/rx_a7105.c \
rx/a7105_flysky.c
endif

View File

@ -22,6 +22,19 @@
#define TARGET_BOARD_IDENTIFIER "MIF3"
#undef USE_SERIAL_RX
#undef USE_CRSF_CMS_TELEMETRY
#undef USE_TELEMETRY_CRSF
#undef USE_TELEMETRY_HOTT
#undef USE_TELEMETRY_IBUS
#undef USE_TELEMETRY_IBUS_EXTENDED
#undef USE_TELEMETRY_JETIEXBUS
#undef USE_TELEMETRY_LTM
#undef USE_TELEMETRY_MAVLINK
#undef USE_TELEMETRY_SRXL
#undef USE_PWM
#undef USE_GYRO_OVERFLOW_CHECK
#define LED0_PIN PB5
@ -97,6 +110,7 @@
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define USE_RX_REDPINE_SPI
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY

View File

@ -12,4 +12,5 @@ TARGET_SRC = \
rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c
rx/cc2500_sfhss.c \
rx/cc2500_redpine.c

View File

@ -239,6 +239,7 @@
#define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define USE_RX_REDPINE_SPI
#define USE_RX_FRSKY_SPI_TELEMETRY
#define USE_RX_CC2500_SPI_PA_LNA
#define USE_RX_CC2500_SPI_DIVERSITY

View File

@ -35,6 +35,7 @@ TARGET_SRC = \
rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c \
rx/cc2500_redpine.c \
rx/a7105_flysky.c \
rx/cyrf6936_spektrum.c \
drivers/rx/rx_cc2500.c \

View File

@ -142,7 +142,7 @@
#undef USE_VTX_TABLE
#endif
#if defined(USE_RX_FRSKY_SPI_D) || defined(USE_RX_FRSKY_SPI_X)
#if defined(USE_RX_FRSKY_SPI_D) || defined(USE_RX_FRSKY_SPI_X) || defined(USE_RX_REDPINE_SPI)
#define USE_RX_CC2500
#define USE_RX_FRSKY_SPI
#endif