Add SFHSS-SPI-RX

This commit is contained in:
chibaron 2018-10-01 23:27:40 +09:00
parent 8980ba1065
commit cb5fc4fd63
23 changed files with 878 additions and 228 deletions

View File

@ -50,6 +50,7 @@ const char * const debugModeNames[DEBUG_COUNT] = {
"FFT_TIME", "FFT_TIME",
"FFT_FREQ", "FFT_FREQ",
"RX_FRSKY_SPI", "RX_FRSKY_SPI",
"RX_SFHSS_SPI",
"GYRO_RAW", "GYRO_RAW",
"DUAL_GYRO", "DUAL_GYRO",
"DUAL_GYRO_RAW", "DUAL_GYRO_RAW",

View File

@ -68,6 +68,7 @@ typedef enum {
DEBUG_FFT_TIME, DEBUG_FFT_TIME,
DEBUG_FFT_FREQ, DEBUG_FFT_FREQ,
DEBUG_RX_FRSKY_SPI, DEBUG_RX_FRSKY_SPI,
DEBUG_RX_SFHSS_SPI,
DEBUG_GYRO_RAW, DEBUG_GYRO_RAW,
DEBUG_DUAL_GYRO, DEBUG_DUAL_GYRO,
DEBUG_DUAL_GYRO_RAW, DEBUG_DUAL_GYRO_RAW,

View File

@ -141,6 +141,7 @@ extern uint8_t __config_end;
#include "rx/spektrum.h" #include "rx/spektrum.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_frsky_x.h" #include "rx/cc2500_frsky_x.h"
#include "rx/cc2500_common.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -2560,13 +2561,14 @@ static void cliBeeper(char *cmdline)
} }
#endif #endif
#ifdef USE_RX_FRSKY_SPI #ifdef USE_RX_BIND
void cliFrSkyBind(char *cmdline){ void cliRxBind(char *cmdline){
UNUSED(cmdline); UNUSED(cmdline);
switch (rxSpiConfig()->rx_spi_protocol) { switch (rxSpiConfig()->rx_spi_protocol) {
case RX_SPI_FRSKY_D: case RX_SPI_FRSKY_D:
case RX_SPI_FRSKY_X: case RX_SPI_FRSKY_X:
frSkySpiBind(); case RX_SPI_SFHSS:
cc2500SpiBind();
cliPrint("Binding..."); cliPrint("Binding...");
@ -4464,8 +4466,9 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite), CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
#endif #endif
#endif #endif
#ifdef USE_RX_FRSKY_SPI #ifdef USE_RX_BIND
CLI_COMMAND_DEF("frsky_bind", "initiate binding for FrSky SPI RX", NULL, cliFrSkyBind), CLI_COMMAND_DEF("frsky_bind", "initiate binding for FrSky SPI RX", NULL, cliRxBind), /* legacy */
CLI_COMMAND_DEF("rx_bind", "initiate binding for RX", NULL, cliRxBind),
#endif #endif
CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet), CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet),
#ifdef USE_GPS #ifdef USE_GPS

View File

@ -87,6 +87,7 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_sfhss.h"
#include "rx/spektrum.h" #include "rx/spektrum.h"
#include "sensors/acceleration.h" #include "sensors/acceleration.h"
@ -224,7 +225,8 @@ static const char * const lookupTableRxSpi[] = {
"FRSKY_X", "FRSKY_X",
"FLYSKY", "FLYSKY",
"FLYSKY_2A", "FLYSKY_2A",
"KN" "KN",
"SFHSS"
}; };
#endif #endif
@ -1112,6 +1114,10 @@ const clivalue_t valueTable[] = {
{ "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_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, 255 }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, rxNum) },
{ "frsky_spi_use_external_adc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, useExternalAdc) }, { "frsky_spi_use_external_adc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, useExternalAdc) },
#endif
#ifdef USE_RX_SFHSS_SPI
{ "sfhss_spi_tx_id", VAR_UINT8 | MASTER_VALUE | MODE_ARRAY, .config.array.length = 2, PG_RX_SFHSS_SPI_CONFIG, offsetof(rxSfhssSpiConfig_t, bindTxId) },
{ "sfhss_spi_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -127, 127 }, PG_RX_SFHSS_SPI_CONFIG, offsetof(rxSfhssSpiConfig_t, bindOffset) },
#endif #endif
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) }, { "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
#ifdef USE_DASHBOARD #ifdef USE_DASHBOARD

View File

@ -135,7 +135,8 @@
#define PG_BOARD_CONFIG 538 #define PG_BOARD_CONFIG 538
#define PG_RCDEVICE_CONFIG 539 #define PG_RCDEVICE_CONFIG 539
#define PG_GYRO_DEVICE_CONFIG 540 #define PG_GYRO_DEVICE_CONFIG 540
#define PG_BETAFLIGHT_END 540 #define PG_RX_SFHSS_SPI_CONFIG 541
#define PG_BETAFLIGHT_END 541
// OSD configuration (subject to change) // OSD configuration (subject to change)

229
src/main/rx/cc2500_common.c Executable file
View File

@ -0,0 +1,229 @@
/*
* 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 <stdbool.h>
#include "platform.h"
#if defined(USE_RX_FRSKY_SPI) || defined(USE_RX_SFHSS_SPI)
#include "common/maths.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "pg/rx_spi.h"
#include "drivers/rx/rx_cc2500.h"
#include "drivers/io.h"
#include "drivers/time.h"
#include "fc/config.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "rx/cc2500_common.h"
static IO_t gdoPin;
static IO_t bindPin = DEFIO_IO(NONE);
static IO_t cc2500LedPin;
static bool bindRequested;
static bool lastBindPinStatus;
#if defined(USE_RX_CC2500_SPI_PA_LNA)
static IO_t txEnPin;
static IO_t rxLnaEnPin;
static IO_t antSelPin;
#endif
static int16_t rssiDbm;
uint16_t cc2500getRssiDbm(void)
{
return rssiDbm;
}
void cc2500setRssiDbm(uint8_t value)
{
if (value >= 128) {
rssiDbm = ((((uint16_t)value) * 18) >> 5) - 82;
} else {
rssiDbm = ((((uint16_t)value) * 18) >> 5) + 65;
}
setRssi(rssiDbm << 3, RSSI_SOURCE_RX_PROTOCOL);
}
void cc2500SpiBind(void)
{
bindRequested = true;
}
bool cc2500checkBindRequested(bool reset)
{
if (bindPin) {
bool bindPinStatus = IORead(bindPin);
if (lastBindPinStatus && !bindPinStatus) {
bindRequested = true;
}
lastBindPinStatus = bindPinStatus;
}
if (!bindRequested) {
return false;
} else {
if (reset) {
bindRequested = false;
}
return true;
}
}
bool cc2500getGdo(void)
{
return IORead(gdoPin);
}
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY)
void cc2500switchAntennae(void)
{
static bool alternativeAntennaSelected = true;
if (alternativeAntennaSelected) {
IOLo(antSelPin);
} else {
IOHi(antSelPin);
}
alternativeAntennaSelected = !alternativeAntennaSelected;
}
#endif
#if defined(USE_RX_CC2500_SPI_PA_LNA)
void cc2500TxEnable(void)
{
IOHi(txEnPin);
}
void cc2500TxDisable(void)
{
IOLo(txEnPin);
}
#endif
void cc2500LedOn(void)
{
#if defined(RX_CC2500_SPI_LED_PIN_INVERTED)
IOLo(cc2500LedPin);
#else
IOHi(cc2500LedPin);
#endif
}
void cc2500LedOff(void)
{
#if defined(RX_CC2500_SPI_LED_PIN_INVERTED)
IOHi(cc2500LedPin);
#else
IOLo(cc2500LedPin);
#endif
}
void cc2500LedBlink(timeMs_t blinkms)
{
static bool ledIsOn=true;
static timeMs_t ledBlinkMs = 0;
if ( (ledBlinkMs + blinkms) > millis() ){
return;
}
ledBlinkMs = millis();
if (ledIsOn) {
cc2500LedOff();
} else {
cc2500LedOn();
}
ledIsOn = !ledIsOn;
}
static bool cc2500SpiDetect(void)
{
const uint8_t chipPartNum = cc2500ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST); //CC2500 read registers chip part num
const uint8_t chipVersion = cc2500ReadReg(CC2500_31_VERSION | CC2500_READ_BURST); //CC2500 read registers chip version
if (chipPartNum == 0x80 && chipVersion == 0x03) {
return true;
}
return false;
}
bool cc2500SpiInit(void)
{
#if !defined(RX_CC2500_SPI_DISABLE_CHIP_DETECTION)
if (!cc2500SpiDetect()) {
return false;
}
#else
UNUSED(cc2500SpiDetect);
#endif
if (rssiSource == RSSI_SOURCE_NONE) {
rssiSource = RSSI_SOURCE_RX_PROTOCOL;
}
// gpio init here
gdoPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_GDO_0_PIN));
IOInit(gdoPin, OWNER_RX_SPI, 0);
IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
cc2500LedPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_LED_PIN));
IOInit(cc2500LedPin, OWNER_LED, 0);
IOConfigGPIO(cc2500LedPin, IOCFG_OUT_PP);
#if defined(USE_RX_CC2500_SPI_PA_LNA)
rxLnaEnPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_LNA_EN_PIN));
IOInit(rxLnaEnPin, OWNER_RX_SPI, 0);
IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
IOHi(rxLnaEnPin); // always on at the moment
txEnPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_TX_EN_PIN));
IOInit(txEnPin, OWNER_RX_SPI, 0);
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
antSelPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_ANT_SEL_PIN));
IOInit(antSelPin, OWNER_RX_SPI, 0);
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
#endif
#endif // USE_RX_CC2500_SPI_PA_LNA
#if defined(BINDPLUG_PIN)
bindPin = IOGetByTag(IO_TAG(BINDPLUG_PIN));
IOInit(bindPin, OWNER_RX_BIND, 0);
IOConfigGPIO(bindPin, IOCFG_IPU);
lastBindPinStatus = IORead(bindPin);
#endif
#if defined(USE_RX_CC2500_SPI_PA_LNA)
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
IOHi(antSelPin);
#endif
cc2500TxDisable();
#endif // USE_RX_CC2500_SPI_PA_LNA
return true;
}
#endif

43
src/main/rx/cc2500_common.h Executable file
View File

@ -0,0 +1,43 @@
/*
* 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 "pg/pg.h"
#include "rx/rx_spi.h"
uint16_t cc2500getRssiDbm(void);
void cc2500setRssiDbm(uint8_t value);
void cc2500SpiBind(void);
bool cc2500checkBindRequested(bool reset);
bool cc2500getGdo(void);
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY)
void cc2500switchAntennae(void);
#endif
#if defined(USE_RX_CC2500_SPI_PA_LNA)
void cc2500TxEnable(void);
void cc2500TxDisable(void);
#endif
void cc2500LedOn(void);
void cc2500LedOff(void);
void cc2500LedBlink(timeMs_t blinkms);
bool cc2500SpiInit(void);

View File

@ -39,4 +39,3 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntime
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet); rx_spi_received_e frSkySpiDataReceived(uint8_t *packet);
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload); void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload);
void frSkySpiBind(void);

View File

@ -46,6 +46,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "rx/cc2500_common.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_frsky_shared.h" #include "rx/cc2500_frsky_shared.h"
@ -123,7 +124,7 @@ static void buildTelemetryFrame(uint8_t *packet)
frame[2] = rxFrSkySpiConfig()->bindTxId[1]; frame[2] = rxFrSkySpiConfig()->bindTxId[1];
frame[3] = a1Value; frame[3] = a1Value;
frame[4] = a2Value; frame[4] = a2Value;
frame[5] = (uint8_t)rssiDbm; frame[5] = (uint8_t)cc2500getRssiDbm();
uint8_t bytesUsed = 0; uint8_t bytesUsed = 0;
#if defined(USE_TELEMETRY_FRSKY_HUB) #if defined(USE_TELEMETRY_FRSKY_HUB)
if (telemetryEnabled) { if (telemetryEnabled) {
@ -195,7 +196,7 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
lastPacketReceivedTime = currentPacketReceivedTime; lastPacketReceivedTime = currentPacketReceivedTime;
*protocolState = STATE_DATA; *protocolState = STATE_DATA;
if (checkBindRequested(false)) { if (cc2500checkBindRequested(false)) {
lastPacketReceivedTime = 0; lastPacketReceivedTime = 0;
timeoutUs = 50; timeoutUs = 50;
missingPackets = 0; missingPackets = 0;
@ -207,7 +208,7 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
FALLTHROUGH; //!!TODO -check this fall through is correct FALLTHROUGH; //!!TODO -check this fall through is correct
// here FS code could be // here FS code could be
case STATE_DATA: case STATE_DATA:
if (IORead(gdoPin)) { if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen >= 20) { if (ccLen >= 20) {
cc2500ReadFifo(packet, 20); cc2500ReadFifo(packet, 20);
@ -217,12 +218,12 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
if (packet[0] == 0x11) { if (packet[0] == 0x11) {
if ((packet[1] == rxFrSkySpiConfig()->bindTxId[0]) && if ((packet[1] == rxFrSkySpiConfig()->bindTxId[0]) &&
(packet[2] == rxFrSkySpiConfig()->bindTxId[1])) { (packet[2] == rxFrSkySpiConfig()->bindTxId[1])) {
LedOn(); cc2500LedOn();
nextChannel(1); nextChannel(1);
#if defined(USE_RX_FRSKY_SPI_TELEMETRY) #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
if ((packet[3] % 4) == 2) { if ((packet[3] % 4) == 2) {
telemetryTimeUs = micros(); telemetryTimeUs = micros();
setRssiDbm(packet[18]); cc2500setRssiDbm(packet[18]);
buildTelemetryFrame(packet); buildTelemetryFrame(packet);
*protocolState = STATE_TELEMETRY; *protocolState = STATE_TELEMETRY;
} else } else
@ -240,13 +241,13 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
} }
if (cmpTimeUs(currentPacketReceivedTime, lastPacketReceivedTime) > (timeoutUs * SYNC_DELAY_MAX)) { if (cmpTimeUs(currentPacketReceivedTime, lastPacketReceivedTime) > (timeoutUs * SYNC_DELAY_MAX)) {
#if defined(USE_RX_FRSKY_SPI_PA_LNA) #if defined(USE_RX_CC2500_SPI_PA_LNA)
TxDisable(); cc2500TxDisable();
#endif #endif
if (timeoutUs == 1) { if (timeoutUs == 1) {
#if defined(USE_RX_FRSKY_SPI_PA_LNA) && defined(USE_RX_FRSKY_SPI_DIVERSITY) // SE4311 chip #if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY) // SE4311 chip
if (missingPackets >= 2) { if (missingPackets >= 2) {
switchAntennae(); cc2500switchAntennae();
} }
#endif #endif
@ -262,9 +263,9 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
nextChannel(1); nextChannel(1);
} else { } else {
if (ledIsOn) { if (ledIsOn) {
LedOff(); cc2500LedOff();
} else { } else {
LedOn(); cc2500LedOn();
} }
ledIsOn = !ledIsOn; ledIsOn = !ledIsOn;
@ -284,8 +285,8 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
cc2500Strobe(CC2500_SIDLE); cc2500Strobe(CC2500_SIDLE);
cc2500SetPower(6); cc2500SetPower(6);
cc2500Strobe(CC2500_SFRX); cc2500Strobe(CC2500_SFRX);
#if defined(USE_RX_FRSKY_SPI_PA_LNA) #if defined(USE_RX_CC2500_SPI_PA_LNA)
TxEnable(); cc2500TxEnable();
#endif #endif
cc2500Strobe(CC2500_SIDLE); cc2500Strobe(CC2500_SIDLE);
cc2500WriteFifo(frame, frame[0] + 1); cc2500WriteFifo(frame, frame[0] + 1);

View File

@ -40,6 +40,7 @@
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/rx_spi.h" #include "rx/rx_spi.h"
#include "rx/cc2500_common.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_frsky_d.h" #include "rx/cc2500_frsky_d.h"
#include "rx/cc2500_frsky_x.h" #include "rx/cc2500_frsky_x.h"
@ -59,9 +60,6 @@ static timeMs_t timeTunedMs;
uint8_t listLength; uint8_t listLength;
static uint8_t bindIdx; static uint8_t bindIdx;
static int8_t bindOffset; static int8_t bindOffset;
static bool lastBindPinStatus;
static bool bindRequested;
typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState); typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState);
typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload); typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload);
@ -69,20 +67,6 @@ typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload);
static handlePacketFn *handlePacket; static handlePacketFn *handlePacket;
static setRcDataFn *setRcData; static setRcDataFn *setRcData;
IO_t gdoPin;
static IO_t bindPin = DEFIO_IO(NONE);
static IO_t frSkyLedPin;
#if defined(USE_RX_FRSKY_SPI_PA_LNA)
static IO_t txEnPin;
static IO_t rxLnaEnPin;
static IO_t antSelPin;
#endif
#ifdef USE_RX_FRSKY_SPI_TELEMETRY
int16_t rssiDbm;
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig, PG_RX_FRSKY_SPI_CONFIG, 1); PG_REGISTER_WITH_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig, PG_RX_FRSKY_SPI_CONFIG, 1);
PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig, PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig,
@ -97,52 +81,9 @@ PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig,
.useExternalAdc = false, .useExternalAdc = false,
); );
#if defined(USE_RX_FRSKY_SPI_TELEMETRY)
void setRssiDbm(uint8_t value)
{
if (value >= 128) {
rssiDbm = ((((uint16_t)value) * 18) >> 5) - 82;
} else {
rssiDbm = ((((uint16_t)value) * 18) >> 5) + 65;
}
setRssi(rssiDbm << 3, RSSI_SOURCE_RX_PROTOCOL);
}
#endif // USE_RX_FRSKY_SPI_TELEMETRY
#if defined(USE_RX_FRSKY_SPI_PA_LNA)
void TxEnable(void)
{
IOHi(txEnPin);
}
void TxDisable(void)
{
IOLo(txEnPin);
}
#endif
void LedOn(void)
{
#if defined(RX_FRSKY_SPI_LED_PIN_INVERTED)
IOLo(frSkyLedPin);
#else
IOHi(frSkyLedPin);
#endif
}
void LedOff(void)
{
#if defined(RX_FRSKY_SPI_LED_PIN_INVERTED)
IOHi(frSkyLedPin);
#else
IOLo(frSkyLedPin);
#endif
}
void frSkySpiBind(void) void frSkySpiBind(void)
{ {
bindRequested = true; cc2500SpiBind();
} }
static void initialise() { static void initialise() {
@ -252,7 +193,7 @@ static bool tuneRx(uint8_t *packet)
bindOffset += 5; bindOffset += 5;
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset); cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
} }
if (IORead(gdoPin)) { if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) { if (ccLen) {
cc2500ReadFifo(packet, ccLen); cc2500ReadFifo(packet, ccLen);
@ -292,7 +233,7 @@ static bool getBind1(uint8_t *packet)
// len|bind |tx // 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| // 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 // Start by getting bind packet 0 and the txid
if (IORead(gdoPin)) { if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) { if (ccLen) {
cc2500ReadFifo(packet, ccLen); cc2500ReadFifo(packet, ccLen);
@ -321,7 +262,7 @@ static bool getBind1(uint8_t *packet)
static bool getBind2(uint8_t *packet) static bool getBind2(uint8_t *packet)
{ {
if (bindIdx <= 120) { if (bindIdx <= 120) {
if (IORead(gdoPin)) { if (cc2500getGdo()) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen) { if (ccLen) {
cc2500ReadFifo(packet, ccLen); cc2500ReadFifo(packet, ccLen);
@ -369,27 +310,6 @@ static bool getBind2(uint8_t *packet)
} }
} }
bool checkBindRequested(bool reset)
{
if (bindPin) {
bool bindPinStatus = IORead(bindPin);
if (lastBindPinStatus && !bindPinStatus) {
bindRequested = true;
}
lastBindPinStatus = bindPinStatus;
}
if (!bindRequested) {
return false;
} else {
if (reset) {
bindRequested = false;
}
return true;
}
}
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet) rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
{ {
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE; rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
@ -404,8 +324,8 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
break; break;
case STATE_BIND: case STATE_BIND:
if (checkBindRequested(true) || rxFrSkySpiConfig()->autoBind) { if (cc2500checkBindRequested(true) || rxFrSkySpiConfig()->autoBind) {
LedOn(); cc2500LedOn();
initTuneRx(); initTuneRx();
protocolState = STATE_BIND_TUNING; protocolState = STATE_BIND_TUNING;
@ -443,9 +363,9 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
} else { } else {
uint8_t ctr = 40; uint8_t ctr = 40;
while (ctr--) { while (ctr--) {
LedOn(); cc2500LedOn();
delay(50); delay(50);
LedOff(); cc2500LedOff();
delay(50); delay(50);
} }
} }
@ -489,40 +409,9 @@ void nextChannel(uint8_t skip)
} }
} }
#if defined(USE_RX_FRSKY_SPI_PA_LNA) && defined(USE_RX_FRSKY_SPI_DIVERSITY)
void switchAntennae(void)
{
static bool alternativeAntennaSelected = true;
if (alternativeAntennaSelected) {
IOLo(antSelPin);
} else {
IOHi(antSelPin);
}
alternativeAntennaSelected = !alternativeAntennaSelected;
}
#endif
static bool frSkySpiDetect(void)
{
const uint8_t chipPartNum = cc2500ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST); //CC2500 read registers chip part num
const uint8_t chipVersion = cc2500ReadReg(CC2500_31_VERSION | CC2500_READ_BURST); //CC2500 read registers chip version
if (chipPartNum == 0x80 && chipVersion == 0x03) {
return true;
}
return false;
}
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig) bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{ {
#if !defined(RX_FRSKY_SPI_DISABLE_CHIP_DETECTION) cc2500SpiInit();
if (!frSkySpiDetect()) {
return false;
}
#else
UNUSED(frSkySpiDetect);
#endif
spiProtocol = rxSpiConfig->rx_spi_protocol; spiProtocol = rxSpiConfig->rx_spi_protocol;
@ -554,42 +443,6 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntime
} }
#endif #endif
// gpio init here
gdoPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_GDO_0_PIN));
IOInit(gdoPin, OWNER_RX_SPI, 0);
IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
frSkyLedPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_LED_PIN));
IOInit(frSkyLedPin, OWNER_LED, 0);
IOConfigGPIO(frSkyLedPin, IOCFG_OUT_PP);
#if defined(USE_RX_FRSKY_SPI_PA_LNA)
rxLnaEnPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_LNA_EN_PIN));
IOInit(rxLnaEnPin, OWNER_RX_SPI, 0);
IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
IOHi(rxLnaEnPin); // always on at the moment
txEnPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_TX_EN_PIN));
IOInit(txEnPin, OWNER_RX_SPI, 0);
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
#if defined(USE_RX_FRSKY_SPI_DIVERSITY)
antSelPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_ANT_SEL_PIN));
IOInit(antSelPin, OWNER_RX_SPI, 0);
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
#endif
#endif // USE_RX_FRSKY_SPI_PA_LNA
#if defined(BINDPLUG_PIN)
bindPin = IOGetByTag(IO_TAG(BINDPLUG_PIN));
IOInit(bindPin, OWNER_RX_BIND, 0);
IOConfigGPIO(bindPin, IOCFG_IPU);
lastBindPinStatus = IORead(bindPin);
#endif
#if defined(USE_RX_FRSKY_SPI_PA_LNA)
#if defined(USE_RX_FRSKY_SPI_DIVERSITY)
IOHi(antSelPin);
#endif
TxDisable();
#endif // USE_RX_FRSKY_SPI_PA_LNA
missingPackets = 0; missingPackets = 0;
timeoutUs = 50; timeoutUs = 50;

View File

@ -50,22 +50,7 @@ enum {
extern uint8_t listLength; extern uint8_t listLength;
extern uint32_t missingPackets; extern uint32_t missingPackets;
extern timeDelta_t timeoutUs; extern timeDelta_t timeoutUs;
extern int16_t rssiDbm;
extern IO_t gdoPin;
void setRssiDbm(uint8_t value);
void TxEnable(void);
void TxDisable(void);
void LedOn(void);
void LedOff(void);
void switchAntennae(void);
void initialiseData(uint8_t adr); void initialiseData(uint8_t adr);
bool checkBindRequested(bool reset);
void nextChannel(uint8_t skip); void nextChannel(uint8_t skip);

View File

@ -47,6 +47,7 @@
#include "fc/config.h" #include "fc/config.h"
#include "rx/cc2500_common.h"
#include "rx/cc2500_frsky_common.h" #include "rx/cc2500_frsky_common.h"
#include "rx/cc2500_frsky_shared.h" #include "rx/cc2500_frsky_shared.h"
@ -190,7 +191,7 @@ static void buildTelemetryFrame(uint8_t *packet)
frame[3] = packet[3]; frame[3] = packet[3];
if (evenRun) { if (evenRun) {
frame[4] = (uint8_t)rssiDbm | 0x80; frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
} else { } else {
uint8_t a1Value; uint8_t a1Value;
if (rxFrSkySpiConfig()->useExternalAdc) { if (rxFrSkySpiConfig()->useExternalAdc) {
@ -331,7 +332,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
*protocolState = STATE_DATA; *protocolState = STATE_DATA;
frameReceived = false; // again set for receive frameReceived = false; // again set for receive
receiveDelayUs = 5300; receiveDelayUs = 5300;
if (checkBindRequested(false)) { if (cc2500checkBindRequested(false)) {
packetTimerUs = 0; packetTimerUs = 0;
timeoutUs = 50; timeoutUs = 50;
missingPackets = 0; missingPackets = 0;
@ -343,7 +344,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
FALLTHROUGH; FALLTHROUGH;
// here FS code could be // here FS code could be
case STATE_DATA: case STATE_DATA:
if (IORead(gdoPin) && (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 ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F; // read 2 times to avoid reading errors
if (ccLen > 32) { if (ccLen > 32) {
@ -360,7 +361,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
missingPackets = 0; missingPackets = 0;
timeoutUs = 1; timeoutUs = 1;
receiveDelayUs = 0; receiveDelayUs = 0;
LedOn(); cc2500LedOn();
if (skipChannels) { if (skipChannels) {
channelsToSkip = packet[5] << 2; channelsToSkip = packet[5] << 2;
if (packet[4] >= listLength) { if (packet[4] >= listLength) {
@ -376,7 +377,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
skipChannels = false; skipChannels = false;
} }
#ifdef USE_RX_FRSKY_SPI_TELEMETRY #ifdef USE_RX_FRSKY_SPI_TELEMETRY
setRssiDbm(packet[ccLen - 2]); cc2500setRssiDbm(packet[ccLen - 2]);
#endif #endif
telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21]; telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
@ -444,9 +445,9 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
} }
if (cmpTimeUs(micros(), packetTimerUs) > timeoutUs * SYNC_DELAY_MAX) { if (cmpTimeUs(micros(), packetTimerUs) > timeoutUs * SYNC_DELAY_MAX) {
if (ledIsOn) { if (ledIsOn) {
LedOff(); cc2500LedOff();
} else { } else {
LedOn(); cc2500LedOn();
} }
ledIsOn = !ledIsOn; ledIsOn = !ledIsOn;
@ -465,8 +466,8 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
cc2500SetPower(6); cc2500SetPower(6);
cc2500Strobe(CC2500_SFRX); cc2500Strobe(CC2500_SFRX);
delayMicroseconds(30); delayMicroseconds(30);
#if defined(USE_RX_FRSKY_SPI_PA_LNA) #if defined(USE_RX_CC2500_SPI_PA_LNA)
TxEnable(); cc2500TxEnable();
#endif #endif
cc2500Strobe(CC2500_SIDLE); cc2500Strobe(CC2500_SIDLE);
cc2500WriteFifo(frame, frame[0] + 1); cc2500WriteFifo(frame, frame[0] + 1);
@ -514,14 +515,14 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
frameReceived = false; // again set for receive frameReceived = false; // again set for receive
nextChannel(channelsToSkip); nextChannel(channelsToSkip);
cc2500Strobe(CC2500_SRX); cc2500Strobe(CC2500_SRX);
#ifdef USE_RX_FRSKY_SPI_PA_LNA #ifdef USE_RX_CC2500_SPI_PA_LNA
TxDisable(); cc2500TxDisable();
#if defined(USE_RX_FRSKY_SPI_DIVERSITY) #if defined(USE_RX_CC2500_SPI_DIVERSITY)
if (missingPackets >= 2) { if (missingPackets >= 2) {
switchAntennae(); cc2500switchAntennae();
} }
#endif #endif
#endif // USE_RX_FRSKY_SPI_PA_LNA #endif // USE_RX_CC2500_SPI_PA_LNA
if (missingPackets > MAX_MISSING_PKT) { if (missingPackets > MAX_MISSING_PKT) {
timeoutUs = 50; timeoutUs = 50;
skipChannels = true; skipChannels = true;

448
src/main/rx/cc2500_sfhss.c Executable file
View File

@ -0,0 +1,448 @@
/*
* 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 <stdbool.h>
#include "platform.h"
#ifdef USE_RX_SFHSS_SPI
#include "build/build_config.h"
#include "build/debug.h"
#include "common/maths.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "pg/rx_spi.h"
#include "drivers/rx/rx_cc2500.h"
#include "drivers/io.h"
#include "drivers/time.h"
#include "fc/config.h"
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "rx/cc2500_common.h"
#include "rx/cc2500_sfhss.h"
//void cliPrintLinef(const char *format, ...);
#define BIND_CH 15
#define SFHSS_PACKET_LEN 15
#define BIND_TUNE_STEP 4
#define SFHSSCH2CHANNR(ch) (ch*6+16)
#define GET_CHAN(x) ((int)((x[5]>>3)&0x1f))
#define GET_CODE(x) (((x[11] & 0x7) <<2 ) | ((x[12]>>6) & 0x3))
#define GET_COMMAND(x) (x[12] & 0xf)
#define GET_CH1(x) ((uint16_t)(((x[5] & 0x07) << 9 | x[6]<<1) | (x[7] & 0x80)>>7))
#define GET_CH2(x) (uint16_t)(((x[7] & 0x7f) << 5 | (x[8] & 0xf8)>>3))
#define GET_CH3(x) (uint16_t)(((x[8] & 0x07) << 9 | x[9]<<1) | (x[10] & 0x80)>>7)
#define GET_CH4(x) (uint16_t)(((x[10] & 0x7f) << 5 | (x[11] & 0xf8)>>3))
#define GET_TXID1(x) (uint8_t)(x[1])
#define GET_TXID2(x) (uint8_t)(x[2])
#define SET_STATE(x) {protocolState = x; DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_STATE, x);}
#define NEXT_CH_TIME_HUNT 500000 /* hunt */
#define NEXT_CH_TIME_SYNC0 6800 /* sync no recv */
#define NEXT_CH_TIME_SYNC1 3500 /* sync ch1-4 recv */
#define NEXT_CH_TIME_SYNC2 500 /* sync ch5-8 recv */
static int8_t sfhss_channel = 0;
static int8_t sfhss_code = 0;
static timeMs_t start_time;
static uint8_t protocolState;
static uint32_t missingPackets;
static uint8_t calData[32][3];
static timeMs_t timeTunedMs;
static int8_t bindOffset_max=0;
static int8_t bindOffset_min=0;
PG_REGISTER_WITH_RESET_TEMPLATE(rxSfhssSpiConfig_t, rxSfhssSpiConfig, PG_RX_SFHSS_SPI_CONFIG, 1);
PG_RESET_TEMPLATE(rxSfhssSpiConfig_t, rxSfhssSpiConfig,
.bindTxId = {0, 0},
.bindOffset = 0,
);
static void initialise() {
cc2500Reset();
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
cc2500WriteReg(CC2500_03_FIFOTHR, 0x07);
cc2500WriteReg(CC2500_04_SYNC1, 0xD3);
cc2500WriteReg(CC2500_05_SYNC0, 0x91);
cc2500WriteReg(CC2500_06_PKTLEN, 0x0D);
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04);
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x0C);
cc2500WriteReg(CC2500_09_ADDR, 0x29);
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x06);
cc2500WriteReg(CC2500_0C_FSCTRL0, (rxSfhssSpiConfigMutable()->bindOffset));
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
cc2500WriteReg(CC2500_0E_FREQ1, 0x4E);
cc2500WriteReg(CC2500_0F_FREQ0, 0xC4);
cc2500WriteReg(CC2500_10_MDMCFG4, 0x7C);
cc2500WriteReg(CC2500_11_MDMCFG3, 0x43);
cc2500WriteReg(CC2500_12_MDMCFG2, 0x03);
cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
cc2500WriteReg(CC2500_14_MDMCFG0, 0x3B);
cc2500WriteReg(CC2500_15_DEVIATN, 0x44);
cc2500WriteReg(CC2500_17_MCSM1, 0x0F);
cc2500WriteReg(CC2500_18_MCSM0, 0x08);
cc2500WriteReg(CC2500_19_FOCCFG, 0x1D);
cc2500WriteReg(CC2500_1A_BSCFG, 0x6C);
cc2500WriteReg(CC2500_1B_AGCCTRL2, 0x03);
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 < 30; c++)
{ //calibrate all channels
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_0A_CHANNR, SFHSSCH2CHANNR(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);
}
}
static bool sfhssRecv(uint8_t *packet)
{
uint8_t ccLen;
if (!(cc2500getGdo())){
return false;
}
ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen < SFHSS_PACKET_LEN){
return false;
}
cc2500ReadFifo(packet, SFHSS_PACKET_LEN);
return true;
}
static bool sfhssPacketParse(uint8_t *packet, bool check_txid)
{
if (!(packet[SFHSS_PACKET_LEN - 1] & 0x80)){
return false; /* crc fail */
}
if (packet[0] != 0x81){
return false; /* sfhss header fail */
}
if (GET_CHAN(packet) != sfhss_channel){
return false; /* channel fail */
}
if (check_txid){
if ((rxSfhssSpiConfigMutable()->bindTxId[0] != GET_TXID1(packet)) ||
(rxSfhssSpiConfigMutable()->bindTxId[1] != GET_TXID2(packet))){
return false; /* txid fail */
}
}
cc2500setRssiDbm(packet[SFHSS_PACKET_LEN - 2]);
sfhss_code = GET_CODE(packet);
return true;
}
void sfhssRx(void)
{
cc2500Strobe(CC2500_SIDLE);
cc2500WriteReg(CC2500_23_FSCAL3, calData[sfhss_channel][0]);
cc2500WriteReg(CC2500_24_FSCAL2, calData[sfhss_channel][1]);
cc2500WriteReg(CC2500_25_FSCAL1, calData[sfhss_channel][2]);
cc2500WriteReg(CC2500_0A_CHANNR, SFHSSCH2CHANNR(sfhss_channel));
cc2500Strobe(CC2500_SFRX);
cc2500Strobe(CC2500_SRX);
}
static void initTuneRx(void)
{
timeTunedMs = millis();
bindOffset_min = -64;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MIN, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
sfhss_channel = BIND_CH;
sfhssRx();
}
static bool tune1Rx(uint8_t *packet)
{
if (bindOffset_min >= 126) {
bindOffset_min = -126;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MIN, bindOffset_min);
}
if ((millis() - timeTunedMs) > 220) { // 220ms
timeTunedMs = millis();
bindOffset_min += BIND_TUNE_STEP<<2;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MIN, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
cc2500Strobe(CC2500_SRX);
}
if (sfhssRecv(packet)){
if (sfhssPacketParse(packet, false)){
if ((packet[SFHSS_PACKET_LEN - 1] & 0x7F) > 40 ){ /* lqi */
rxSfhssSpiConfigMutable()->bindTxId[0] = GET_TXID1(packet);
rxSfhssSpiConfigMutable()->bindTxId[1] = GET_TXID2(packet);
bindOffset_max = bindOffset_min;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MAX, bindOffset_max);
cc2500Strobe(CC2500_SRX);
timeTunedMs = millis();
return true;
}
}
cc2500Strobe(CC2500_SRX);
}
return false;
}
static bool tune2Rx(uint8_t *packet)
{
cc2500LedBlink(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 (sfhssRecv(packet)){
if (sfhssPacketParse(packet, true)){
timeTunedMs = millis();
bindOffset_max += BIND_TUNE_STEP;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MAX, bindOffset_max);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_max);
}
cc2500Strobe(CC2500_SRX);
}
return false;
}
static bool tune3Rx(uint8_t *packet)
{
cc2500LedBlink(100);
if (((millis() - timeTunedMs) > 880) || bindOffset_min < (-126+BIND_TUNE_STEP)) { // 220ms *4
return true;
}
if (sfhssRecv(packet)){
if (sfhssPacketParse(packet, true)){
timeTunedMs = millis();
bindOffset_min -= BIND_TUNE_STEP;
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MIN, bindOffset_min);
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset_min);
}
cc2500Strobe(CC2500_SRX);
}
return false;
}
void sfhssnextChannel(void)
{
do {
sfhss_channel += sfhss_code + 2;
if (sfhss_channel > 29) {
sfhss_channel -= 31;
}
}while( sfhss_channel < 0);
sfhssRx();
}
void sfhssSpiSetRcData(uint16_t *rcData, const uint8_t *payload)
{
if( GET_COMMAND(payload) & 0x8 ){
rcData[4] = GET_CH1(payload);
rcData[5] = GET_CH2(payload);
rcData[6] = GET_CH3(payload);
rcData[7] = GET_CH4(payload);
}else{
rcData[0] = GET_CH1(payload);
rcData[1] = GET_CH2(payload);
rcData[2] = GET_CH3(payload);
rcData[3] = GET_CH4(payload);
}
}
rx_spi_received_e sfhssSpiDataReceived(uint8_t *packet)
{
static uint16_t dataMissingFrame = 0;
static timeUs_t nextFrameReceiveStartTime = 0;
static uint8_t frame_recvd = 0;
timeUs_t currentPacketReceivedTime;
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
currentPacketReceivedTime = micros();
switch (protocolState) {
case STATE_INIT:
if ((millis() - start_time) > 10) {
cc2500LedOff();
dataMissingFrame = 0;
initialise();
SET_STATE(STATE_BIND);
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_MISSING_FRAME, dataMissingFrame);
}
break;
case STATE_BIND:
if (cc2500checkBindRequested(true)) {
cc2500LedOn();
initTuneRx();
SET_STATE( STATE_BIND_TUNING1 );
} else {
SET_STATE( STATE_HUNT );
sfhssnextChannel();
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
nextFrameReceiveStartTime = currentPacketReceivedTime + NEXT_CH_TIME_HUNT;
}
break;
case STATE_BIND_TUNING1:
if (tune1Rx(packet)) {
SET_STATE( STATE_BIND_TUNING2 );
}
break;
case STATE_BIND_TUNING2:
if (tune2Rx(packet)) {
SET_STATE( STATE_BIND_TUNING3);
}
break;
case STATE_BIND_TUNING3:
if (tune3Rx(packet)) {
if(((int16_t)bindOffset_max - (int16_t)bindOffset_min) <= 2){
initTuneRx();
SET_STATE( STATE_BIND_TUNING1 ); // retry
}else{
rxSfhssSpiConfigMutable()->bindOffset = ((int16_t)bindOffset_max + (int16_t)bindOffset_min)/2 ;
SET_STATE(STATE_BIND_COMPLETE);
}
}
break;
case STATE_BIND_COMPLETE:
writeEEPROM();
ret = RX_SPI_RECEIVED_BIND;
SET_STATE(STATE_INIT);
break;
case STATE_HUNT:
if (sfhssRecv(packet)){
if (sfhssPacketParse(packet, true)){
if (GET_COMMAND(packet) & 0x8){ /* ch=5-8 */
missingPackets = 0;
cc2500LedOn();
frame_recvd = 0x3;
SET_STATE(STATE_SYNC);
nextFrameReceiveStartTime = currentPacketReceivedTime + NEXT_CH_TIME_SYNC2;
return RX_SPI_RECEIVED_NONE;
}
}
cc2500Strobe(CC2500_SRX);
}else if (cmpTimeUs(currentPacketReceivedTime, nextFrameReceiveStartTime) > 0) {
cc2500LedBlink(500);
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY) // SE4311 chip
cc2500switchAntennae();
#endif
sfhssnextChannel();
nextFrameReceiveStartTime += NEXT_CH_TIME_HUNT;
}else if (cc2500checkBindRequested(false)) {
SET_STATE(STATE_INIT);
break;
}
break;
case STATE_SYNC:
if (sfhssRecv(packet)){
if (sfhssPacketParse(packet, true)){
missingPackets = 0;
if( GET_COMMAND(packet) & 0x8 ){
nextFrameReceiveStartTime = currentPacketReceivedTime + NEXT_CH_TIME_SYNC2;
frame_recvd |= 0x2; /* ch5-8 */
}else{
nextFrameReceiveStartTime = currentPacketReceivedTime + NEXT_CH_TIME_SYNC1;
cc2500Strobe(CC2500_SRX);
frame_recvd |= 0x1; /* ch1-4 */
}
if (GET_COMMAND(packet) & 0x4){
return RX_SPI_RECEIVED_NONE; /* failsafe data */
}
return RX_SPI_RECEIVED_DATA;
}
cc2500Strobe(CC2500_SRX);
}else if (cmpTimeUs(currentPacketReceivedTime, nextFrameReceiveStartTime) > 0) {
nextFrameReceiveStartTime += NEXT_CH_TIME_SYNC0;
if (frame_recvd != 0x3){
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_MISSING_FRAME, ++dataMissingFrame);
}
if (frame_recvd == 0){
if (++missingPackets > MAX_MISSING_PKT) {
SET_STATE(STATE_HUNT);
sfhssnextChannel();
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
nextFrameReceiveStartTime = currentPacketReceivedTime + NEXT_CH_TIME_HUNT;
break;
}
#if defined(USE_RX_CC2500_SPI_PA_LNA) && defined(USE_RX_CC2500_SPI_DIVERSITY) // SE4311 chip
if (missingPackets >= 2) {
cc2500switchAntennae();
}
#endif
}
frame_recvd = 0;
sfhssnextChannel();
}else if (cc2500checkBindRequested(false)) {
SET_STATE(STATE_INIT);
break;
}
break;
}
return ret;
}
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
{
UNUSED(rxSpiConfig);
cc2500SpiInit();
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_SFHSS;
start_time = millis();
SET_STATE(STATE_INIT);
return true;
}
#endif

55
src/main/rx/cc2500_sfhss.h Executable file
View File

@ -0,0 +1,55 @@
/*
* 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 "pg/pg.h"
#include "rx/rx_spi.h"
#define MAX_MISSING_PKT 100
#define RC_CHANNEL_COUNT_SFHSS 8
#define DEBUG_DATA_STATE 0
#define DEBUG_DATA_MISSING_FRAME 1
#define DEBUG_DATA_OFFSET_MAX 2
#define DEBUG_DATA_OFFSET_MIN 3
#define STATE_INIT 0
#define STATE_HUNT 1
#define STATE_SYNC 2
#define STATE_BIND 10
#define STATE_BIND_TUNING1 11
#define STATE_BIND_TUNING2 12
#define STATE_BIND_TUNING3 13
#define STATE_BIND_COMPLETE 14
typedef struct rxSfhssSpiConfig_s {
uint8_t bindTxId[2];
int8_t bindOffset;
} rxSfhssSpiConfig_t;
PG_DECLARE(rxSfhssSpiConfig_t, rxSfhssSpiConfig);
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
rx_spi_received_e sfhssSpiDataReceived(uint8_t *packet);
void sfhssSpiSetRcData(uint16_t *rcData, const uint8_t *payload);
void sfhssSpiBind(void);

View File

@ -47,6 +47,7 @@
#include "rx/nrf24_inav.h" #include "rx/nrf24_inav.h"
#include "rx/nrf24_kn.h" #include "rx/nrf24_kn.h"
#include "rx/flysky.h" #include "rx/flysky.h"
#include "rx/cc2500_sfhss.h"
uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
@ -145,7 +146,14 @@ STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
protocolSetRcDataFromPayload = flySkySetRcDataFromPayload; protocolSetRcDataFromPayload = flySkySetRcDataFromPayload;
break; break;
#endif #endif
#ifdef USE_RX_SFHSS_SPI
case RX_SPI_SFHSS:
protocolInit = sfhssSpiInit;
protocolDataReceived = sfhssSpiDataReceived;
protocolSetRcDataFromPayload = sfhssSpiSetRcData;
break;
} }
#endif
return true; return true;
} }

View File

@ -39,6 +39,7 @@ typedef enum {
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,
RX_SPI_SFHSS,
RX_SPI_PROTOCOL_COUNT RX_SPI_PROTOCOL_COUNT
} rx_spi_protocol_e; } rx_spi_protocol_e;

View File

@ -133,12 +133,13 @@
#define USE_RX_FRSKY_SPI_D #define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X #define USE_RX_FRSKY_SPI_X
#define USE_RX_FRSKY_SPI_TELEMETRY #define USE_RX_FRSKY_SPI_TELEMETRY
#define USE_RX_SFHSS_SPI
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI #define DEFAULT_RX_FEATURE FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X #define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define RX_SPI_INSTANCE SPI2 #define RX_SPI_INSTANCE SPI2
#define RX_NSS_PIN SPI2_NSS_PIN #define RX_NSS_PIN SPI2_NSS_PIN
#define RX_FRSKY_SPI_GDO_0_PIN PA8 #define RX_CC2500_SPI_GDO_0_PIN PA8
#define RX_FRSKY_SPI_LED_PIN PA10 #define RX_CC2500_SPI_LED_PIN PA10
#define BINDPLUG_PIN PA9 #define BINDPLUG_PIN PA9
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_MOTOR_STOP) #define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_MOTOR_STOP)
#endif #endif

View File

@ -15,8 +15,10 @@ else
ifeq ($(TARGET), CRAZYBEEF3FR) ifeq ($(TARGET), CRAZYBEEF3FR)
TARGET_SRC += \ TARGET_SRC += \
drivers/rx/rx_cc2500.c \ drivers/rx/rx_cc2500.c \
rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \ rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \ rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c
endif endif
endif endif

View File

@ -72,22 +72,23 @@
#define RX_SPI_INSTANCE SPI3 #define RX_SPI_INSTANCE SPI3
#define RX_NSS_PIN PA15 #define RX_NSS_PIN PA15
#define RX_FRSKY_SPI_DISABLE_CHIP_DETECTION #define RX_CC2500_SPI_DISABLE_CHIP_DETECTION
#define RX_FRSKY_SPI_GDO_0_PIN PC14 #define RX_CC2500_SPI_GDO_0_PIN PC14
#define RX_FRSKY_SPI_LED_PIN PB9 #define RX_CC2500_SPI_LED_PIN PB9
#define RX_FRSKY_SPI_LED_PIN_INVERTED #define RX_CC2500_SPI_LED_PIN_INVERTED
#define USE_RX_FRSKY_SPI_PA_LNA #define USE_RX_CC2500_SPI_PA_LNA
#define RX_FRSKY_SPI_TX_EN_PIN PA8 #define RX_CC2500_SPI_TX_EN_PIN PA8
#define RX_FRSKY_SPI_LNA_EN_PIN PA13 #define RX_CC2500_SPI_LNA_EN_PIN PA13
#define USE_RX_FRSKY_SPI_DIVERSITY #define USE_RX_CC2500_SPI_DIVERSITY
#define RX_FRSKY_SPI_ANT_SEL_PIN PA14 #define RX_CC2500_SPI_ANT_SEL_PIN PA14
#define BINDPLUG_PIN PB2 #define BINDPLUG_PIN PB2
#define USE_RX_FRSKY_SPI_D #define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X #define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI #define DEFAULT_RX_FEATURE FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X #define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY #define USE_RX_FRSKY_SPI_TELEMETRY

View File

@ -6,6 +6,8 @@ TARGET_SRC = \
drivers/accgyro/accgyro_spi_mpu6000.c \ drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/max7456.c \ drivers/max7456.c \
drivers/rx/rx_cc2500.c \ drivers/rx/rx_cc2500.c \
rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \ rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \ rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c

View File

@ -103,26 +103,27 @@
#define USE_RX_FRSKY_SPI_D #define USE_RX_FRSKY_SPI_D
#define USE_RX_FRSKY_SPI_X #define USE_RX_FRSKY_SPI_X
#define USE_RX_SFHSS_SPI
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI #define DEFAULT_RX_FEATURE FEATURE_RX_SPI
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X #define RX_SPI_DEFAULT_PROTOCOL RX_SPI_FRSKY_X
#define USE_RX_FRSKY_SPI_TELEMETRY #define USE_RX_FRSKY_SPI_TELEMETRY
#define RX_NSS_PIN PA4 #define RX_NSS_PIN PA4
#define RX_FRSKY_SPI_GDO_0_PIN PB0 #define RX_CC2500_SPI_GDO_0_PIN PB0
#define RX_FRSKY_SPI_LED_PIN PB6 #define RX_CC2500_SPI_LED_PIN PB6
#define USE_RX_FRSKY_SPI_PA_LNA #define USE_RX_CC2500_SPI_PA_LNA
#define RX_FRSKY_SPI_TX_EN_PIN PB1 #define RX_CC2500_SPI_TX_EN_PIN PB1
#define RX_FRSKY_SPI_LNA_EN_PIN PB11 #define RX_CC2500_SPI_LNA_EN_PIN PB11
#define USE_RX_FRSKY_SPI_DIVERSITY #define USE_RX_CC2500_SPI_DIVERSITY
#define RX_FRSKY_SPI_ANT_SEL_PIN PB2 #define RX_CC2500_SPI_ANT_SEL_PIN PB2
#define BINDPLUG_PIN PC13 #define BINDPLUG_PIN PC13

View File

@ -6,6 +6,8 @@ TARGET_SRC = \
drivers/accgyro/accgyro_mpu.c \ drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu6050.c \ drivers/accgyro/accgyro_mpu6050.c \
drivers/rx/rx_cc2500.c \ drivers/rx/rx_cc2500.c \
rx/cc2500_common.c \
rx/cc2500_frsky_shared.c \ rx/cc2500_frsky_shared.c \
rx/cc2500_frsky_d.c \ rx/cc2500_frsky_d.c \
rx/cc2500_frsky_x.c rx/cc2500_frsky_x.c \
rx/cc2500_sfhss.c

View File

@ -126,6 +126,12 @@
#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)
#define USE_RX_CC2500 #define USE_RX_CC2500
#define USE_RX_FRSKY_SPI #define USE_RX_FRSKY_SPI
#define USE_RX_BIND
#endif
#if defined(USE_RX_SFHSS_SPI)
#define USE_RX_CC2500
#define USE_RX_BIND
#endif #endif
// Burst dshot to default off if not configured explicitly by target // Burst dshot to default off if not configured explicitly by target