mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Merge pull request #7339 from phobos-/frsky-x-lbt
Implemented FRSKY X EU LBT
This commit is contained in:
commit
ec083dfa9e
8 changed files with 120 additions and 84 deletions
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#define RX_SPI_MAX_PAYLOAD_SIZE 32
|
#define RX_SPI_MAX_PAYLOAD_SIZE 35
|
||||||
|
|
||||||
struct rxSpiConfig_s;
|
struct rxSpiConfig_s;
|
||||||
|
|
||||||
|
|
|
@ -2622,6 +2622,7 @@ void cliRxSpiBind(char *cmdline){
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_RX_FRSKY_SPI_X)
|
#if defined(USE_RX_FRSKY_SPI_X)
|
||||||
case RX_SPI_FRSKY_X:
|
case RX_SPI_FRSKY_X:
|
||||||
|
case RX_SPI_FRSKY_X_LBT:
|
||||||
#endif
|
#endif
|
||||||
#endif // USE_RX_FRSKY_SPI
|
#endif // USE_RX_FRSKY_SPI
|
||||||
#ifdef USE_RX_SFHSS_SPI
|
#ifdef USE_RX_SFHSS_SPI
|
||||||
|
|
|
@ -228,6 +228,7 @@ static const char * const lookupTableRxSpi[] = {
|
||||||
"INAV",
|
"INAV",
|
||||||
"FRSKY_D",
|
"FRSKY_D",
|
||||||
"FRSKY_X",
|
"FRSKY_X",
|
||||||
|
"FRSKY_X_LBT",
|
||||||
"FLYSKY",
|
"FLYSKY",
|
||||||
"FLYSKY_2A",
|
"FLYSKY_2A",
|
||||||
"KN",
|
"KN",
|
||||||
|
|
|
@ -85,14 +85,11 @@ PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig,
|
||||||
static void initialise() {
|
static void initialise() {
|
||||||
cc2500Reset();
|
cc2500Reset();
|
||||||
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
|
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
|
||||||
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
|
|
||||||
cc2500WriteReg(CC2500_18_MCSM0, 0x18);
|
cc2500WriteReg(CC2500_18_MCSM0, 0x18);
|
||||||
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04);
|
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04);
|
||||||
cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
|
cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
|
||||||
cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
|
cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
|
||||||
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
|
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
|
||||||
cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
|
|
||||||
cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
|
|
||||||
cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
|
cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
|
||||||
cc2500WriteReg(CC2500_14_MDMCFG0, 0x7A);
|
cc2500WriteReg(CC2500_14_MDMCFG0, 0x7A);
|
||||||
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
|
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
|
||||||
|
@ -115,6 +112,9 @@ static void initialise() {
|
||||||
|
|
||||||
switch (spiProtocol) {
|
switch (spiProtocol) {
|
||||||
case RX_SPI_FRSKY_D:
|
case RX_SPI_FRSKY_D:
|
||||||
|
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
|
||||||
|
cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
|
||||||
|
cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
|
||||||
cc2500WriteReg(CC2500_06_PKTLEN, 0x19);
|
cc2500WriteReg(CC2500_06_PKTLEN, 0x19);
|
||||||
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05);
|
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05);
|
||||||
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
|
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
|
||||||
|
@ -125,6 +125,9 @@ static void initialise() {
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case RX_SPI_FRSKY_X:
|
case RX_SPI_FRSKY_X:
|
||||||
|
cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
|
||||||
|
cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
|
||||||
|
cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
|
||||||
cc2500WriteReg(CC2500_06_PKTLEN, 0x1E);
|
cc2500WriteReg(CC2500_06_PKTLEN, 0x1E);
|
||||||
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
|
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
|
||||||
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A);
|
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A);
|
||||||
|
@ -133,6 +136,19 @@ static void initialise() {
|
||||||
cc2500WriteReg(CC2500_12_MDMCFG2, 0x13);
|
cc2500WriteReg(CC2500_12_MDMCFG2, 0x13);
|
||||||
cc2500WriteReg(CC2500_15_DEVIATN, 0x51);
|
cc2500WriteReg(CC2500_15_DEVIATN, 0x51);
|
||||||
|
|
||||||
|
break;
|
||||||
|
case RX_SPI_FRSKY_X_LBT:
|
||||||
|
cc2500WriteReg(CC2500_17_MCSM1, 0x0E);
|
||||||
|
cc2500WriteReg(CC2500_0E_FREQ1, 0x80);
|
||||||
|
cc2500WriteReg(CC2500_0F_FREQ0, 0x00);
|
||||||
|
cc2500WriteReg(CC2500_06_PKTLEN, 0x23);
|
||||||
|
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
|
||||||
|
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
|
||||||
|
cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B);
|
||||||
|
cc2500WriteReg(CC2500_11_MDMCFG3, 0xF8);
|
||||||
|
cc2500WriteReg(CC2500_12_MDMCFG2, 0x03);
|
||||||
|
cc2500WriteReg(CC2500_15_DEVIATN, 0x53);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|
||||||
|
@ -420,11 +436,12 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntime
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case RX_SPI_FRSKY_X:
|
case RX_SPI_FRSKY_X:
|
||||||
|
case RX_SPI_FRSKY_X_LBT:
|
||||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
|
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
|
||||||
|
|
||||||
handlePacket = frSkyXHandlePacket;
|
handlePacket = frSkyXHandlePacket;
|
||||||
setRcData = frSkyXSetRcData;
|
setRcData = frSkyXSetRcData;
|
||||||
frSkyXInit();
|
frSkyXInit(spiProtocol);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
|
|
@ -152,8 +152,10 @@ static bool telemetryEnabled = false;
|
||||||
#endif
|
#endif
|
||||||
#endif // USE_RX_FRSKY_SPI_TELEMETRY
|
#endif // USE_RX_FRSKY_SPI_TELEMETRY
|
||||||
|
|
||||||
|
static uint8_t packetLength;
|
||||||
|
static uint16_t telemetryDelayUs;
|
||||||
|
|
||||||
static uint16_t calculateCrc(uint8_t *data, uint8_t len) {
|
static uint16_t calculateCrc(const uint8_t *data, uint8_t len) {
|
||||||
uint16_t crc = 0;
|
uint16_t crc = 0;
|
||||||
for (unsigned i = 0; i < len; i++) {
|
for (unsigned i = 0; i < len; i++) {
|
||||||
crc = (crc << 8) ^ (crcTable[((uint8_t)(crc >> 8) ^ *data++) & 0xFF]);
|
crc = (crc << 8) ^ (crcTable[((uint8_t)(crc >> 8) ^ *data++) & 0xFF]);
|
||||||
|
@ -294,6 +296,19 @@ void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool isValidPacket(const uint8_t *packet)
|
||||||
|
{
|
||||||
|
uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
|
||||||
|
if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
|
||||||
|
(packet[0] == packetLength - 3) &&
|
||||||
|
(packet[1] == rxFrSkySpiConfig()->bindTxId[0]) &&
|
||||||
|
(packet[2] == rxFrSkySpiConfig()->bindTxId[1]) &&
|
||||||
|
(rxFrSkySpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxFrSkySpiConfig()->rxNum)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState)
|
rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState)
|
||||||
{
|
{
|
||||||
static unsigned receiveTelemetryRetryCount = 0;
|
static unsigned receiveTelemetryRetryCount = 0;
|
||||||
|
@ -347,18 +362,9 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
case STATE_DATA:
|
case STATE_DATA:
|
||||||
if (cc2500getGdo() && (frameReceived == false)){
|
if (cc2500getGdo() && (frameReceived == false)){
|
||||||
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
|
||||||
ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; // read 2 times to avoid reading errors
|
if (ccLen >= packetLength) {
|
||||||
if (ccLen > 32) {
|
cc2500ReadFifo(packet, packetLength);
|
||||||
ccLen = 32;
|
if (isValidPacket(packet)) {
|
||||||
}
|
|
||||||
if (ccLen) {
|
|
||||||
cc2500ReadFifo(packet, ccLen);
|
|
||||||
uint16_t lcrc= calculateCrc(&packet[3], (ccLen - 7));
|
|
||||||
if((lcrc >> 8) == packet[ccLen-4] && (lcrc&0x00FF) == packet[ccLen - 3]){ // check calculateCrc
|
|
||||||
if (packet[0] == 0x1D) {
|
|
||||||
if ((packet[1] == rxFrSkySpiConfig()->bindTxId[0]) &&
|
|
||||||
(packet[2] == rxFrSkySpiConfig()->bindTxId[1]) &&
|
|
||||||
(rxFrSkySpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxFrSkySpiConfig()->rxNum)) {
|
|
||||||
missingPackets = 0;
|
missingPackets = 0;
|
||||||
timeoutUs = 1;
|
timeoutUs = 1;
|
||||||
receiveDelayUs = 0;
|
receiveDelayUs = 0;
|
||||||
|
@ -377,7 +383,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
telemetryReceived = true; // now telemetry can be sent
|
telemetryReceived = true; // now telemetry can be sent
|
||||||
skipChannels = false;
|
skipChannels = false;
|
||||||
}
|
}
|
||||||
cc2500setRssiDbm(packet[ccLen - 2]);
|
cc2500setRssiDbm(packet[packetLength - 2]);
|
||||||
|
|
||||||
telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
|
telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
|
||||||
|
|
||||||
|
@ -406,7 +412,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
receiveTelemetryRetryCount = 0;
|
receiveTelemetryRetryCount = 0;
|
||||||
|
|
||||||
remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
|
remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
|
||||||
uint8_t remoteNextAckId;
|
uint8_t remoteNextAckId = remoteToAckId;
|
||||||
while (telemetryRxBuffer[remoteToAckId].needsProcessing && remoteToAckId != remoteAckId) {
|
while (telemetryRxBuffer[remoteToAckId].needsProcessing && remoteToAckId != remoteAckId) {
|
||||||
remoteNextAckId = remoteToAckId;
|
remoteNextAckId = remoteToAckId;
|
||||||
remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
|
remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
|
||||||
|
@ -428,8 +434,6 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
packetTimerUs = micros();
|
packetTimerUs = micros();
|
||||||
frameReceived = true; // no need to process frame again.
|
frameReceived = true; // no need to process frame again.
|
||||||
}
|
}
|
||||||
}
|
|
||||||
}
|
|
||||||
if (!frameReceived) {
|
if (!frameReceived) {
|
||||||
packetErrors++;
|
packetErrors++;
|
||||||
DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_BAD_FRAME, packetErrors);
|
DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_BAD_FRAME, packetErrors);
|
||||||
|
@ -453,7 +457,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
break;
|
break;
|
||||||
#ifdef USE_RX_FRSKY_SPI_TELEMETRY
|
#ifdef USE_RX_FRSKY_SPI_TELEMETRY
|
||||||
case STATE_TELEMETRY:
|
case STATE_TELEMETRY:
|
||||||
if(cmpTimeUs(micros(), packetTimerUs) >= receiveDelayUs + 400) { // if received or not received in this time sent telemetry data
|
if (cmpTimeUs(micros(), packetTimerUs) >= receiveDelayUs + telemetryDelayUs) { // if received or not received in this time sent telemetry data
|
||||||
cc2500Strobe(CC2500_SIDLE);
|
cc2500Strobe(CC2500_SIDLE);
|
||||||
cc2500SetPower(6);
|
cc2500SetPower(6);
|
||||||
cc2500Strobe(CC2500_SFRX);
|
cc2500Strobe(CC2500_SFRX);
|
||||||
|
@ -524,7 +528,6 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
}
|
}
|
||||||
missingPackets++;
|
missingPackets++;
|
||||||
DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_MISSING_PACKETS, missingPackets);
|
DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_MISSING_PACKETS, missingPackets);
|
||||||
|
|
||||||
*protocolState = STATE_DATA;
|
*protocolState = STATE_DATA;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -533,8 +536,20 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void frSkyXInit(void)
|
void frSkyXInit(const rx_spi_protocol_e spiProtocol)
|
||||||
{
|
{
|
||||||
|
switch(spiProtocol) {
|
||||||
|
case RX_SPI_FRSKY_X:
|
||||||
|
packetLength = 32;
|
||||||
|
telemetryDelayUs = 400;
|
||||||
|
break;
|
||||||
|
case RX_SPI_FRSKY_X_LBT:
|
||||||
|
packetLength = 35;
|
||||||
|
telemetryDelayUs = 1400;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
#if defined(USE_TELEMETRY_SMARTPORT)
|
#if defined(USE_TELEMETRY_SMARTPORT)
|
||||||
if (featureIsEnabled(FEATURE_TELEMETRY)) {
|
if (featureIsEnabled(FEATURE_TELEMETRY)) {
|
||||||
telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame);
|
telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame);
|
||||||
|
|
|
@ -27,5 +27,5 @@
|
||||||
|
|
||||||
void frSkyXSetRcData(uint16_t *rcData, const uint8_t *payload);
|
void frSkyXSetRcData(uint16_t *rcData, const uint8_t *payload);
|
||||||
|
|
||||||
void frSkyXInit(void);
|
void frSkyXInit(const rx_spi_protocol_e spiProtocol);
|
||||||
rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState);
|
rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState);
|
||||||
|
|
|
@ -132,6 +132,7 @@ STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_RX_FRSKY_SPI_X)
|
#if defined(USE_RX_FRSKY_SPI_X)
|
||||||
case RX_SPI_FRSKY_X:
|
case RX_SPI_FRSKY_X:
|
||||||
|
case RX_SPI_FRSKY_X_LBT:
|
||||||
#endif
|
#endif
|
||||||
protocolInit = frSkySpiInit;
|
protocolInit = frSkySpiInit;
|
||||||
protocolDataReceived = frSkySpiDataReceived;
|
protocolDataReceived = frSkySpiDataReceived;
|
||||||
|
|
|
@ -36,6 +36,7 @@ typedef enum {
|
||||||
RX_SPI_NRF24_INAV,
|
RX_SPI_NRF24_INAV,
|
||||||
RX_SPI_FRSKY_D,
|
RX_SPI_FRSKY_D,
|
||||||
RX_SPI_FRSKY_X,
|
RX_SPI_FRSKY_X,
|
||||||
|
RX_SPI_FRSKY_X_LBT,
|
||||||
RX_SPI_A7105_FLYSKY,
|
RX_SPI_A7105_FLYSKY,
|
||||||
RX_SPI_A7105_FLYSKY_2A,
|
RX_SPI_A7105_FLYSKY_2A,
|
||||||
RX_SPI_NRF24_KN,
|
RX_SPI_NRF24_KN,
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue