Skip to content

Commit

Permalink
Initial FrSky ACCST V2.1.x support
Browse files Browse the repository at this point in the history
  • Loading branch information
MJ666 authored and McGiverGim committed Dec 22, 2022
1 parent 87b9155 commit cc98c09
Show file tree
Hide file tree
Showing 10 changed files with 282 additions and 151 deletions.
7 changes: 5 additions & 2 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,10 @@ static const char * const lookupTableRxSpi[] = {
"KN",
"SFHSS",
"SPEKTRUM",
"FRSKY_X_LBT"
"FRSKY_X_LBT",
"REDPINE",
"FRSKY_X_V2",
"FRSKY_X_LBT_V2",
};
#endif

Expand Down Expand Up @@ -1429,7 +1432,7 @@ const clivalue_t valueTable[] = {

#ifdef USE_RX_FRSKY_SPI
{ "frsky_spi_autobind", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, autoBind) },
{ "frsky_spi_tx_id", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 2, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, bindTxId) },
{ "frsky_spi_tx_id", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 3, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, bindTxId) },
{ "frsky_spi_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -127, 127 }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, bindOffset) },
{ "frsky_spi_bind_hop_data", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 50, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, bindHopData) },
{ "frsky_x_rx_num", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, rxNum) },
Expand Down
4 changes: 2 additions & 2 deletions src/main/pg/rx_spi_cc2500.c
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

#include "rx_spi_cc2500.h"

PG_REGISTER_WITH_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig, PG_RX_CC2500_SPI_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig, PG_RX_CC2500_SPI_CONFIG, 2);

#if defined(RX_CC2500_SPI_DISABLE_CHIP_DETECTION)
#define CC2500_SPI_CHIP_DETECTION false
Expand All @@ -39,7 +39,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig, PG_RX_CC

PG_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig,
.autoBind = false,
.bindTxId = {0, 0},
.bindTxId = {0, 0, 0},
.bindOffset = 0,
.bindHopData = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
Expand Down
2 changes: 1 addition & 1 deletion src/main/pg/rx_spi_cc2500.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ typedef enum {

typedef struct rxCc2500SpiConfig_s {
uint8_t autoBind;
uint8_t bindTxId[2];
uint8_t bindTxId[3];
int8_t bindOffset;
uint8_t bindHopData[50];
uint8_t rxNum;
Expand Down
222 changes: 127 additions & 95 deletions src/main/rx/cc2500_frsky_shared.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,10 @@

#include "cc2500_frsky_shared.h"

static rx_spi_protocol_e spiProtocol;
rx_spi_protocol_e spiProtocol;

static timeMs_t start_time;
static uint8_t packetLength;
static uint8_t protocolState;

uint32_t missingPackets;
Expand All @@ -59,8 +60,8 @@ timeDelta_t timeoutUs;
static uint8_t calData[255][3];
static timeMs_t timeTunedMs;
uint8_t listLength;
static uint8_t bindIdx;
static int8_t bindOffset;
static uint16_t bindState;
static int8_t bindOffset, bindOffset_min, bindOffset_max;

typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState);
typedef rx_spi_received_e processFrameFn(uint8_t * const packet);
Expand All @@ -74,7 +75,7 @@ const cc2500RegisterConfigElement_t cc2500FrskyBaseConfig[] =
{
{ CC2500_02_IOCFG0, 0x01 },
{ CC2500_18_MCSM0, 0x18 },
{ CC2500_07_PKTCTRL1, 0x04 },
{ CC2500_07_PKTCTRL1, 0x05 },
{ CC2500_3E_PATABLE, 0xFF },
{ CC2500_0C_FSCTRL0, 0x00 },
{ CC2500_0D_FREQ2, 0x5C },
Expand Down Expand Up @@ -141,6 +142,18 @@ const cc2500RegisterConfigElement_t cc2500FrskyXLbtConfig[] =
{ CC2500_15_DEVIATN, 0x53 }
};

const cc2500RegisterConfigElement_t cc2500FrskyXV2Config[] =
{
{ CC2500_17_MCSM1, 0x0E },
{ CC2500_08_PKTCTRL0, 0x05 },
{ CC2500_11_MDMCFG3, 0x84 },
};

const cc2500RegisterConfigElement_t cc2500FrskyXLbtV2Config[] =
{
{ CC2500_08_PKTCTRL0, 0x05 },
};

static void initialise() {
cc2500Reset();

Expand All @@ -158,6 +171,16 @@ static void initialise() {
case RX_SPI_FRSKY_X_LBT:
cc2500ApplyRegisterConfig(cc2500FrskyXLbtConfig, sizeof(cc2500FrskyXLbtConfig));

break;
case RX_SPI_FRSKY_X_V2:
cc2500ApplyRegisterConfig(cc2500FrskyXConfig, sizeof(cc2500FrskyXConfig));
cc2500ApplyRegisterConfig(cc2500FrskyXV2Config, sizeof(cc2500FrskyXV2Config));

break;
case RX_SPI_FRSKY_X_LBT_V2:
cc2500ApplyRegisterConfig(cc2500FrskyXLbtConfig, sizeof(cc2500FrskyXLbtConfig));
cc2500ApplyRegisterConfig(cc2500FrskyXLbtV2Config, sizeof(cc2500FrskyXLbtV2Config));

break;
default:

Expand Down Expand Up @@ -207,29 +230,34 @@ static void initTuneRx(void)
cc2500Strobe(CC2500_SRX);
}

static bool tuneRx(uint8_t *packet)
static bool isValidBindPacket(uint8_t *packet)
{
if (bindOffset >= 126) {
bindOffset = -126;
if (spiProtocol == RX_SPI_FRSKY_D || spiProtocol == RX_SPI_FRSKY_X_V2 || spiProtocol == RX_SPI_FRSKY_X_LBT_V2) {
if (!(packet[packetLength - 1] & 0x80)) {
return false;
}
}
if ((millis() - timeTunedMs) > 50) {
if ((packet[0] == packetLength - 3) && (packet[1] == 0x03) && (packet[2] == 0x01)) {
return true;
}

return false;
}

static bool tuneRx(uint8_t *packet, int8_t inc)
{
if ((millis() - timeTunedMs) > 50 || bindOffset == 126 || bindOffset == -126) {
timeTunedMs = millis();
bindOffset += 5;
bindOffset += inc;
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
cc2500Strobe(CC2500_SRX);
}
if (rxSpiGetExtiState()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
uint8_t Lqi = packet[ccLen - 1] & 0x7F;
// higher lqi represent better link quality
if (Lqi > 50) {
rxCc2500SpiConfigMutable()->bindOffset = bindOffset;
return true;
}
}
if (ccLen >= packetLength) {
cc2500ReadFifo(packet, packetLength);
if (isValidBindPacket(packet)) {
return true;
}
}
}
Expand All @@ -249,29 +277,73 @@ static void initGetBind(void)

cc2500Strobe(CC2500_SRX);
listLength = 0;
bindIdx = 0x05;
bindState = 0;
}

static bool getBind1(uint8_t *packet)
static void generateV2HopData(uint16_t id)
{
uint8_t inc = (id % 46) + 1; // Increment
if (inc == 12 || inc == 35) inc++; // Exception list from dumps
uint8_t offset = id % 5; // Start offset

uint8_t channel;
for (uint8_t i = 0; i < 47; i++) {
channel = 5 * ((uint16_t)(inc * i) % 47) + offset; // Exception list from dumps
if (spiProtocol == RX_SPI_FRSKY_X_LBT_V2) { // LBT or FCC
// LBT
if (channel <=1 || channel == 43 || channel == 44 || channel == 87 || channel == 88 || channel == 129 || channel == 130 || channel == 173 || channel == 174) {
channel += 2;
}
else if (channel == 216 || channel == 217 || channel == 218) {
channel += 3;
}
} else {
// FCC
if (channel == 3 || channel == 4 || channel == 46 || channel == 47 || channel == 90 || channel == 91 || channel == 133 || channel == 134 || channel == 176 || channel == 177 || channel == 220 || channel == 221) {
channel += 2;
}
}
rxCc2500SpiConfigMutable()->bindHopData[i] = channel; // Store
}
rxCc2500SpiConfigMutable()->bindHopData[47] = 0; //Bind freq
rxCc2500SpiConfigMutable()->bindHopData[48] = 0;
rxCc2500SpiConfigMutable()->bindHopData[49] = 0;
}

static bool getBind(uint8_t *packet)
{
// len|bind |tx
// id|03|01|idx|h0|h1|h2|h3|h4|00|00|00|00|00|00|00|00|00|00|00|00|00|00|00|CHK1|CHK2|RSSI|LQI/CRC|
// Start by getting bind packet 0 and the txid
if (rxSpiGetExtiState()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
if (ccLen >= packetLength) {
cc2500ReadFifo(packet, packetLength);
if (isValidBindPacket(packet)) {
if (spiProtocol == RX_SPI_FRSKY_X_V2 || spiProtocol == RX_SPI_FRSKY_X_LBT_V2) {
for (uint8_t i = 3; i < packetLength - 4; i++) {
packet[i] ^= 0xA7;
}
rxCc2500SpiConfigMutable()->bindTxId[0] = packet[3];
rxCc2500SpiConfigMutable()->bindTxId[1] = packet[4];
rxCc2500SpiConfigMutable()->bindTxId[2] = packet[5];
rxCc2500SpiConfigMutable()->rxNum = packet[6];
generateV2HopData((packet[4] << 8) + packet[3]);
listLength = 47;

return true;
} else {
if (packet[5] == 0x00) {
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];
}

rxCc2500SpiConfigMutable()->bindTxId[2] = packet[11];
rxCc2500SpiConfigMutable()->rxNum = packet[12];
}
for (uint8_t n = 0; n < 5; n++) {
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = (packet[5] + n) >= 47 ? 0 : packet[6 + n];
}
bindState |= 1 << (packet[5] / 5);
if (bindState == 0x3FF) {
listLength = 47;

return true;
}
Expand All @@ -283,57 +355,6 @@ static bool getBind1(uint8_t *packet)
return false;
}

static bool getBind2(uint8_t *packet)
{
if (bindIdx <= 120) {
if (rxSpiGetExtiState()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) {
cc2500ReadFifo(packet, ccLen);
if (packet[ccLen - 1] & 0x80) {
if (packet[2] == 0x01) {
if ((packet[3] == rxCc2500SpiConfig()->bindTxId[0]) &&
(packet[4] == rxCc2500SpiConfig()->bindTxId[1])) {
if (packet[5] == bindIdx) {
#if defined(DJTS)
if (packet[5] == 0x2D) {
for (uint8_t i = 0; i < 2; i++) {
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i];
}
listLength = 47;

return true;
}
#endif

for (uint8_t n = 0; n < 5; n++) {
if (packet[6 + n] == packet[ccLen - 3] || (packet[6 + n] == 0)) {
if (bindIdx >= 0x2D) {
listLength = packet[5] + n;

return true;
}
}

rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
}

bindIdx = bindIdx + 5;

return false;
}
}
}
}
}
}

return false;
} else {
return true;
}
}

rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
{
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
Expand All @@ -352,29 +373,38 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
rxSpiLedOn();
initTuneRx();

protocolState = STATE_BIND_TUNING;
protocolState = STATE_BIND_TUNING_LOW;
} else {
protocolState = STATE_STARTING;
}

break;
case STATE_BIND_TUNING:
if (tuneRx(packet)) {
initGetBind();
initialiseData(true);
case STATE_BIND_TUNING_LOW:
if (tuneRx(packet, 2)) {
bindOffset_min = bindOffset;
bindOffset = 126;

protocolState = STATE_BIND_BINDING1;
protocolState = STATE_BIND_TUNING_HIGH;
}

break;
case STATE_BIND_BINDING1:
if (getBind1(packet)) {
protocolState = STATE_BIND_BINDING2;
case STATE_BIND_TUNING_HIGH:
if (tuneRx(packet, -2)) {
bindOffset_max = bindOffset;
bindOffset = ((int16_t)bindOffset_max + (int16_t)bindOffset_min) / 2;
rxCc2500SpiConfigMutable()->bindOffset = bindOffset;
initGetBind();
initialiseData(true);

if(bindOffset_min < bindOffset_max)
protocolState = STATE_BIND_BINDING;
else
protocolState = STATE_BIND;
}

break;
case STATE_BIND_BINDING2:
if (getBind2(packet)) {
case STATE_BIND_BINDING:
if (getBind(packet)) {
cc2500Strobe(CC2500_SIDLE);

protocolState = STATE_BIND_COMPLETE;
Expand Down Expand Up @@ -462,14 +492,16 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeS
break;
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
case RX_SPI_FRSKY_X_V2:
case RX_SPI_FRSKY_X_LBT_V2:
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_FRSKY_X;

handlePacket = frSkyXHandlePacket;
#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
processFrame = frSkyXProcessFrame;
#endif
setRcData = frSkyXSetRcData;
frSkyXInit(spiProtocol);
packetLength = frSkyXInit();

break;
default:
Expand Down
Loading

0 comments on commit cc98c09

Please sign in to comment.