Skip to content

Commit

Permalink
Added flysky spi rx specific cli commands
Browse files Browse the repository at this point in the history
  • Loading branch information
phobos- committed Jan 16, 2019
1 parent e0fc930 commit 305e423
Show file tree
Hide file tree
Showing 9 changed files with 47 additions and 41 deletions.
24 changes: 12 additions & 12 deletions src/main/drivers/rx/rx_a7105.c
Expand Up @@ -54,7 +54,7 @@ void a7105extiHandler(extiCallbackRec_t* cb)
}
}

void A7105Init (uint32_t id)
void A7105Init(uint32_t id)
{
spiDeviceByInstance(RX_SPI_INSTANCE);
rxIntIO = IOGetByTag(IO_TAG(RX_IRQ_PIN)); /* config receiver IRQ pin */
Expand All @@ -73,12 +73,12 @@ void A7105Init (uint32_t id)
A7105WriteID(id);
}

void A7105Config (const uint8_t *regsTable, uint8_t size)
void A7105Config(const uint8_t *regsTable, uint8_t size)
{
if (regsTable) {
uint32_t timeout = 1000;
unsigned timeout = 1000;

for (uint8_t i = 0; i < size; i++) {
for (unsigned i = 0; i < size; i++) {
if (regsTable[i] != 0xFF) {
A7105WriteReg ((A7105Reg_t)i, regsTable[i]);
}
Expand All @@ -98,7 +98,7 @@ void A7105Config (const uint8_t *regsTable, uint8_t size)
}
}

bool A7105RxTxFinished (uint32_t *timeStamp) {
bool A7105RxTxFinished(uint32_t *timeStamp) {
bool result = false;

if (occurEvent) {
Expand All @@ -112,22 +112,22 @@ bool A7105RxTxFinished (uint32_t *timeStamp) {
return result;
}

void A7105SoftReset (void)
void A7105SoftReset(void)
{
rxSpiWriteCommand((uint8_t)A7105_00_MODE, 0x00);
}

uint8_t A7105ReadReg (A7105Reg_t reg)
uint8_t A7105ReadReg(A7105Reg_t reg)
{
return rxSpiReadCommand((uint8_t)reg | 0x40, 0xFF);
}

void A7105WriteReg (A7105Reg_t reg, uint8_t data)
void A7105WriteReg(A7105Reg_t reg, uint8_t data)
{
rxSpiWriteCommand((uint8_t)reg, data);
}

void A7105Strobe (A7105State_t state)
void A7105Strobe(A7105State_t state)
{
if (A7105_TX == state || A7105_RX == state) {
EXTIEnable(rxIntIO, true);
Expand Down Expand Up @@ -156,7 +156,7 @@ void A7105WriteID(uint32_t id)
rxSpiWriteCommandMulti((uint8_t)A7105_06_ID_DATA, &data[0], sizeof(data));
}

uint32_t A7105ReadID (void)
uint32_t A7105ReadID(void)
{
uint32_t id;
uint8_t data[4];
Expand All @@ -165,7 +165,7 @@ uint32_t A7105ReadID (void)
return id;
}

void A7105ReadFIFO (uint8_t *data, uint8_t num)
void A7105ReadFIFO(uint8_t *data, uint8_t num)
{
if (data) {
if(num > 64) {
Expand All @@ -177,7 +177,7 @@ void A7105ReadFIFO (uint8_t *data, uint8_t num)
}
}

void A7105WriteFIFO (uint8_t *data, uint8_t num)
void A7105WriteFIFO(uint8_t *data, uint8_t num)
{
if (data) {
if(num > 64) {
Expand Down
11 changes: 9 additions & 2 deletions src/main/interface/settings.c
Expand Up @@ -93,6 +93,7 @@
#include "rx/cc2500_sfhss.h"
#include "rx/spektrum.h"
#include "rx/cyrf6936_spektrum.h"
#include "rx/a7105_flysky.h"

#include "sensors/acceleration.h"
#include "sensors/barometer.h"
Expand Down Expand Up @@ -1234,7 +1235,7 @@ const clivalue_t valueTable[] = {
{ "frsky_spi_tx_id", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 2, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindTxId) },
{ "frsky_spi_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -127, 127 }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindOffset) },
{ "frsky_spi_bind_hop_data", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 50, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindHopData) },
{ "frsky_x_rx_num", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, rxNum) },
{ "frsky_x_rx_num", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, UINT8_MAX }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, rxNum) },
{ "frsky_spi_a1_source", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_FRSKY_SPI_A1_SOURCE }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, a1Source) },
#endif
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
Expand Down Expand Up @@ -1317,7 +1318,7 @@ const clivalue_t valueTable[] = {
{ "mco2_on_pc9", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MCO_CONFIG, offsetof(mcoConfig_t, enabled[1]) },
#endif
#ifdef USE_RX_SPEKTRUM
{ "spektrum_spi_protocol", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_RX_SPEKTRUM_SPI_CONFIG, offsetof(spektrumConfig_t, protocol) },
{ "spektrum_spi_protocol", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, UINT8_MAX }, PG_RX_SPEKTRUM_SPI_CONFIG, offsetof(spektrumConfig_t, protocol) },
{ "spektrum_spi_mfg_id", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 4, PG_RX_SPEKTRUM_SPI_CONFIG, offsetof(spektrumConfig_t, mfgId) },
{ "spektrum_spi_num_channels", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, DSM_MAX_CHANNEL_COUNT }, PG_RX_SPEKTRUM_SPI_CONFIG, offsetof(spektrumConfig_t, numChannels) },
#endif
Expand All @@ -1335,6 +1336,12 @@ const clivalue_t valueTable[] = {
{ "dterm_rpm_notch_q", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 1000 }, PG_RPM_FILTER_CONFIG, offsetof(rpmFilterConfig_t, dterm_rpm_notch_q) },
{ "dterm_rpm_notch_min", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 50, 200 }, PG_RPM_FILTER_CONFIG, offsetof(rpmFilterConfig_t, dterm_rpm_notch_min) },
#endif

#ifdef USE_RX_FLYSKY
{ "flysky_spi_tx_id", VAR_UINT32 | MASTER_VALUE, .config.u32_max = 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.minmax = { 0, UINT8_MAX }, PG_FLYSKY_CONFIG, offsetof(flySkyConfig_t, protocol) },
#endif
};

const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
Expand Down
45 changes: 22 additions & 23 deletions src/main/rx/flysky.c → src/main/rx/a7105_flysky.c
Expand Up @@ -40,14 +40,14 @@
#include "pg/pg_ids.h"
#include "pg/rx_spi.h"

#include "rx/flysky_defs.h"
#include "rx/a7105_flysky_defs.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "rx/rx_spi_common.h"

#include "sensors/battery.h"

#include "flysky.h"
#include "a7105_flysky.h"

#if FLYSKY_CHANNEL_COUNT > MAX_FLYSKY_CHANNEL_COUNT
#error "FlySky AFHDS protocol support 8 channel max"
Expand Down Expand Up @@ -123,15 +123,14 @@ static uint16_t errorRate = 0;
static uint16_t rssi_dBm = 0;
static uint8_t rfChannelMap[FLYSKY_FREQUENCY_COUNT] = {0};


static uint8_t getNextChannel (uint8_t step)
static uint8_t getNextChannel(uint8_t step)
{
static uint8_t channel = 0;
channel = (channel + step) & 0x0F;
return rfChannelMap[channel];
}

static void flySkyCalculateRfChannels (void)
static void flySkyCalculateRfChannels(void)
{
uint32_t channelRow = txId & 0x0F;
uint32_t channelOffset = ((txId & 0xF0) >> 4) + 1;
Expand All @@ -140,20 +139,20 @@ static void flySkyCalculateRfChannels (void)
channelOffset = 9; // from sloped soarer findings, bug in flysky protocol
}

for (uint32_t i = 0; i < FLYSKY_FREQUENCY_COUNT; i++) {
for (unsigned i = 0; i < FLYSKY_FREQUENCY_COUNT; i++) {
rfChannelMap[i] = flySkyRfChannels[channelRow][i] - channelOffset;
}
}

static void resetTimeout (const uint32_t timeStamp)
static void resetTimeout(const uint32_t timeStamp)
{
timeLastPacket = timeStamp;
timeout = timings->firstPacket;
countTimeout = 0;
countPacket++;
}

static void checkTimeout (void)
static void checkTimeout(void)
{
static uint32_t timeMeasuareErrRate = 0;
static uint32_t timeLastTelemetry = 0;
Expand Down Expand Up @@ -189,7 +188,7 @@ static void checkTimeout (void)
}
}

static void checkRSSI (void)
static void checkRSSI(void)
{
static uint8_t buf[FLYSKY_RSSI_SAMPLE_COUNT] = {0};
static int16_t sum = 0;
Expand All @@ -208,12 +207,12 @@ static void checkRSSI (void)
setRssiDirect(tmp, RSSI_SOURCE_RX_PROTOCOL);
}

static bool isValidPacket (const uint8_t *packet) {
static bool isValidPacket(const uint8_t *packet) {
const flySky2ARcDataPkt_t *rcPacket = (const flySky2ARcDataPkt_t*) packet;
return (rcPacket->rxId == rxId && rcPacket->txId == txId);
}

static void buildAndWriteTelemetry (uint8_t *packet)
static void buildAndWriteTelemetry(uint8_t *packet)
{
if (packet) {
static uint8_t bytesToWrite = FLYSKY_2A_PAYLOAD_SIZE; // first time write full packet to buffer a7105
Expand Down Expand Up @@ -245,7 +244,7 @@ static void buildAndWriteTelemetry (uint8_t *packet)
}
}

static rx_spi_received_e flySky2AReadAndProcess (uint8_t *payload, const uint32_t timeStamp)
static rx_spi_received_e flySky2AReadAndProcess(uint8_t *payload, const uint32_t timeStamp)
{
rx_spi_received_e result = RX_SPI_RECEIVED_NONE;
uint8_t packet[FLYSKY_2A_PAYLOAD_SIZE];
Expand All @@ -254,9 +253,9 @@ static rx_spi_received_e flySky2AReadAndProcess (uint8_t *payload, const uint32_
A7105ReadFIFO(packet, bytesToRead);

switch (packet[0]) {
case FLYSKY_2A_PACKET_RC_DATA:
case FLYSKY_2A_PACKET_FS_SETTINGS: // failsafe settings
case FLYSKY_2A_PACKET_SETTINGS: // receiver settings
case FLYSKY_2A_PACKET_RC_DATA:
case FLYSKY_2A_PACKET_FS_SETTINGS: // failsafe settings
case FLYSKY_2A_PACKET_SETTINGS: // receiver settings
if (isValidPacket(packet)) {
checkRSSI();
resetTimeout(timeStamp);
Expand Down Expand Up @@ -284,8 +283,8 @@ static rx_spi_received_e flySky2AReadAndProcess (uint8_t *payload, const uint32_
}
break;

case FLYSKY_2A_PACKET_BIND1:
case FLYSKY_2A_PACKET_BIND2:
case FLYSKY_2A_PACKET_BIND1:
case FLYSKY_2A_PACKET_BIND2:
if (!bound) {
resetTimeout(timeStamp);

Expand All @@ -306,7 +305,7 @@ static rx_spi_received_e flySky2AReadAndProcess (uint8_t *payload, const uint32_
}
break;

default:
default:
break;
}

Expand All @@ -316,7 +315,7 @@ static rx_spi_received_e flySky2AReadAndProcess (uint8_t *payload, const uint32_
return result;
}

static rx_spi_received_e flySkyReadAndProcess (uint8_t *payload, const uint32_t timeStamp)
static rx_spi_received_e flySkyReadAndProcess(uint8_t *payload, const uint32_t timeStamp)
{
rx_spi_received_e result = RX_SPI_RECEIVED_NONE;
uint8_t packet[FLYSKY_PAYLOAD_SIZE];
Expand Down Expand Up @@ -354,7 +353,7 @@ static rx_spi_received_e flySkyReadAndProcess (uint8_t *payload, const uint32_t
return result;
}

bool flySkyInit (const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
{
protocol = rxSpiConfig->rx_spi_protocol;

Expand Down Expand Up @@ -402,19 +401,19 @@ bool flySkyInit (const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxR
return true;
}

void flySkySetRcDataFromPayload (uint16_t *rcData, const uint8_t *payload)
void flySkySetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
{
if (rcData && payload) {
uint32_t channelCount;
channelCount = (protocol == RX_SPI_A7105_FLYSKY_2A) ? (FLYSKY_2A_CHANNEL_COUNT) : (FLYSKY_CHANNEL_COUNT);

for (uint8_t i = 0; i < channelCount; i++) {
for (unsigned i = 0; i < channelCount; i++) {
rcData[i] = payload[2 * i + 1] << 8 | payload [2 * i + 0];
}
}
}

rx_spi_received_e flySkyDataReceived (uint8_t *payload)
rx_spi_received_e flySkyDataReceived(uint8_t *payload)
{
rx_spi_received_e result = RX_SPI_RECEIVED_NONE;
uint32_t timeStamp;
Expand Down
File renamed without changes.
File renamed without changes.
2 changes: 1 addition & 1 deletion src/main/rx/rx_spi.c
Expand Up @@ -46,7 +46,7 @@
#include "rx/nrf24_h8_3d.h"
#include "rx/nrf24_inav.h"
#include "rx/nrf24_kn.h"
#include "rx/flysky.h"
#include "rx/a7105_flysky.h"
#include "rx/cc2500_sfhss.h"
#include "rx/cyrf6936_spektrum.h"

Expand Down
2 changes: 1 addition & 1 deletion src/main/target/CRAZYBEEF3FR/target.mk
Expand Up @@ -10,7 +10,7 @@ TARGET_SRC = \
ifeq ($(TARGET), CRAZYBEEF3FS)
TARGET_SRC += \
drivers/rx/rx_a7105.c \
rx/flysky.c
rx/a7105_flysky.c
else
ifeq ($(TARGET), CRAZYBEEF3FR)
TARGET_SRC += \
Expand Down
2 changes: 1 addition & 1 deletion src/main/target/EACHIF3/target.mk
Expand Up @@ -8,4 +8,4 @@ TARGET_SRC = \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms5611.c \
drivers/rx/rx_a7105.c \
rx/flysky.c
rx/a7105_flysky.c
2 changes: 1 addition & 1 deletion src/main/target/MATEKF411RX/target.mk
Expand Up @@ -14,5 +14,5 @@ TARGET_SRC = \
ifeq ($(TARGET), CRAZYBEEF4FS)
TARGET_SRC += \
drivers/rx/rx_a7105.c \
rx/flysky.c
rx/a7105_flysky.c
endif

0 comments on commit 305e423

Please sign in to comment.