Added configurability for FlySky.

This commit is contained in:
mikeller 2019-03-02 23:54:02 +13:00
parent 86a5a30267
commit 96d5b5dcac
7 changed files with 37 additions and 35 deletions

View File

@ -1412,7 +1412,6 @@ const clivalue_t valueTable[] = {
#ifdef USE_RX_FLYSKY
{ "flysky_spi_tx_id", VAR_UINT32 | MASTER_VALUE, .config.u32Max = UINT32_MAX, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, txId) },
{ "flysky_spi_rf_channels", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 16, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, rfChannelMap) },
{ "flysky_spi_protocol", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, protocol) },
#endif
};

View File

@ -35,9 +35,7 @@
#include "drivers/rx/rx_spi.h"
#include "drivers/time.h"
#ifdef RX_PA_TXEN_PIN
static IO_t txEnIO = IO_NONE;
#endif
static IO_t rxIntIO = IO_NONE;
static extiCallbackRec_t a7105extiCallbackRec;
@ -48,26 +46,28 @@ void a7105extiHandler(extiCallbackRec_t* cb)
{
UNUSED(cb);
if (IORead (rxIntIO) != 0) {
if (IORead(rxIntIO) != 0) {
timeEvent = micros();
occurEvent = true;
}
}
void A7105Init(uint32_t id)
void A7105Init(uint32_t id, IO_t extiPin, IO_t txEnPin)
{
spiDeviceByInstance(RX_SPI_INSTANCE);
rxIntIO = IOGetByTag(IO_TAG(RX_EXTI_PIN)); /* config receiver IRQ pin */
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
rxIntIO = extiPin; /* config receiver IRQ pin */
IOInit(rxIntIO, OWNER_RX_SPI, 0);
EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler);
EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_RISING);
EXTIEnable(rxIntIO, false);
#ifdef RX_PA_TXEN_PIN
txEnIO = IOGetByTag(IO_TAG(RX_PA_TXEN_PIN));
IOInit(txEnIO, OWNER_RX_SPI_CS, 0);
IOConfigGPIO(txEnIO, IOCFG_OUT_PP);
#endif
if (txEnPin) {
txEnIO = txEnPin;
IOInit(txEnIO, OWNER_RX_SPI_CS, 0);
IOConfigGPIO(txEnIO, IOCFG_OUT_PP);
} else {
txEnIO = IO_NONE;
}
A7105SoftReset();
A7105WriteID(id);
@ -135,13 +135,13 @@ void A7105Strobe(A7105State_t state)
EXTIEnable(rxIntIO, false);
}
#ifdef RX_PA_TXEN_PIN
if (A7105_TX == state) {
IOHi(txEnIO); /* enable PA */
} else {
IOLo(txEnIO); /* disable PA */
if (txEnIO) {
if (A7105_TX == state) {
IOHi(txEnIO); /* enable PA */
} else {
IOLo(txEnIO); /* disable PA */
}
}
#endif
rxSpiWriteByte((uint8_t)state);
}

View File

@ -97,7 +97,7 @@ typedef enum {
#define A7105_MODE_TRSR 0x02 // [0]: RX state. [1]: TX state. Serviceable if TRER=1 (TRX is enable).
#define A7105_MODE_TRER 0x01 // [0]: TRX is disabled. [1]: TRX is enabled.
void A7105Init(uint32_t id);
void A7105Init(uint32_t id, IO_t extiPin, IO_t txEnPin);
void A7105SoftReset(void);
void A7105Config(const uint8_t *regsTable, uint8_t size);

View File

@ -19,6 +19,7 @@
*/
#include <string.h>
#include "platform.h"
#ifdef USE_RX_FLYSKY
@ -57,8 +58,8 @@
#error "FlySky AFHDS 2A protocol support 14 channel max"
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(flySkyConfig_t, flySkyConfig, PG_FLYSKY_CONFIG, 0);
PG_RESET_TEMPLATE(flySkyConfig_t, flySkyConfig, .txId = 0, .rfChannelMap = {0}, .protocol = 0);
PG_REGISTER_WITH_RESET_TEMPLATE(flySkyConfig_t, flySkyConfig, PG_FLYSKY_CONFIG, 1);
PG_RESET_TEMPLATE(flySkyConfig_t, flySkyConfig, .txId = 0, .rfChannelMap = {0});
static const uint8_t flySkyRegs[] = {
0xff, 0x42, 0x00, 0x14, 0x00, 0xff, 0xff, 0x00,
@ -355,12 +356,13 @@ static rx_spi_received_e flySkyReadAndProcess(uint8_t *payload, const uint32_t t
bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
{
protocol = rxSpiConfig->rx_spi_protocol;
if (protocol != flySkyConfig()->protocol) {
PG_RESET(flySkyConfig);
IO_t extiPin = IOGetByTag(rxSpiConfig->extiIoTag);
if (!extiPin) {
return false;
}
protocol = rxSpiConfig->rx_spi_protocol;
rxSpiCommonIOInit(rxSpiConfig);
uint8_t startRxChannel;
@ -370,13 +372,13 @@ bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRu
timings = &flySky2ATimings;
rxId = U_ID_0 ^ U_ID_1 ^ U_ID_2;
startRxChannel = flySky2ABindChannels[0];
A7105Init(0x5475c52A);
A7105Init(0x5475c52A, extiPin, IO_NONE);
A7105Config(flySky2ARegs, sizeof(flySky2ARegs));
} else {
rxRuntimeConfig->channelCount = FLYSKY_CHANNEL_COUNT;
timings = &flySkyTimings;
startRxChannel = 0;
A7105Init(0x5475c52A);
A7105Init(0x5475c52A, extiPin, IO_NONE);
A7105Config(flySkyRegs, sizeof(flySkyRegs));
}
@ -459,7 +461,6 @@ rx_spi_received_e flySkyDataReceived(uint8_t *payload)
bound = true;
flySkyConfigMutable()->txId = txId; // store TXID
memcpy (flySkyConfigMutable()->rfChannelMap, rfChannelMap, FLYSKY_FREQUENCY_COUNT);// store channel map
flySkyConfigMutable()->protocol = protocol;
writeEEPROM();
}
rxSpiLedBlinkBind();

View File

@ -26,7 +26,6 @@
typedef struct flySkyConfig_s {
uint32_t txId;
uint8_t rfChannelMap[16];
rx_spi_protocol_e protocol;
} flySkyConfig_t;
PG_DECLARE(flySkyConfig_t, flySkyConfig);

View File

@ -126,10 +126,6 @@ bool cc2500SpiInit(void)
UNUSED(cc2500SpiDetect);
#endif
if (rssiSource == RSSI_SOURCE_NONE) {
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
}
// gpio init here
gdoPin = IOGetByTag(rxSpiConfig()->extiIoTag);
@ -151,6 +147,8 @@ bool cc2500SpiInit(void)
txEnPin = IOGetByTag(rxCc2500SpiConfig()->txEnIoTag);
IOInit(txEnPin, OWNER_RX_SPI, 0);
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
} else {
txEnPin = IO_NONE;
}
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
if (rxCc2500SpiConfig()->antSelIoTag) {
@ -159,6 +157,8 @@ bool cc2500SpiInit(void)
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
IOHi(antSelPin);
} else {
antSelPin = IO_NONE;
}
#endif
#endif // USE_RX_CC2500_SPI_PA_LNA
@ -167,6 +167,10 @@ bool cc2500SpiInit(void)
cc2500TxDisable();
#endif // USE_RX_CC2500_SPI_PA_LNA
if (rssiSource == RSSI_SOURCE_NONE) {
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
}
return true;
}
#endif

View File

@ -110,8 +110,7 @@
#define USE_RX_CC2500_SPI_PA_LNA
#define USE_RX_CC2500_SPI_DIVERSITY
//TODO: Make this work with runtime configurability
//#define USE_RX_FLYSKY
#define USE_RX_FLYSKY
//TODO: Make this work with runtime configurability
//#define USE_RX_SPEKTRUM