mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Made CC2500 (FrSky, SFHSS) SPI RX runtime configurable.
This commit is contained in:
parent
29db27584f
commit
86a5a30267
29 changed files with 329 additions and 184 deletions
|
@ -4411,8 +4411,16 @@ const cliResourceValue_t resourceTable[] = {
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RX_SPI
|
#ifdef USE_RX_SPI
|
||||||
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
|
DEFS( OWNER_RX_SPI_CS, PG_RX_SPI_CONFIG, rxSpiConfig_t, csnTag ),
|
||||||
|
DEFS( OWNER_RX_SPI_EXTI, PG_RX_SPI_CONFIG, rxSpiConfig_t, extiIoTag ),
|
||||||
DEFS( OWNER_RX_SPI_BIND, PG_RX_SPI_CONFIG, rxSpiConfig_t, bindIoTag ),
|
DEFS( OWNER_RX_SPI_BIND, PG_RX_SPI_CONFIG, rxSpiConfig_t, bindIoTag ),
|
||||||
DEFS( OWNER_RX_SPI_LED, PG_RX_SPI_CONFIG, rxSpiConfig_t, ledIoTag ),
|
DEFS( OWNER_RX_SPI_LED, PG_RX_SPI_CONFIG, rxSpiConfig_t, ledIoTag ),
|
||||||
|
#if defined(USE_RX_SPI_CC2500) && defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
|
DEFS( OWNER_RX_SPI_CC2500_TX_EN, PG_RX_SPI_CC2500_CONFIG, rxCc2500SpiConfig_t, txEnIoTag ),
|
||||||
|
DEFS( OWNER_RX_SPI_CC2500_LNA_EN, PG_RX_SPI_CC2500_CONFIG, rxCc2500SpiConfig_t, lnaEnIoTag ),
|
||||||
|
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
|
||||||
|
DEFS( OWNER_RX_SPI_CC2500_ANT_SEL, PG_RX_SPI_CC2500_CONFIG, rxCc2500SpiConfig_t, antSelIoTag ),
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GYRO_EXTI
|
#ifdef USE_GYRO_EXTI
|
||||||
DEFW( OWNER_GYRO_EXTI, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, extiTag, MAX_GYRODEV_COUNT ),
|
DEFW( OWNER_GYRO_EXTI, PG_GYRO_DEVICE_CONFIG, gyroDeviceConfig_t, extiTag, MAX_GYRODEV_COUNT ),
|
||||||
|
|
|
@ -79,8 +79,9 @@
|
||||||
#include "pg/pinio.h"
|
#include "pg/pinio.h"
|
||||||
#include "pg/piniobox.h"
|
#include "pg/piniobox.h"
|
||||||
#include "pg/rx.h"
|
#include "pg/rx.h"
|
||||||
#include "pg/rx_spi.h"
|
|
||||||
#include "pg/rx_pwm.h"
|
#include "pg/rx_pwm.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
#include "pg/sdcard.h"
|
#include "pg/sdcard.h"
|
||||||
#include "pg/vcd.h"
|
#include "pg/vcd.h"
|
||||||
#include "pg/usb.h"
|
#include "pg/usb.h"
|
||||||
|
@ -1300,12 +1301,13 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_RX_FRSKY_SPI
|
#ifdef USE_RX_FRSKY_SPI
|
||||||
{ "frsky_spi_autobind", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, autoBind) },
|
{ "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_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindTxId) },
|
{ "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_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -127, 127 }, PG_RX_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindOffset) },
|
{ "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_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, bindHopData) },
|
{ "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_FRSKY_SPI_CONFIG, offsetof(rxFrSkySpiConfig_t, rxNum) },
|
{ "frsky_x_rx_num", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_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) },
|
{ "frsky_spi_a1_source", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RX_FRSKY_SPI_A1_SOURCE }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, a1Source) },
|
||||||
|
{ "cc2500_spi_chip_detect", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CC2500_SPI_CONFIG, offsetof(rxCc2500SpiConfig_t, chipDetectEnabled) },
|
||||||
#endif
|
#endif
|
||||||
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
|
{ "led_inversion", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, ((1 << STATUS_LED_NUMBER) - 1) }, PG_STATUS_LED_CONFIG, offsetof(statusLedConfig_t, inversion) },
|
||||||
#ifdef USE_DASHBOARD
|
#ifdef USE_DASHBOARD
|
||||||
|
|
|
@ -80,4 +80,8 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||||
"RX_SPI_BIND",
|
"RX_SPI_BIND",
|
||||||
"RX_SPI_LED",
|
"RX_SPI_LED",
|
||||||
"PREINIT",
|
"PREINIT",
|
||||||
|
"RX_SPI_EXTI",
|
||||||
|
"RX_SPI_CC2500_TX_EN",
|
||||||
|
"RX_SPI_CC2500_LNA_EN",
|
||||||
|
"RX_SPI_CC2500_ANT_SEL",
|
||||||
};
|
};
|
||||||
|
|
|
@ -78,6 +78,10 @@ typedef enum {
|
||||||
OWNER_RX_SPI_BIND,
|
OWNER_RX_SPI_BIND,
|
||||||
OWNER_RX_SPI_LED,
|
OWNER_RX_SPI_LED,
|
||||||
OWNER_PREINIT,
|
OWNER_PREINIT,
|
||||||
|
OWNER_RX_SPI_EXTI,
|
||||||
|
OWNER_RX_SPI_CC2500_TX_EN,
|
||||||
|
OWNER_RX_SPI_CC2500_LNA_EN,
|
||||||
|
OWNER_RX_SPI_CC2500_ANT_SEL,
|
||||||
OWNER_TOTAL_COUNT
|
OWNER_TOTAL_COUNT
|
||||||
} resourceOwner_e;
|
} resourceOwner_e;
|
||||||
|
|
||||||
|
|
|
@ -57,7 +57,7 @@ void a7105extiHandler(extiCallbackRec_t* cb)
|
||||||
void A7105Init(uint32_t id)
|
void A7105Init(uint32_t id)
|
||||||
{
|
{
|
||||||
spiDeviceByInstance(RX_SPI_INSTANCE);
|
spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||||
rxIntIO = IOGetByTag(IO_TAG(RX_IRQ_PIN)); /* config receiver IRQ pin */
|
rxIntIO = IOGetByTag(IO_TAG(RX_EXTI_PIN)); /* config receiver IRQ pin */
|
||||||
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
|
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
|
||||||
EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler);
|
EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler);
|
||||||
EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_RISING);
|
EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_RISING);
|
||||||
|
|
|
@ -72,7 +72,7 @@ bool cyrf6936RxFinished(uint32_t *timeStamp)
|
||||||
bool cyrf6936Init(void)
|
bool cyrf6936Init(void)
|
||||||
{
|
{
|
||||||
spiDeviceByInstance(RX_SPI_INSTANCE);
|
spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||||
rxIntIO = IOGetByTag(IO_TAG(RX_IRQ_PIN));
|
rxIntIO = IOGetByTag(IO_TAG(RX_EXTI_PIN));
|
||||||
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
|
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
|
||||||
EXTIHandlerInit(&cyrf6936extiCallbackRec, cyrf6936ExtiHandler);
|
EXTIHandlerInit(&cyrf6936extiCallbackRec, cyrf6936ExtiHandler);
|
||||||
EXTIConfig(rxIntIO, &cyrf6936extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_FALLING);
|
EXTIConfig(rxIntIO, &cyrf6936extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_FALLING);
|
||||||
|
|
|
@ -117,7 +117,7 @@
|
||||||
#define PG_SPI_PIN_CONFIG 520
|
#define PG_SPI_PIN_CONFIG 520
|
||||||
#define PG_ESCSERIAL_CONFIG 521
|
#define PG_ESCSERIAL_CONFIG 521
|
||||||
#define PG_CAMERA_CONTROL_CONFIG 522
|
#define PG_CAMERA_CONTROL_CONFIG 522
|
||||||
#define PG_RX_FRSKY_SPI_CONFIG 523
|
#define PG_RX_CC2500_SPI_CONFIG 523
|
||||||
#define PG_MAX7456_CONFIG 524
|
#define PG_MAX7456_CONFIG 524
|
||||||
#define PG_FLYSKY_CONFIG 525
|
#define PG_FLYSKY_CONFIG 525
|
||||||
#define PG_TIME_CONFIG 526
|
#define PG_TIME_CONFIG 526
|
||||||
|
|
|
@ -41,6 +41,8 @@ void pgResetFn_rxSpiConfig(rxSpiConfig_t *rxSpiConfig)
|
||||||
rxSpiConfig->csnTag = IO_TAG(RX_NSS_PIN);
|
rxSpiConfig->csnTag = IO_TAG(RX_NSS_PIN);
|
||||||
rxSpiConfig->spibus = SPI_DEV_TO_CFG(spiDeviceByInstance(RX_SPI_INSTANCE));
|
rxSpiConfig->spibus = SPI_DEV_TO_CFG(spiDeviceByInstance(RX_SPI_INSTANCE));
|
||||||
|
|
||||||
|
rxSpiConfig->extiIoTag = IO_TAG(RX_SPI_EXTI_PIN);
|
||||||
|
|
||||||
rxSpiConfig->bindIoTag = IO_TAG(BINDPLUG_PIN);
|
rxSpiConfig->bindIoTag = IO_TAG(BINDPLUG_PIN);
|
||||||
rxSpiConfig->ledIoTag = IO_TAG(RX_SPI_LED_PIN);
|
rxSpiConfig->ledIoTag = IO_TAG(RX_SPI_LED_PIN);
|
||||||
#ifdef RX_SPI_LED_INVERTED
|
#ifdef RX_SPI_LED_INVERTED
|
||||||
|
|
|
@ -39,6 +39,7 @@ typedef struct rxSpiConfig_s {
|
||||||
ioTag_t ledIoTag;
|
ioTag_t ledIoTag;
|
||||||
uint8_t ledInversion;
|
uint8_t ledInversion;
|
||||||
|
|
||||||
|
ioTag_t extiIoTag;
|
||||||
} rxSpiConfig_t;
|
} rxSpiConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(rxSpiConfig_t, rxSpiConfig);
|
PG_DECLARE(rxSpiConfig_t, rxSpiConfig);
|
||||||
|
|
49
src/main/pg/rx_spi_cc2500.c
Normal file
49
src/main/pg/rx_spi_cc2500.c
Normal file
|
@ -0,0 +1,49 @@
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
|
||||||
|
#if defined(USE_RX_CC2500)
|
||||||
|
|
||||||
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/pg_ids.h"
|
||||||
|
|
||||||
|
#include "rx_spi_cc2500.h"
|
||||||
|
|
||||||
|
PG_REGISTER_WITH_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig, PG_RX_CC2500_SPI_CONFIG, 1);
|
||||||
|
|
||||||
|
PG_RESET_TEMPLATE(rxCc2500SpiConfig_t, rxCc2500SpiConfig,
|
||||||
|
.autoBind = false,
|
||||||
|
.bindTxId = {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,
|
||||||
|
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||||
|
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0},
|
||||||
|
.rxNum = 0,
|
||||||
|
.a1Source = FRSKY_SPI_A1_SOURCE_VBAT,
|
||||||
|
.chipDetectEnabled = true,
|
||||||
|
.txEnIoTag = IO_TAG(RX_CC2500_SPI_TX_EN_PIN),
|
||||||
|
.lnaEnIoTag = IO_TAG(RX_CC2500_SPI_LNA_EN_PIN),
|
||||||
|
.antSelIoTag = IO_TAG(RX_CC2500_SPI_ANT_SEL_PIN),
|
||||||
|
);
|
||||||
|
#endif
|
46
src/main/pg/rx_spi_cc2500.h
Normal file
46
src/main/pg/rx_spi_cc2500.h
Normal file
|
@ -0,0 +1,46 @@
|
||||||
|
/*
|
||||||
|
* 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 "drivers/io_types.h"
|
||||||
|
|
||||||
|
#include "pg/pg.h"
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
FRSKY_SPI_A1_SOURCE_VBAT = 0,
|
||||||
|
FRSKY_SPI_A1_SOURCE_EXTADC,
|
||||||
|
FRSKY_SPI_A1_SOURCE_CONST
|
||||||
|
} frSkySpiA1Source_e;
|
||||||
|
|
||||||
|
typedef struct rxFrSkySpiConfig_s {
|
||||||
|
uint8_t autoBind;
|
||||||
|
uint8_t bindTxId[2];
|
||||||
|
int8_t bindOffset;
|
||||||
|
uint8_t bindHopData[50];
|
||||||
|
uint8_t rxNum;
|
||||||
|
uint8_t a1Source;
|
||||||
|
uint8_t chipDetectEnabled;
|
||||||
|
ioTag_t txEnIoTag;
|
||||||
|
ioTag_t lnaEnIoTag;
|
||||||
|
ioTag_t antSelIoTag;
|
||||||
|
} rxCc2500SpiConfig_t;
|
||||||
|
|
||||||
|
PG_DECLARE(rxCc2500SpiConfig_t, rxCc2500SpiConfig);
|
|
@ -26,28 +26,31 @@
|
||||||
|
|
||||||
#include "common/maths.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/io.h"
|
||||||
|
#include "drivers/rx/rx_cc2500.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/pg_ids.h"
|
||||||
|
#include "pg/rx.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
|
|
||||||
#include "rx/cc2500_common.h"
|
#include "cc2500_common.h"
|
||||||
|
|
||||||
static IO_t gdoPin;
|
static IO_t gdoPin;
|
||||||
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
static IO_t txEnPin;
|
static IO_t txEnPin;
|
||||||
static IO_t rxLnaEnPin;
|
static IO_t rxLnaEnPin;
|
||||||
|
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
|
||||||
static IO_t antSelPin;
|
static IO_t antSelPin;
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
static int16_t rssiDbm;
|
static int16_t rssiDbm;
|
||||||
|
|
||||||
uint16_t cc2500getRssiDbm(void)
|
uint16_t cc2500getRssiDbm(void)
|
||||||
|
@ -76,23 +79,29 @@ void cc2500switchAntennae(void)
|
||||||
{
|
{
|
||||||
static bool alternativeAntennaSelected = true;
|
static bool alternativeAntennaSelected = true;
|
||||||
|
|
||||||
|
if (antSelPin) {
|
||||||
if (alternativeAntennaSelected) {
|
if (alternativeAntennaSelected) {
|
||||||
IOLo(antSelPin);
|
IOLo(antSelPin);
|
||||||
} else {
|
} else {
|
||||||
IOHi(antSelPin);
|
IOHi(antSelPin);
|
||||||
}
|
}
|
||||||
alternativeAntennaSelected = !alternativeAntennaSelected;
|
alternativeAntennaSelected = !alternativeAntennaSelected;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
void cc2500TxEnable(void)
|
void cc2500TxEnable(void)
|
||||||
{
|
{
|
||||||
|
if (txEnPin) {
|
||||||
IOHi(txEnPin);
|
IOHi(txEnPin);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void cc2500TxDisable(void)
|
void cc2500TxDisable(void)
|
||||||
{
|
{
|
||||||
|
if (txEnPin) {
|
||||||
IOLo(txEnPin);
|
IOLo(txEnPin);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -110,7 +119,7 @@ static bool cc2500SpiDetect(void)
|
||||||
bool cc2500SpiInit(void)
|
bool cc2500SpiInit(void)
|
||||||
{
|
{
|
||||||
#if !defined(RX_CC2500_SPI_DISABLE_CHIP_DETECTION)
|
#if !defined(RX_CC2500_SPI_DISABLE_CHIP_DETECTION)
|
||||||
if (!cc2500SpiDetect()) {
|
if (rxCc2500SpiConfig()->chipDetectEnabled && !cc2500SpiDetect()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
|
@ -122,28 +131,39 @@ bool cc2500SpiInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
// gpio init here
|
// gpio init here
|
||||||
gdoPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_GDO_0_PIN));
|
gdoPin = IOGetByTag(rxSpiConfig()->extiIoTag);
|
||||||
|
|
||||||
|
if (!gdoPin) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
IOInit(gdoPin, OWNER_RX_SPI, 0);
|
IOInit(gdoPin, OWNER_RX_SPI, 0);
|
||||||
IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
|
IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
|
||||||
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
rxLnaEnPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_LNA_EN_PIN));
|
if (rxCc2500SpiConfig()->lnaEnIoTag) {
|
||||||
|
rxLnaEnPin = IOGetByTag(rxCc2500SpiConfig()->lnaEnIoTag);
|
||||||
IOInit(rxLnaEnPin, OWNER_RX_SPI, 0);
|
IOInit(rxLnaEnPin, OWNER_RX_SPI, 0);
|
||||||
IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
|
IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
|
||||||
|
|
||||||
IOHi(rxLnaEnPin); // always on at the moment
|
IOHi(rxLnaEnPin); // always on at the moment
|
||||||
txEnPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_TX_EN_PIN));
|
}
|
||||||
|
if (rxCc2500SpiConfig()->txEnIoTag) {
|
||||||
|
txEnPin = IOGetByTag(rxCc2500SpiConfig()->txEnIoTag);
|
||||||
IOInit(txEnPin, OWNER_RX_SPI, 0);
|
IOInit(txEnPin, OWNER_RX_SPI, 0);
|
||||||
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
|
IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
|
||||||
|
}
|
||||||
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
|
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
|
||||||
antSelPin = IOGetByTag(IO_TAG(RX_CC2500_SPI_ANT_SEL_PIN));
|
if (rxCc2500SpiConfig()->antSelIoTag) {
|
||||||
|
antSelPin = IOGetByTag(rxCc2500SpiConfig()->antSelIoTag);
|
||||||
IOInit(antSelPin, OWNER_RX_SPI, 0);
|
IOInit(antSelPin, OWNER_RX_SPI, 0);
|
||||||
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
|
IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
|
||||||
|
|
||||||
|
IOHi(antSelPin);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif // USE_RX_CC2500_SPI_PA_LNA
|
#endif // USE_RX_CC2500_SPI_PA_LNA
|
||||||
|
|
||||||
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
#if defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
#if defined(USE_RX_CC2500_SPI_DIVERSITY)
|
|
||||||
IOHi(antSelPin);
|
|
||||||
#endif
|
|
||||||
cc2500TxDisable();
|
cc2500TxDisable();
|
||||||
#endif // USE_RX_CC2500_SPI_PA_LNA
|
#endif // USE_RX_CC2500_SPI_PA_LNA
|
||||||
|
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "pg/pg.h"
|
|
||||||
|
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
|
|
||||||
uint16_t cc2500getRssiDbm(void);
|
uint16_t cc2500getRssiDbm(void);
|
||||||
|
|
|
@ -20,27 +20,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "pg/pg.h"
|
|
||||||
|
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
FRSKY_SPI_A1_SOURCE_VBAT = 0,
|
|
||||||
FRSKY_SPI_A1_SOURCE_EXTADC,
|
|
||||||
FRSKY_SPI_A1_SOURCE_CONST
|
|
||||||
} frSkySpiA1Source_e;
|
|
||||||
|
|
||||||
typedef struct rxFrSkySpiConfig_s {
|
|
||||||
uint8_t autoBind;
|
|
||||||
uint8_t bindTxId[2];
|
|
||||||
int8_t bindOffset;
|
|
||||||
uint8_t bindHopData[50];
|
|
||||||
uint8_t rxNum;
|
|
||||||
uint8_t a1Source;
|
|
||||||
} rxFrSkySpiConfig_t;
|
|
||||||
|
|
||||||
PG_DECLARE(rxFrSkySpiConfig_t, rxFrSkySpiConfig);
|
|
||||||
|
|
||||||
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||||
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);
|
||||||
|
|
|
@ -30,9 +30,6 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
|
||||||
#include "pg/rx_spi.h"
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
@ -46,6 +43,10 @@
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#include "pg/rx.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
|
|
||||||
#include "rx/rx_spi_common.h"
|
#include "rx/rx_spi_common.h"
|
||||||
#include "rx/cc2500_common.h"
|
#include "rx/cc2500_common.h"
|
||||||
#include "rx/cc2500_frsky_common.h"
|
#include "rx/cc2500_frsky_common.h"
|
||||||
|
@ -115,7 +116,7 @@ static void frSkyDTelemetryWriteByte(const char data)
|
||||||
static void buildTelemetryFrame(uint8_t *packet)
|
static void buildTelemetryFrame(uint8_t *packet)
|
||||||
{
|
{
|
||||||
uint8_t a1Value;
|
uint8_t a1Value;
|
||||||
switch (rxFrSkySpiConfig()->a1Source) {
|
switch (rxCc2500SpiConfig()->a1Source) {
|
||||||
case FRSKY_SPI_A1_SOURCE_VBAT:
|
case FRSKY_SPI_A1_SOURCE_VBAT:
|
||||||
a1Value = (getBatteryVoltage() / 5) & 0xff;
|
a1Value = (getBatteryVoltage() / 5) & 0xff;
|
||||||
break;
|
break;
|
||||||
|
@ -129,8 +130,8 @@ static void buildTelemetryFrame(uint8_t *packet)
|
||||||
const uint8_t a2Value = (adcGetChannel(ADC_RSSI)) >> 4;
|
const uint8_t a2Value = (adcGetChannel(ADC_RSSI)) >> 4;
|
||||||
telemetryId = packet[4];
|
telemetryId = packet[4];
|
||||||
frame[0] = 0x11; // length
|
frame[0] = 0x11; // length
|
||||||
frame[1] = rxFrSkySpiConfig()->bindTxId[0];
|
frame[1] = rxCc2500SpiConfig()->bindTxId[0];
|
||||||
frame[2] = rxFrSkySpiConfig()->bindTxId[1];
|
frame[2] = rxCc2500SpiConfig()->bindTxId[1];
|
||||||
frame[3] = a1Value;
|
frame[3] = a1Value;
|
||||||
frame[4] = a2Value;
|
frame[4] = a2Value;
|
||||||
frame[5] = (uint8_t)cc2500getRssiDbm();
|
frame[5] = (uint8_t)cc2500getRssiDbm();
|
||||||
|
@ -223,8 +224,8 @@ rx_spi_received_e frSkyDHandlePacket(uint8_t * const packet, uint8_t * const pro
|
||||||
missingPackets = 0;
|
missingPackets = 0;
|
||||||
timeoutUs = 1;
|
timeoutUs = 1;
|
||||||
if (packet[0] == 0x11) {
|
if (packet[0] == 0x11) {
|
||||||
if ((packet[1] == rxFrSkySpiConfig()->bindTxId[0]) &&
|
if ((packet[1] == rxCc2500SpiConfig()->bindTxId[0]) &&
|
||||||
(packet[2] == rxFrSkySpiConfig()->bindTxId[1])) {
|
(packet[2] == rxCc2500SpiConfig()->bindTxId[1])) {
|
||||||
rxSpiLedOn();
|
rxSpiLedOn();
|
||||||
nextChannel(1);
|
nextChannel(1);
|
||||||
cc2500setRssiDbm(packet[18]);
|
cc2500setRssiDbm(packet[18]);
|
||||||
|
|
|
@ -26,17 +26,16 @@
|
||||||
|
|
||||||
#include "common/maths.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/rx/rx_cc2500.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#include "pg/rx.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
#include "rx/rx_spi_common.h"
|
#include "rx/rx_spi_common.h"
|
||||||
|
@ -68,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;
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig, PG_RX_FRSKY_SPI_CONFIG, 1);
|
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig,
|
|
||||||
.autoBind = false,
|
|
||||||
.bindTxId = {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,
|
|
||||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
|
||||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0},
|
|
||||||
.rxNum = 0,
|
|
||||||
.a1Source = FRSKY_SPI_A1_SOURCE_VBAT,
|
|
||||||
);
|
|
||||||
|
|
||||||
static void initialise() {
|
static void initialise() {
|
||||||
cc2500Reset();
|
cc2500Reset();
|
||||||
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
|
cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
|
||||||
|
@ -169,9 +154,9 @@ static void initialise() {
|
||||||
|
|
||||||
void initialiseData(uint8_t adr)
|
void initialiseData(uint8_t adr)
|
||||||
{
|
{
|
||||||
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)rxFrSkySpiConfig()->bindOffset);
|
cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)rxCc2500SpiConfig()->bindOffset);
|
||||||
cc2500WriteReg(CC2500_18_MCSM0, 0x8);
|
cc2500WriteReg(CC2500_18_MCSM0, 0x8);
|
||||||
cc2500WriteReg(CC2500_09_ADDR, adr ? 0x03 : rxFrSkySpiConfig()->bindTxId[0]);
|
cc2500WriteReg(CC2500_09_ADDR, adr ? 0x03 : rxCc2500SpiConfig()->bindTxId[0]);
|
||||||
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0D);
|
cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0D);
|
||||||
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
|
cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
|
||||||
delay(10);
|
delay(10);
|
||||||
|
@ -214,7 +199,7 @@ static bool tuneRx(uint8_t *packet)
|
||||||
uint8_t Lqi = packet[ccLen - 1] & 0x7F;
|
uint8_t Lqi = packet[ccLen - 1] & 0x7F;
|
||||||
// higher lqi represent better link quality
|
// higher lqi represent better link quality
|
||||||
if (Lqi > 50) {
|
if (Lqi > 50) {
|
||||||
rxFrSkySpiConfigMutable()->bindOffset = bindOffset;
|
rxCc2500SpiConfigMutable()->bindOffset = bindOffset;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -252,14 +237,14 @@ static bool getBind1(uint8_t *packet)
|
||||||
if (packet[ccLen - 1] & 0x80) {
|
if (packet[ccLen - 1] & 0x80) {
|
||||||
if (packet[2] == 0x01) {
|
if (packet[2] == 0x01) {
|
||||||
if (packet[5] == 0x00) {
|
if (packet[5] == 0x00) {
|
||||||
rxFrSkySpiConfigMutable()->bindTxId[0] = packet[3];
|
rxCc2500SpiConfigMutable()->bindTxId[0] = packet[3];
|
||||||
rxFrSkySpiConfigMutable()->bindTxId[1] = packet[4];
|
rxCc2500SpiConfigMutable()->bindTxId[1] = packet[4];
|
||||||
for (uint8_t n = 0; n < 5; n++) {
|
for (uint8_t n = 0; n < 5; n++) {
|
||||||
rxFrSkySpiConfigMutable()->bindHopData[packet[5] + n] =
|
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] =
|
||||||
packet[6 + n];
|
packet[6 + n];
|
||||||
}
|
}
|
||||||
|
|
||||||
rxFrSkySpiConfigMutable()->rxNum = packet[12];
|
rxCc2500SpiConfigMutable()->rxNum = packet[12];
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -280,13 +265,13 @@ static bool getBind2(uint8_t *packet)
|
||||||
cc2500ReadFifo(packet, ccLen);
|
cc2500ReadFifo(packet, ccLen);
|
||||||
if (packet[ccLen - 1] & 0x80) {
|
if (packet[ccLen - 1] & 0x80) {
|
||||||
if (packet[2] == 0x01) {
|
if (packet[2] == 0x01) {
|
||||||
if ((packet[3] == rxFrSkySpiConfig()->bindTxId[0]) &&
|
if ((packet[3] == rxCc2500SpiConfig()->bindTxId[0]) &&
|
||||||
(packet[4] == rxFrSkySpiConfig()->bindTxId[1])) {
|
(packet[4] == rxCc2500SpiConfig()->bindTxId[1])) {
|
||||||
if (packet[5] == bindIdx) {
|
if (packet[5] == bindIdx) {
|
||||||
#if defined(DJTS)
|
#if defined(DJTS)
|
||||||
if (packet[5] == 0x2D) {
|
if (packet[5] == 0x2D) {
|
||||||
for (uint8_t i = 0; i < 2; i++) {
|
for (uint8_t i = 0; i < 2; i++) {
|
||||||
rxFrSkySpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i];
|
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i];
|
||||||
}
|
}
|
||||||
listLength = 47;
|
listLength = 47;
|
||||||
|
|
||||||
|
@ -303,7 +288,7 @@ static bool getBind2(uint8_t *packet)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
rxFrSkySpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
|
rxCc2500SpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
|
||||||
}
|
}
|
||||||
|
|
||||||
bindIdx = bindIdx + 5;
|
bindIdx = bindIdx + 5;
|
||||||
|
@ -336,7 +321,7 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case STATE_BIND:
|
case STATE_BIND:
|
||||||
if (rxSpiCheckBindRequested(true) || rxFrSkySpiConfig()->autoBind) {
|
if (rxSpiCheckBindRequested(true) || rxCc2500SpiConfig()->autoBind) {
|
||||||
rxSpiLedOn();
|
rxSpiLedOn();
|
||||||
initTuneRx();
|
initTuneRx();
|
||||||
|
|
||||||
|
@ -370,7 +355,7 @@ rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case STATE_BIND_COMPLETE:
|
case STATE_BIND_COMPLETE:
|
||||||
if (!rxFrSkySpiConfig()->autoBind) {
|
if (!rxCc2500SpiConfig()->autoBind) {
|
||||||
writeEEPROM();
|
writeEEPROM();
|
||||||
} else {
|
} else {
|
||||||
uint8_t ctr = 80;
|
uint8_t ctr = 80;
|
||||||
|
@ -408,12 +393,12 @@ void nextChannel(uint8_t skip)
|
||||||
}
|
}
|
||||||
cc2500Strobe(CC2500_SIDLE);
|
cc2500Strobe(CC2500_SIDLE);
|
||||||
cc2500WriteReg(CC2500_23_FSCAL3,
|
cc2500WriteReg(CC2500_23_FSCAL3,
|
||||||
calData[rxFrSkySpiConfig()->bindHopData[channr]][0]);
|
calData[rxCc2500SpiConfig()->bindHopData[channr]][0]);
|
||||||
cc2500WriteReg(CC2500_24_FSCAL2,
|
cc2500WriteReg(CC2500_24_FSCAL2,
|
||||||
calData[rxFrSkySpiConfig()->bindHopData[channr]][1]);
|
calData[rxCc2500SpiConfig()->bindHopData[channr]][1]);
|
||||||
cc2500WriteReg(CC2500_25_FSCAL1,
|
cc2500WriteReg(CC2500_25_FSCAL1,
|
||||||
calData[rxFrSkySpiConfig()->bindHopData[channr]][2]);
|
calData[rxCc2500SpiConfig()->bindHopData[channr]][2]);
|
||||||
cc2500WriteReg(CC2500_0A_CHANNR, rxFrSkySpiConfig()->bindHopData[channr]);
|
cc2500WriteReg(CC2500_0A_CHANNR, rxCc2500SpiConfig()->bindHopData[channr]);
|
||||||
if (spiProtocol == RX_SPI_FRSKY_D) {
|
if (spiProtocol == RX_SPI_FRSKY_D) {
|
||||||
cc2500Strobe(CC2500_SFRX);
|
cc2500Strobe(CC2500_SFRX);
|
||||||
}
|
}
|
||||||
|
|
|
@ -19,7 +19,6 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <sys/_stdint.h>
|
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -28,9 +27,6 @@
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "pg/rx.h"
|
|
||||||
#include "pg/rx_spi.h"
|
|
||||||
|
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
@ -47,6 +43,10 @@
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#include "pg/rx.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
|
|
||||||
#include "rx/rx_spi_common.h"
|
#include "rx/rx_spi_common.h"
|
||||||
#include "rx/cc2500_common.h"
|
#include "rx/cc2500_common.h"
|
||||||
#include "rx/cc2500_frsky_common.h"
|
#include "rx/cc2500_frsky_common.h"
|
||||||
|
@ -191,15 +191,15 @@ static void buildTelemetryFrame(uint8_t *packet)
|
||||||
static bool evenRun = false;
|
static bool evenRun = false;
|
||||||
|
|
||||||
frame[0] = 0x0E;//length
|
frame[0] = 0x0E;//length
|
||||||
frame[1] = rxFrSkySpiConfig()->bindTxId[0];
|
frame[1] = rxCc2500SpiConfig()->bindTxId[0];
|
||||||
frame[2] = rxFrSkySpiConfig()->bindTxId[1];
|
frame[2] = rxCc2500SpiConfig()->bindTxId[1];
|
||||||
frame[3] = packet[3];
|
frame[3] = packet[3];
|
||||||
|
|
||||||
if (evenRun) {
|
if (evenRun) {
|
||||||
frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
|
frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
|
||||||
} else {
|
} else {
|
||||||
uint8_t a1Value;
|
uint8_t a1Value;
|
||||||
switch (rxFrSkySpiConfig()->a1Source) {
|
switch (rxCc2500SpiConfig()->a1Source) {
|
||||||
case FRSKY_SPI_A1_SOURCE_VBAT:
|
case FRSKY_SPI_A1_SOURCE_VBAT:
|
||||||
a1Value = getLegacyBatteryVoltage() & 0x7f;
|
a1Value = getLegacyBatteryVoltage() & 0x7f;
|
||||||
break;
|
break;
|
||||||
|
@ -309,9 +309,9 @@ bool isValidPacket(const uint8_t *packet)
|
||||||
uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
|
uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
|
||||||
if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
|
if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
|
||||||
(packet[0] == packetLength - 3) &&
|
(packet[0] == packetLength - 3) &&
|
||||||
(packet[1] == rxFrSkySpiConfig()->bindTxId[0]) &&
|
(packet[1] == rxCc2500SpiConfig()->bindTxId[0]) &&
|
||||||
(packet[2] == rxFrSkySpiConfig()->bindTxId[1]) &&
|
(packet[2] == rxCc2500SpiConfig()->bindTxId[1]) &&
|
||||||
(rxFrSkySpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxFrSkySpiConfig()->rxNum)) {
|
(rxCc2500SpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxCc2500SpiConfig()->rxNum)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -29,26 +29,22 @@
|
||||||
|
|
||||||
#include "common/maths.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/rx/rx_cc2500.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "fc/config.h"
|
#include "fc/config.h"
|
||||||
|
|
||||||
|
#include "pg/rx.h"
|
||||||
|
#include "pg/rx_spi.h"
|
||||||
|
#include "pg/rx_spi_cc2500.h"
|
||||||
|
|
||||||
|
#include "rx/cc2500_common.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/rx_spi.h"
|
#include "rx/rx_spi.h"
|
||||||
#include "rx/rx_spi_common.h"
|
#include "rx/rx_spi_common.h"
|
||||||
|
|
||||||
#include "rx/cc2500_common.h"
|
#include "cc2500_sfhss.h"
|
||||||
#include "rx/cc2500_frsky_common.h"
|
|
||||||
#include "rx/cc2500_sfhss.h"
|
|
||||||
|
|
||||||
//void cliPrintLinef(const char *format, ...);
|
|
||||||
|
|
||||||
#define BIND_CH 15
|
#define BIND_CH 15
|
||||||
#define SFHSS_PACKET_LEN 15
|
#define SFHSS_PACKET_LEN 15
|
||||||
|
@ -97,7 +93,7 @@ static void initialise()
|
||||||
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x0C);
|
cc2500WriteReg(CC2500_08_PKTCTRL0, 0x0C);
|
||||||
cc2500WriteReg(CC2500_09_ADDR, 0x29);
|
cc2500WriteReg(CC2500_09_ADDR, 0x29);
|
||||||
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x06);
|
cc2500WriteReg(CC2500_0B_FSCTRL1, 0x06);
|
||||||
cc2500WriteReg(CC2500_0C_FSCTRL0, (rxFrSkySpiConfigMutable()->bindOffset));
|
cc2500WriteReg(CC2500_0C_FSCTRL0, rxCc2500SpiConfig()->bindOffset);
|
||||||
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
|
cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
|
||||||
cc2500WriteReg(CC2500_0E_FREQ1, 0x4E);
|
cc2500WriteReg(CC2500_0E_FREQ1, 0x4E);
|
||||||
cc2500WriteReg(CC2500_0F_FREQ0, 0xC4);
|
cc2500WriteReg(CC2500_0F_FREQ0, 0xC4);
|
||||||
|
@ -167,8 +163,8 @@ static bool sfhssPacketParse(uint8_t *packet, bool check_txid)
|
||||||
}
|
}
|
||||||
|
|
||||||
if (check_txid) {
|
if (check_txid) {
|
||||||
if ((rxFrSkySpiConfigMutable()->bindTxId[0] != GET_TXID1(packet)) ||
|
if ((rxCc2500SpiConfigMutable()->bindTxId[0] != GET_TXID1(packet)) ||
|
||||||
(rxFrSkySpiConfigMutable()->bindTxId[1] != GET_TXID2(packet))) {
|
(rxCc2500SpiConfigMutable()->bindTxId[1] != GET_TXID2(packet))) {
|
||||||
return false; /* txid fail */
|
return false; /* txid fail */
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -216,8 +212,8 @@ static bool tune1Rx(uint8_t *packet)
|
||||||
if (sfhssRecv(packet)) {
|
if (sfhssRecv(packet)) {
|
||||||
if (sfhssPacketParse(packet, false)) {
|
if (sfhssPacketParse(packet, false)) {
|
||||||
if ((packet[SFHSS_PACKET_LEN - 1] & 0x7F) > 40 ) { /* lqi */
|
if ((packet[SFHSS_PACKET_LEN - 1] & 0x7F) > 40 ) { /* lqi */
|
||||||
rxFrSkySpiConfigMutable()->bindTxId[0] = GET_TXID1(packet);
|
rxCc2500SpiConfigMutable()->bindTxId[0] = GET_TXID1(packet);
|
||||||
rxFrSkySpiConfigMutable()->bindTxId[1] = GET_TXID2(packet);
|
rxCc2500SpiConfigMutable()->bindTxId[1] = GET_TXID2(packet);
|
||||||
bindOffset_max = bindOffset_min;
|
bindOffset_max = bindOffset_min;
|
||||||
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MAX, bindOffset_max);
|
DEBUG_SET(DEBUG_RX_SFHSS_SPI, DEBUG_DATA_OFFSET_MAX, bindOffset_max);
|
||||||
cc2500Strobe(CC2500_SRX);
|
cc2500Strobe(CC2500_SRX);
|
||||||
|
@ -343,7 +339,7 @@ rx_spi_received_e sfhssSpiDataReceived(uint8_t *packet)
|
||||||
initTuneRx();
|
initTuneRx();
|
||||||
SET_STATE(STATE_BIND_TUNING1); // retry
|
SET_STATE(STATE_BIND_TUNING1); // retry
|
||||||
} else {
|
} else {
|
||||||
rxFrSkySpiConfigMutable()->bindOffset = ((int16_t)bindOffset_max + (int16_t)bindOffset_min) / 2 ;
|
rxCc2500SpiConfigMutable()->bindOffset = ((int16_t)bindOffset_max + (int16_t)bindOffset_min) / 2 ;
|
||||||
SET_STATE(STATE_BIND_COMPLETE);
|
SET_STATE(STATE_BIND_COMPLETE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -39,31 +39,45 @@ static bool lastBindPinStatus;
|
||||||
|
|
||||||
void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig)
|
void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig)
|
||||||
{
|
{
|
||||||
|
if (rxSpiConfig->ledIoTag) {
|
||||||
ledPin = IOGetByTag(rxSpiConfig->ledIoTag);
|
ledPin = IOGetByTag(rxSpiConfig->ledIoTag);
|
||||||
IOInit(ledPin, OWNER_LED, 0);
|
IOInit(ledPin, OWNER_LED, 0);
|
||||||
IOConfigGPIO(ledPin, IOCFG_OUT_PP);
|
IOConfigGPIO(ledPin, IOCFG_OUT_PP);
|
||||||
ledInversion = rxSpiConfig->ledInversion;
|
ledInversion = rxSpiConfig->ledInversion;
|
||||||
rxSpiLedOff();
|
rxSpiLedOff();
|
||||||
|
} else {
|
||||||
|
ledPin = IO_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (rxSpiConfig->bindIoTag) {
|
||||||
bindPin = IOGetByTag(rxSpiConfig->bindIoTag);
|
bindPin = IOGetByTag(rxSpiConfig->bindIoTag);
|
||||||
IOInit(bindPin, OWNER_RX_BIND, 0);
|
IOInit(bindPin, OWNER_RX_BIND, 0);
|
||||||
IOConfigGPIO(bindPin, IOCFG_IPU);
|
IOConfigGPIO(bindPin, IOCFG_IPU);
|
||||||
lastBindPinStatus = IORead(bindPin);
|
lastBindPinStatus = IORead(bindPin);
|
||||||
|
} else {
|
||||||
|
bindPin = IO_NONE;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiLedOn(void)
|
void rxSpiLedOn(void)
|
||||||
{
|
{
|
||||||
|
if (ledPin) {
|
||||||
ledInversion ? IOLo(ledPin) : IOHi(ledPin);
|
ledInversion ? IOLo(ledPin) : IOHi(ledPin);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiLedOff(void)
|
void rxSpiLedOff(void)
|
||||||
{
|
{
|
||||||
|
if (ledPin) {
|
||||||
ledInversion ? IOHi(ledPin) : IOLo(ledPin);
|
ledInversion ? IOHi(ledPin) : IOLo(ledPin);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiLedToggle(void)
|
void rxSpiLedToggle(void)
|
||||||
{
|
{
|
||||||
|
if (ledPin) {
|
||||||
IOToggle(ledPin);
|
IOToggle(ledPin);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiLedBlink(timeMs_t blinkMs)
|
void rxSpiLedBlink(timeMs_t blinkMs)
|
||||||
|
@ -81,6 +95,8 @@ void rxSpiLedBlink(timeMs_t blinkMs)
|
||||||
void rxSpiLedBlinkRxLoss(rx_spi_received_e result)
|
void rxSpiLedBlinkRxLoss(rx_spi_received_e result)
|
||||||
{
|
{
|
||||||
static uint16_t rxLossCount = 0;
|
static uint16_t rxLossCount = 0;
|
||||||
|
|
||||||
|
if (ledPin) {
|
||||||
if (result == RX_SPI_RECEIVED_DATA) {
|
if (result == RX_SPI_RECEIVED_DATA) {
|
||||||
rxLossCount = 0;
|
rxLossCount = 0;
|
||||||
rxSpiLedOn();
|
rxSpiLedOn();
|
||||||
|
@ -91,6 +107,7 @@ void rxSpiLedBlinkRxLoss(rx_spi_received_e result)
|
||||||
rxSpiLedBlink(INTERVAL_RX_LOSS_MS);
|
rxSpiLedBlink(INTERVAL_RX_LOSS_MS);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void rxSpiLedBlinkBind(void)
|
void rxSpiLedBlinkBind(void)
|
||||||
|
|
|
@ -67,7 +67,7 @@
|
||||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||||
#define RX_CE_PIN PA4
|
#define RX_CE_PIN PA4
|
||||||
#define RX_NSS_PIN PA11
|
#define RX_NSS_PIN PA11
|
||||||
#define RX_IRQ_PIN PA8
|
#define RX_EXTI_PIN PA8
|
||||||
// CJMCU has NSS on PA11, rather than the standard PA4
|
// CJMCU has NSS on PA11, rather than the standard PA4
|
||||||
#define SPI1_NSS_PIN RX_NSS_PIN
|
#define SPI1_NSS_PIN RX_NSS_PIN
|
||||||
|
|
||||||
|
|
|
@ -117,7 +117,7 @@
|
||||||
#define FLYSKY_2A_CHANNEL_COUNT 14
|
#define FLYSKY_2A_CHANNEL_COUNT 14
|
||||||
#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_IRQ_PIN PA8
|
#define RX_EXTI_PIN PA8
|
||||||
#define BINDPLUG_PIN PA9
|
#define BINDPLUG_PIN PA9
|
||||||
#define RX_SPI_LED_PIN PA10
|
#define RX_SPI_LED_PIN PA10
|
||||||
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_MOTOR_STOP)
|
#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_MOTOR_STOP)
|
||||||
|
@ -137,7 +137,7 @@
|
||||||
#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_CC2500_SPI_GDO_0_PIN PA8
|
#define RX_SPI_EXTI_PIN PA8
|
||||||
#define RX_SPI_LED_PIN PA10
|
#define RX_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)
|
||||||
|
|
|
@ -58,7 +58,7 @@
|
||||||
#define FLYSKY_2A_CHANNEL_COUNT 10
|
#define FLYSKY_2A_CHANNEL_COUNT 10
|
||||||
|
|
||||||
#define RX_SPI_INSTANCE SPI2
|
#define RX_SPI_INSTANCE SPI2
|
||||||
#define RX_IRQ_PIN PB12
|
#define RX_EXTI_PIN PB12
|
||||||
#define SPI2_NSS_PIN PA4
|
#define SPI2_NSS_PIN PA4
|
||||||
#define SPI2_SCK_PIN PB13
|
#define SPI2_SCK_PIN PB13
|
||||||
#define SPI2_MISO_PIN PB14
|
#define SPI2_MISO_PIN PB14
|
||||||
|
|
|
@ -106,13 +106,13 @@
|
||||||
#define RX_CHANNELS_AETR
|
#define RX_CHANNELS_AETR
|
||||||
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_A7105_FLYSKY_2A
|
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_A7105_FLYSKY_2A
|
||||||
#define FLYSKY_2A_CHANNEL_COUNT 14
|
#define FLYSKY_2A_CHANNEL_COUNT 14
|
||||||
#define RX_IRQ_PIN PA14
|
#define RX_EXTI_PIN PA14
|
||||||
#define USE_RX_FLYSKY_SPI_LED
|
#define USE_RX_FLYSKY_SPI_LED
|
||||||
#define RX_FLYSKY_SPI_LED_PIN PB9
|
#define RX_SPI_LED_PIN PB9
|
||||||
|
|
||||||
#elif defined(CRAZYBEEF4FR)
|
#elif defined(CRAZYBEEF4FR)
|
||||||
#define RX_CC2500_SPI_DISABLE_CHIP_DETECTION
|
#define RX_CC2500_SPI_DISABLE_CHIP_DETECTION
|
||||||
#define RX_CC2500_SPI_GDO_0_PIN PC14
|
#define RX_SPI_EXTI_PIN PC14
|
||||||
#define RX_SPI_LED_PIN PB9
|
#define RX_SPI_LED_PIN PB9
|
||||||
#define USE_RX_FRSKY_SPI_D
|
#define USE_RX_FRSKY_SPI_D
|
||||||
#define USE_RX_FRSKY_SPI_X
|
#define USE_RX_FRSKY_SPI_X
|
||||||
|
@ -122,7 +122,7 @@
|
||||||
|
|
||||||
#else // MATEKF411RX
|
#else // MATEKF411RX
|
||||||
#define RX_CC2500_SPI_DISABLE_CHIP_DETECTION
|
#define RX_CC2500_SPI_DISABLE_CHIP_DETECTION
|
||||||
#define RX_CC2500_SPI_GDO_0_PIN PC14
|
#define RX_SPI_EXTI_PIN PC14
|
||||||
#define RX_SPI_LED_PIN PB9
|
#define RX_SPI_LED_PIN PB9
|
||||||
#define RX_SPI_LED_INVERTED
|
#define RX_SPI_LED_INVERTED
|
||||||
|
|
||||||
|
|
|
@ -104,7 +104,7 @@
|
||||||
|
|
||||||
#define RX_NSS_PIN PA4
|
#define RX_NSS_PIN PA4
|
||||||
|
|
||||||
#define RX_CC2500_SPI_GDO_0_PIN PB0
|
#define RX_SPI_EXTI_PIN PB0
|
||||||
|
|
||||||
#define RX_SPI_LED_PIN PB6
|
#define RX_SPI_LED_PIN PB6
|
||||||
|
|
||||||
|
|
|
@ -181,7 +181,7 @@
|
||||||
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_CYRF6936_DSM
|
#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_CYRF6936_DSM
|
||||||
#define RX_SPI_INSTANCE SPI3
|
#define RX_SPI_INSTANCE SPI3
|
||||||
#define RX_NSS_PIN PD2
|
#define RX_NSS_PIN PD2
|
||||||
#define RX_IRQ_PIN PA0 // instead of rssi input
|
#define RX_EXTI_PIN PA0 // instead of rssi input
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
|
@ -101,17 +101,21 @@
|
||||||
|
|
||||||
#define USE_ADC
|
#define USE_ADC
|
||||||
|
|
||||||
//TODO: Make this work with runtime configurability
|
#define USE_RX_SPI
|
||||||
//#define USE_RX_FRSKY_SPI_D
|
|
||||||
//#define USE_RX_FRSKY_SPI_X
|
#define USE_RX_FRSKY_SPI_D
|
||||||
//#define USE_RX_SFHSS_SPI
|
#define USE_RX_FRSKY_SPI_X
|
||||||
//#define USE_RX_FRSKY_SPI_TELEMETRY
|
#define USE_RX_SFHSS_SPI
|
||||||
//#define USE_RX_CC2500_SPI_PA_LNA
|
#define USE_RX_FRSKY_SPI_TELEMETRY
|
||||||
//#define USE_RX_CC2500_SPI_DIVERSITY
|
#define USE_RX_CC2500_SPI_PA_LNA
|
||||||
|
#define USE_RX_CC2500_SPI_DIVERSITY
|
||||||
|
|
||||||
//TODO: Make this work with runtime configurability
|
//TODO: Make this work with runtime configurability
|
||||||
//#define USE_RX_FLYSKY
|
//#define USE_RX_FLYSKY
|
||||||
//#define USE_RX_FLYSKY_SPI_LED
|
|
||||||
|
//TODO: Make this work with runtime configurability
|
||||||
|
//#define USE_RX_SPEKTRUM
|
||||||
|
//#define USE_RX_SPEKTRUM_TELEMETRY
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
|
@ -262,9 +262,35 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_RX_SPI
|
#ifdef USE_RX_SPI
|
||||||
|
#if !defined(RX_SPI_INSTANCE)
|
||||||
|
#define RX_SPI_INSTANCE NULL
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(RX_NSS_PIN)
|
||||||
|
#define RX_NSS_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef RX_SPI_LED_PIN
|
#ifndef RX_SPI_LED_PIN
|
||||||
#define RX_SPI_LED_PIN NONE
|
#define RX_SPI_LED_PIN NONE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(RX_SPI_EXTI_PIN)
|
||||||
|
#define RX_SPI_EXTI_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_RX_CC2500)
|
||||||
|
#if !defined(RX_CC2500_SPI_TX_EN_PIN)
|
||||||
|
#define RX_CC2500_SPI_TX_EN_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(RX_CC2500_SPI_LNA_EN_PIN)
|
||||||
|
#define RX_CC2500_SPI_LNA_EN_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(RX_CC2500_SPI_ANT_SEL_PIN)
|
||||||
|
#define RX_CC2500_SPI_ANT_SEL_PIN NONE
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// F4 and F7 single gyro boards
|
// F4 and F7 single gyro boards
|
||||||
|
|
|
@ -145,6 +145,14 @@
|
||||||
#define USE_RX_CC2500
|
#define USE_RX_CC2500
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_RX_CC2500)
|
||||||
|
#undef USE_RX_CC2500_SPI_PA_LNA
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !defined(USE_RX_CC2500_SPI_PA_LNA)
|
||||||
|
#undef USE_RX_CC2500_SPI_DIVERSITY
|
||||||
|
#endif
|
||||||
|
|
||||||
// Burst dshot to default off if not configured explicitly by target
|
// Burst dshot to default off if not configured explicitly by target
|
||||||
#ifndef ENABLE_DSHOT_DMAR
|
#ifndef ENABLE_DSHOT_DMAR
|
||||||
#define ENABLE_DSHOT_DMAR false
|
#define ENABLE_DSHOT_DMAR false
|
||||||
|
|
|
@ -1,6 +1,4 @@
|
||||||
# Betaflight / CRAZYBEEF4FR (C4FR) 4.0.0 Feb 28 2019 / 18:10:50 (b63a3e117) MSP API: 1.41
|
# Betaflight / CRAZYBEEF4FR (C4FR) 4.0.0 Mar 2 2019 / 21:03:37 (48d32d8b1) MSP API: 1.41
|
||||||
|
|
||||||
# This is not usable yet, as the SPI RX is not fully runtime configurable yet
|
|
||||||
|
|
||||||
board_name CRAZYBEEF4FR
|
board_name CRAZYBEEF4FR
|
||||||
manufacturer_id HAMO
|
manufacturer_id HAMO
|
||||||
|
@ -35,6 +33,7 @@ resource ADC_BATT 1 B00
|
||||||
resource ADC_CURR 1 B01
|
resource ADC_CURR 1 B01
|
||||||
resource OSD_CS 1 B12
|
resource OSD_CS 1 B12
|
||||||
resource RX_SPI_CS 1 A15
|
resource RX_SPI_CS 1 A15
|
||||||
|
resource RX_SPI_EXTI 1 C14
|
||||||
resource RX_SPI_BIND 1 B02
|
resource RX_SPI_BIND 1 B02
|
||||||
resource RX_SPI_LED 1 B09
|
resource RX_SPI_LED 1 B09
|
||||||
resource GYRO_EXTI 1 A01
|
resource GYRO_EXTI 1 A01
|
||||||
|
@ -70,12 +69,7 @@ dmaopt pin A10 0
|
||||||
# pin A10: DMA2 Stream 6 Channel 0
|
# pin A10: DMA2 Stream 6 Channel 0
|
||||||
|
|
||||||
# feature
|
# feature
|
||||||
feature TELEMETRY
|
|
||||||
feature OSD
|
|
||||||
feature AIRMODE
|
|
||||||
feature RX_SPI
|
feature RX_SPI
|
||||||
feature ANTI_GRAVITY
|
|
||||||
feature DYNAMIC_FILTER
|
|
||||||
|
|
||||||
# master
|
# master
|
||||||
set rx_spi_protocol = FRSKY_X
|
set rx_spi_protocol = FRSKY_X
|
||||||
|
@ -83,13 +77,12 @@ set rx_spi_bus = 3
|
||||||
set rx_spi_led_inversion = OFF
|
set rx_spi_led_inversion = OFF
|
||||||
set adc_device = 1
|
set adc_device = 1
|
||||||
set motor_pwm_protocol = DSHOT600
|
set motor_pwm_protocol = DSHOT600
|
||||||
|
set current_meter = ADC
|
||||||
|
set battery_meter = ADC
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set max7456_clock = DEFAULT
|
set system_hse_mhz = 8
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set max7456_preinit_opu = OFF
|
set cc2500_spi_chip_detect = ON
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
set gyro_1_spibus = 1
|
set gyro_1_spibus = 1
|
||||||
set gyro_1_i2cBus = 0
|
|
||||||
set gyro_1_i2c_address = 0
|
|
||||||
set gyro_1_sensor_align = CW90
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue