mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 00:05:28 +03:00
Refactor NRF24 RX into SPI and NRF24 parts
This commit is contained in:
parent
9bfcb78265
commit
47f8e8d9c9
32 changed files with 518 additions and 435 deletions
3
Makefile
3
Makefile
|
@ -385,6 +385,7 @@ COMMON_SRC = \
|
|||
drivers/io.c \
|
||||
drivers/light_led.c \
|
||||
drivers/rx_nrf24l01.c \
|
||||
drivers/rx_spi.c \
|
||||
drivers/rx_xn297.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
|
@ -414,7 +415,6 @@ COMMON_SRC = \
|
|||
rx/ibus.c \
|
||||
rx/jetiexbus.c \
|
||||
rx/msp.c \
|
||||
rx/nrf24.c \
|
||||
rx/nrf24_cx10.c \
|
||||
rx/nrf24_inav.c \
|
||||
rx/nrf24_h8_3d.c \
|
||||
|
@ -422,6 +422,7 @@ COMMON_SRC = \
|
|||
rx/nrf24_v202.c \
|
||||
rx/pwm.c \
|
||||
rx/rx.c \
|
||||
rx/rx_spi.c \
|
||||
rx/sbus.c \
|
||||
rx/spektrum.c \
|
||||
rx/sumd.c \
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -57,7 +57,7 @@
|
|||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
@ -88,8 +88,8 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
|
|||
#ifndef DEFAULT_RX_FEATURE
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
|
||||
#endif
|
||||
#ifndef NRF24_DEFAULT_PROTOCOL
|
||||
#define NRF24_DEFAULT_PROTOCOL 0
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
#define RX_SPI_DEFAULT_PROTOCOL 0
|
||||
#endif
|
||||
|
||||
#if !defined(FLASH_SIZE)
|
||||
|
@ -516,7 +516,7 @@ static void resetConf(void)
|
|||
#endif
|
||||
|
||||
masterConfig.rxConfig.serialrx_provider = 0;
|
||||
masterConfig.rxConfig.nrf24rx_protocol = NRF24_DEFAULT_PROTOCOL;
|
||||
masterConfig.rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
|
||||
masterConfig.rxConfig.spektrum_sat_bind = 0;
|
||||
masterConfig.rxConfig.midrc = 1500;
|
||||
masterConfig.rxConfig.mincheck = 1100;
|
||||
|
@ -847,23 +847,23 @@ void activateConfig(void)
|
|||
|
||||
static void validateAndFixConfig(void)
|
||||
{
|
||||
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_NRF24))) {
|
||||
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
|
||||
featureSet(DEFAULT_RX_FEATURE);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_PPM)) {
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_NRF24);
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_MSP)) {
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_NRF24);
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_SERIAL)) {
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_NRF24);
|
||||
featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
|
||||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_NRF24)) {
|
||||
if (featureConfigured(FEATURE_RX_SPI)) {
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
|
||||
}
|
||||
|
||||
|
@ -886,7 +886,7 @@ static void validateAndFixConfig(void)
|
|||
}
|
||||
|
||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_NRF24);
|
||||
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
|
||||
#if defined(STM32F10X)
|
||||
// rssi adc needs the same ports
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
|
|
|
@ -48,7 +48,7 @@ typedef enum {
|
|||
FEATURE_AIRMODE = 1 << 22,
|
||||
FEATURE_SUPEREXPO_RATES = 1 << 23,
|
||||
FEATURE_VTX = 1 << 24,
|
||||
FEATURE_RX_NRF24 = 1 << 25,
|
||||
FEATURE_RX_SPI = 1 << 25,
|
||||
FEATURE_SOFTSPI = 1 << 26,
|
||||
} features_e;
|
||||
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -53,7 +53,7 @@
|
|||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
|
|
|
@ -108,8 +108,8 @@ void spiInitDevice(SPIDevice device)
|
|||
spi->sdcard = true;
|
||||
}
|
||||
#endif
|
||||
#ifdef NRF24_SPI_INSTANCE
|
||||
if (spi->dev == NRF24_SPI_INSTANCE) {
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
if (spi->dev == RX_SPI_INSTANCE) {
|
||||
spi->nrf24l01 = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -31,7 +31,7 @@ typedef enum {
|
|||
OWNER_RX,
|
||||
OWNER_TX,
|
||||
OWNER_SOFTSPI,
|
||||
OWNER_NRF24,
|
||||
OWNER_RX_SPI,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_t;
|
||||
|
||||
|
@ -48,7 +48,7 @@ typedef enum {
|
|||
RESOURCE_I2C_SCL, RESOURCE_I2C_SDA,
|
||||
RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS,
|
||||
RESOURCE_ADC_BATTERY, RESOURCE_ADC_RSSI, RESOURCE_ADC_EXTERNAL1, RESOURCE_ADC_CURRENT,
|
||||
RESOURCE_NRF24_CE,
|
||||
RESOURCE_RX_CE,
|
||||
RESOURCE_TOTAL_COUNT
|
||||
} resourceType_t;
|
||||
|
||||
|
|
|
@ -33,94 +33,12 @@
|
|||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
#include "rx_spi.h"
|
||||
#include "rx_nrf24l01.h"
|
||||
|
||||
#ifdef UNIT_TEST
|
||||
|
||||
#define NRF24_CE_HI() {}
|
||||
#define NRF24_CE_LO() {}
|
||||
void NRF24L01_SpiInit(void) {}
|
||||
|
||||
#else
|
||||
|
||||
#include "bus_spi.h"
|
||||
#include "bus_spi_soft.h"
|
||||
|
||||
#define DISABLE_NRF24() {IOHi(IOGetByTag(IO_TAG(NRF24_CSN_PIN)));}
|
||||
#define ENABLE_NRF24() {IOLo(IOGetByTag(IO_TAG(NRF24_CSN_PIN)));}
|
||||
#define NRF24_CE_HI() {IOHi(IOGetByTag(IO_TAG(NRF24_CE_PIN)));}
|
||||
#define NRF24_CE_LO() {IOLo(IOGetByTag(IO_TAG(NRF24_CE_PIN)));}
|
||||
|
||||
#ifdef USE_NRF24_SOFTSPI
|
||||
static const softSPIDevice_t softSPIDevice = {
|
||||
.sckTag = IO_TAG(NRF24_SCK_PIN),
|
||||
.mosiTag = IO_TAG(NRF24_MOSI_PIN),
|
||||
.misoTag = IO_TAG(NRF24_MISO_PIN),
|
||||
// Note: Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
.nssTag = IO_TAG(NRF24_CSN_PIN),
|
||||
};
|
||||
#endif // USE_NRF24_SOFTSPI
|
||||
|
||||
#ifdef USE_NRF24_SOFTSPI
|
||||
static bool useSoftSPI = false;
|
||||
#endif
|
||||
void NRF24L01_SpiInit(nfr24l01_spi_type_e spiType)
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_NRF24_SOFTSPI
|
||||
if (spiType == NFR24L01_SOFTSPI) {
|
||||
useSoftSPI = true;
|
||||
softSpiInit(&softSPIDevice);
|
||||
}
|
||||
const SPIDevice nrf24SPIDevice = SOFT_SPIDEV_1;
|
||||
#else
|
||||
UNUSED(spiType);
|
||||
const SPIDevice nrf24SPIDevice = spiDeviceByInstance(NRF24_SPI_INSTANCE);
|
||||
IOInit(IOGetByTag(IO_TAG(NRF24_CSN_PIN)), OWNER_SPI, RESOURCE_SPI_CS, nrf24SPIDevice + 1);
|
||||
#endif // USE_NRF24_SOFTSPI
|
||||
|
||||
#if defined(STM32F10X)
|
||||
RCC_AHBPeriphClockCmd(NRF24_CSN_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(NRF24_CE_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
#endif
|
||||
|
||||
// CE as OUTPUT
|
||||
IOInit(IOGetByTag(IO_TAG(NRF24_CE_PIN)), OWNER_NRF24, RESOURCE_NRF24_CE, nrf24SPIDevice + 1);
|
||||
#if defined(STM32F10X)
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(NRF24_CE_PIN)), SPI_IO_CS_CFG);
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
IOConfigGPIOAF(IOGetByTag(IO_TAG(NRF24_CE_PIN)), SPI_IO_CS_CFG, 0);
|
||||
#endif
|
||||
|
||||
DISABLE_NRF24();
|
||||
NRF24_CE_LO();
|
||||
|
||||
#ifdef NRF24_SPI_INSTANCE
|
||||
spiSetDivisor(NRF24_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
#endif
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
||||
uint8_t nrf24TransferByte(uint8_t data)
|
||||
{
|
||||
#ifdef USE_NRF24_SOFTSPI
|
||||
if (useSoftSPI) {
|
||||
return softSpiTransferByte(&softSPIDevice, data);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
#ifdef NRF24_SPI_INSTANCE
|
||||
return spiTransferByte(NRF24_SPI_INSTANCE, data);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#define NRF24_CE_HI() {IOHi(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
#define NRF24_CE_LO() {IOLo(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
|
||||
// Instruction Mnemonics
|
||||
// nRF24L01: Table 16. Command set for the nRF24L01 SPI. Product Specification, p46
|
||||
|
@ -140,27 +58,12 @@ uint8_t nrf24TransferByte(uint8_t data)
|
|||
|
||||
uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data)
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
nrf24TransferByte(W_REGISTER | (REGISTER_MASK & reg));
|
||||
nrf24TransferByte(data);
|
||||
DISABLE_NRF24();
|
||||
return true;
|
||||
}
|
||||
|
||||
static uint8_t NRF24L01_WriteMulti(uint8_t type, const uint8_t *data, uint8_t length)
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
const uint8_t ret = nrf24TransferByte(type);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
nrf24TransferByte(data[i]);
|
||||
}
|
||||
DISABLE_NRF24();
|
||||
return ret;
|
||||
return rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length)
|
||||
{
|
||||
return NRF24L01_WriteMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
|
||||
return rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -170,37 +73,22 @@ uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t le
|
|||
*/
|
||||
uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length)
|
||||
{
|
||||
return NRF24L01_WriteMulti(W_TX_PAYLOAD, data, length);
|
||||
return rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe)
|
||||
{
|
||||
return NRF24L01_WriteMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
|
||||
return rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_ReadReg(uint8_t reg)
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
nrf24TransferByte(R_REGISTER | (REGISTER_MASK & reg));
|
||||
const uint8_t ret = nrf24TransferByte(NOP);
|
||||
DISABLE_NRF24();
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint8_t NRF24L01_ReadMulti(uint8_t type, uint8_t *data, uint8_t length)
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
const uint8_t ret = nrf24TransferByte(type);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
data[i] = nrf24TransferByte(NOP);
|
||||
}
|
||||
DISABLE_NRF24();
|
||||
return ret;
|
||||
return rxSpiReadCommand(R_REGISTER | (REGISTER_MASK & reg), NOP);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
|
||||
{
|
||||
return NRF24L01_ReadMulti(R_REGISTER | (REGISTER_MASK & reg), data, length);
|
||||
return rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -208,7 +96,7 @@ uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
|
|||
*/
|
||||
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
|
||||
{
|
||||
return NRF24L01_ReadMulti(R_RX_PAYLOAD, data, length);
|
||||
return rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -216,9 +104,7 @@ uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
|
|||
*/
|
||||
void NRF24L01_FlushTx()
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
nrf24TransferByte(FLUSH_TX);
|
||||
DISABLE_NRF24();
|
||||
rxSpiWriteByte(FLUSH_TX);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -226,22 +112,14 @@ void NRF24L01_FlushTx()
|
|||
*/
|
||||
void NRF24L01_FlushRx()
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
nrf24TransferByte(FLUSH_RX);
|
||||
DISABLE_NRF24();
|
||||
rxSpiWriteByte(FLUSH_RX);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_Activate(uint8_t code)
|
||||
{
|
||||
ENABLE_NRF24();
|
||||
const uint8_t ret = nrf24TransferByte(ACTIVATE);
|
||||
nrf24TransferByte(code);
|
||||
DISABLE_NRF24();
|
||||
return ret;
|
||||
return rxSpiWriteCommand(ACTIVATE, code);
|
||||
}
|
||||
|
||||
#endif // UNIT_TEST
|
||||
|
||||
// standby configuration, used to simplify switching between RX, TX, and Standby modes
|
||||
static uint8_t standbyConfig;
|
||||
|
||||
|
@ -334,6 +212,8 @@ bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length)
|
|||
}
|
||||
|
||||
#ifndef UNIT_TEST
|
||||
#define DISABLE_RX() {IOHi(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
#define ENABLE_RX() {IOLo(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
/*
|
||||
* Fast read of payload, for use in interrupt service routine
|
||||
*/
|
||||
|
@ -343,21 +223,21 @@ bool NRF24L01_ReadPayloadIfAvailableFast(uint8_t *data, uint8_t length)
|
|||
// for 16 byte payload, that is 8*19 = 152
|
||||
// at 50MHz clock rate that is approximately 3 microseconds
|
||||
bool ret = false;
|
||||
ENABLE_NRF24();
|
||||
nrf24TransferByte(R_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
const uint8_t status = nrf24TransferByte(NOP);
|
||||
ENABLE_RX();
|
||||
rxSpiTransferByte(R_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
const uint8_t status = rxSpiTransferByte(NOP);
|
||||
if ((status & BV(NRF24L01_07_STATUS_RX_DR)) == 0) {
|
||||
ret = true;
|
||||
// clear RX_DR flag
|
||||
nrf24TransferByte(W_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
nrf24TransferByte(BV(NRF24L01_07_STATUS_RX_DR));
|
||||
nrf24TransferByte(R_RX_PAYLOAD);
|
||||
rxSpiTransferByte(W_REGISTER | (REGISTER_MASK & NRF24L01_07_STATUS));
|
||||
rxSpiTransferByte(BV(NRF24L01_07_STATUS_RX_DR));
|
||||
rxSpiTransferByte(R_RX_PAYLOAD);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
data[i] = nrf24TransferByte(NOP);
|
||||
data[i] = rxSpiTransferByte(NOP);
|
||||
}
|
||||
}
|
||||
DISABLE_NRF24();
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
#endif // UNIT_TEST
|
||||
#endif // USE_RX_NRF24
|
||||
|
|
|
@ -23,6 +23,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "rx_spi.h"
|
||||
|
||||
#define NRF24L01_MAX_PAYLOAD_SIZE 32
|
||||
|
||||
#define BV(x) (1<<(x)) // bit value
|
||||
|
@ -173,12 +175,6 @@ enum {
|
|||
NRF24L01_PIPE5 = 5
|
||||
};
|
||||
|
||||
typedef enum {
|
||||
NFR24L01_SOFTSPI,
|
||||
NFR24L01_SPI,
|
||||
} nfr24l01_spi_type_e;
|
||||
|
||||
void NRF24L01_SpiInit(nfr24l01_spi_type_e spiType);
|
||||
void NRF24L01_Initialize(uint8_t baseConfig);
|
||||
uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data);
|
||||
uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length);
|
||||
|
@ -188,13 +184,13 @@ uint8_t NRF24L01_ReadReg(uint8_t reg);
|
|||
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
|
||||
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
|
||||
|
||||
|
||||
// Utility functions
|
||||
|
||||
void NRF24L01_FlushTx(void);
|
||||
void NRF24L01_FlushRx(void);
|
||||
uint8_t NRF24L01_Activate(uint8_t code);
|
||||
|
||||
|
||||
// Utility functions
|
||||
|
||||
void NRF24L01_SetupBasic(void);
|
||||
void NRF24L01_SetStandbyMode(void);
|
||||
void NRF24L01_SetRxMode(void);
|
||||
|
|
166
src/main/drivers/rx_spi.c
Normal file
166
src/main/drivers/rx_spi.c
Normal file
|
@ -0,0 +1,166 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// This file is copied with modifications from project Deviation,
|
||||
// see http://deviationtx.com
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef USE_RX_SPI
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "system.h"
|
||||
#include "gpio.h"
|
||||
#include "io.h"
|
||||
#include "io_impl.h"
|
||||
#include "rcc.h"
|
||||
#include "rx_spi.h"
|
||||
|
||||
#include "bus_spi.h"
|
||||
#include "bus_spi_soft.h"
|
||||
|
||||
#define DISABLE_RX() {IOHi(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
#define ENABLE_RX() {IOLo(IOGetByTag(IO_TAG(RX_NSS_PIN)));}
|
||||
#ifdef RX_CE_PIN
|
||||
#define RX_CE_HI() {IOHi(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
#define RX_CE_LO() {IOLo(IOGetByTag(IO_TAG(RX_CE_PIN)));}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_SOFTSPI
|
||||
static const softSPIDevice_t softSPIDevice = {
|
||||
.sckTag = IO_TAG(RX_SCK_PIN),
|
||||
.mosiTag = IO_TAG(RX_MOSI_PIN),
|
||||
.misoTag = IO_TAG(RX_MISO_PIN),
|
||||
// Note: Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
.nssTag = IO_TAG(RX_NSS_PIN),
|
||||
};
|
||||
static bool useSoftSPI = false;
|
||||
#endif // USE_RX_SOFTSPI
|
||||
|
||||
void rxSpiDeviceInit(rx_spi_type_e spiType)
|
||||
{
|
||||
static bool hardwareInitialised = false;
|
||||
|
||||
if (hardwareInitialised) {
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_RX_SOFTSPI
|
||||
if (spiType == RX_SPI_SOFTSPI) {
|
||||
useSoftSPI = true;
|
||||
softSpiInit(&softSPIDevice);
|
||||
}
|
||||
const SPIDevice rxSPIDevice = SOFT_SPIDEV_1;
|
||||
#else
|
||||
UNUSED(spiType);
|
||||
const SPIDevice rxSPIDevice = spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||
IOInit(IOGetByTag(IO_TAG(RX_NSS_PIN)), OWNER_SPI, RESOURCE_SPI_CS, rxSPIDevice + 1);
|
||||
#endif // USE_RX_SOFTSPI
|
||||
|
||||
#if defined(STM32F10X)
|
||||
RCC_AHBPeriphClockCmd(RX_NSS_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
RCC_AHBPeriphClockCmd(RX_CE_GPIO_CLK_PERIPHERAL, ENABLE);
|
||||
#endif
|
||||
|
||||
#ifdef RX_CE_PIN
|
||||
// CE as OUTPUT
|
||||
IOInit(IOGetByTag(IO_TAG(RX_CE_PIN)), OWNER_RX_SPI, RESOURCE_RX_CE, rxSPIDevice + 1);
|
||||
#if defined(STM32F10X)
|
||||
IOConfigGPIO(IOGetByTag(IO_TAG(RX_CE_PIN)), SPI_IO_CS_CFG);
|
||||
#elif defined(STM32F3) || defined(STM32F4)
|
||||
IOConfigGPIOAF(IOGetByTag(IO_TAG(RX_CE_PIN)), SPI_IO_CS_CFG, 0);
|
||||
#endif
|
||||
RX_CE_LO();
|
||||
#endif // RX_CE_PIN
|
||||
DISABLE_RX();
|
||||
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
spiSetDivisor(RX_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||
#endif
|
||||
hardwareInitialised = true;
|
||||
}
|
||||
|
||||
uint8_t rxSpiTransferByte(uint8_t data)
|
||||
{
|
||||
#ifdef USE_RX_SOFTSPI
|
||||
if (useSoftSPI) {
|
||||
return softSpiTransferByte(&softSPIDevice, data);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
#ifdef RX_SPI_INSTANCE
|
||||
return spiTransferByte(RX_SPI_INSTANCE, data);
|
||||
#else
|
||||
return 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteByte(uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
rxSpiTransferByte(data[i]);
|
||||
}
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiReadCommand(uint8_t command, uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
rxSpiTransferByte(command);
|
||||
const uint8_t ret = rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(command);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
retData[i] = rxSpiTransferByte(commandData);
|
||||
}
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
35
src/main/drivers/rx_spi.h
Normal file
35
src/main/drivers/rx_spi.h
Normal file
|
@ -0,0 +1,35 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef enum {
|
||||
RX_SPI_SOFTSPI,
|
||||
RX_SPI_HARDSPI,
|
||||
} rx_spi_type_e;
|
||||
|
||||
#define RX_SPI_MAX_PAYLOAD_SIZE 32
|
||||
|
||||
void rxSpiDeviceInit(rx_spi_type_e spiType);
|
||||
uint8_t rxSpiTransferByte(uint8_t data);
|
||||
uint8_t rxSpiWriteByte(uint8_t data);
|
||||
uint8_t rxSpiWriteCommand(uint8_t command, uint8_t data);
|
||||
uint8_t rxSpiWriteCommandMulti(uint8_t command, const uint8_t *data, uint8_t length);
|
||||
uint8_t rxSpiReadCommand(uint8_t command, uint8_t commandData);
|
||||
uint8_t rxSpiReadCommandMulti(uint8_t command, uint8_t commandData, uint8_t *retData, uint8_t length);
|
||||
|
|
@ -21,7 +21,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "rx_spi.h"
|
||||
#include "rx_nrf24l01.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
|
||||
|
|
|
@ -922,9 +922,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize8(0); // for compatibility with betaflight
|
||||
serialize8(0); // for compatibility with betaflight
|
||||
serialize16(0); // for compatibility with betaflight
|
||||
serialize8(masterConfig.rxConfig.nrf24rx_protocol);
|
||||
serialize32(masterConfig.rxConfig.nrf24rx_id);
|
||||
serialize8(masterConfig.rxConfig.nrf24rx_rf_channel_count);
|
||||
serialize8(masterConfig.rxConfig.rx_spi_protocol);
|
||||
serialize32(masterConfig.rxConfig.rx_spi_id);
|
||||
serialize8(masterConfig.rxConfig.rx_spi_rf_channel_count);
|
||||
break;
|
||||
|
||||
case MSP_FAILSAFE_CONFIG:
|
||||
|
@ -1460,13 +1460,13 @@ static bool processInCommand(void)
|
|||
read16();
|
||||
}
|
||||
if (currentPort->dataSize > 16) {
|
||||
masterConfig.rxConfig.nrf24rx_protocol = read8();
|
||||
masterConfig.rxConfig.rx_spi_protocol = read8();
|
||||
}
|
||||
if (currentPort->dataSize > 17) {
|
||||
masterConfig.rxConfig.nrf24rx_id = read32();
|
||||
masterConfig.rxConfig.rx_spi_id = read32();
|
||||
}
|
||||
if (currentPort->dataSize > 21) {
|
||||
masterConfig.rxConfig.nrf24rx_rf_channel_count = read8();
|
||||
masterConfig.rxConfig.rx_spi_rf_channel_count = read8();
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
|
@ -211,7 +211,7 @@ static const char * const featureNames[] = {
|
|||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
|
||||
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
|
||||
"SUPEREXPO", "VTX", "RX_NRF24", "SOFTSPI", NULL
|
||||
"SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", NULL
|
||||
};
|
||||
|
||||
// sync this with rxFailsafeChannelMode_e
|
||||
|
@ -419,9 +419,9 @@ static const char * const lookupTableSerialRX[] = {
|
|||
};
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_NRF24
|
||||
// sync with nrf24_protocol_t
|
||||
static const char * const lookupTableNRF24RX[] = {
|
||||
#ifdef USE_RX_SPI
|
||||
// sync with rx_spi_protocol_e
|
||||
static const char * const lookupTableRxSpi[] = {
|
||||
"V202_250K",
|
||||
"V202_1M",
|
||||
"SYMA_X",
|
||||
|
@ -484,8 +484,8 @@ typedef enum {
|
|||
#ifdef SERIAL_RX
|
||||
TABLE_SERIAL_RX,
|
||||
#endif
|
||||
#ifdef USE_RX_NRF24
|
||||
TABLE_NRF24_RX,
|
||||
#ifdef USE_RX_SPI
|
||||
TABLE_RX_SPI,
|
||||
#endif
|
||||
TABLE_GYRO_LPF,
|
||||
TABLE_FAILSAFE_PROCEDURE,
|
||||
|
@ -515,8 +515,8 @@ static const lookupTableEntry_t lookupTables[] = {
|
|||
#ifdef SERIAL_RX
|
||||
{ lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
|
||||
#endif
|
||||
#ifdef USE_RX_NRF24
|
||||
{ lookupTableNRF24RX, sizeof(lookupTableNRF24RX) / sizeof(char *) },
|
||||
#ifdef USE_RX_SPI
|
||||
{ lookupTableRxSpi, sizeof(lookupTableRxSpi) / sizeof(char *) },
|
||||
#endif
|
||||
{ lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
|
||||
{ lookupTableFailsafeProcedure, sizeof(lookupTableFailsafeProcedure) / sizeof(char *) },
|
||||
|
@ -693,10 +693,10 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef SERIAL_RX
|
||||
{ "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX }, 0 },
|
||||
#endif
|
||||
#ifdef USE_RX_NRF24
|
||||
{ "nrf24rx_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.nrf24rx_protocol, .config.lookup = { TABLE_NRF24_RX }, 0 },
|
||||
{ "nrf24rx_id", VAR_UINT32 | MASTER_VALUE, &masterConfig.rxConfig.nrf24rx_id, .config.minmax = { 0, 0 }, 0 },
|
||||
{ "nrf24rx_rf_channel_count", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.nrf24rx_rf_channel_count, .config.minmax = { 0, 8 }, 0 },
|
||||
#ifdef USE_RX_SPI
|
||||
{ "rx_spi_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rx_spi_protocol, .config.lookup = { TABLE_RX_SPI }, 0 },
|
||||
{ "rx_spi_id", VAR_UINT32 | MASTER_VALUE, &masterConfig.rxConfig.rx_spi_id, .config.minmax = { 0, 0 }, 0 },
|
||||
{ "rx_spi_rf_channel_count", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rx_spi_rf_channel_count, .config.minmax = { 0, 8 }, 0 },
|
||||
#endif
|
||||
#ifdef SPEKTRUM_BIND
|
||||
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, 0 },
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#include "drivers/rx_xn297.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_cx10.h"
|
||||
|
||||
/*
|
||||
|
@ -71,7 +71,7 @@ enum {
|
|||
#define FLAG_VIDEO 0x02
|
||||
#define FLAG_PICTURE 0x04
|
||||
|
||||
static nrf24_protocol_t cx10Protocol;
|
||||
static rx_spi_protocol_e cx10Protocol;
|
||||
|
||||
typedef enum {
|
||||
STATE_BIND = 0,
|
||||
|
@ -129,10 +129,10 @@ STATIC_UNIT_TESTED uint16_t cx10ConvertToPwmUnsigned(const uint8_t *pVal)
|
|||
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
||||
{
|
||||
const uint8_t offset = (cx10Protocol == NRF24RX_CX10) ? 0 : 4;
|
||||
rcData[NRF24_ROLL] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[5 + offset]); // aileron
|
||||
rcData[NRF24_PITCH] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[7 + offset]); // elevator
|
||||
rcData[NRF24_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle
|
||||
rcData[NRF24_YAW] = cx10ConvertToPwmUnsigned(&payload[11 + offset]); // rudder
|
||||
rcData[RC_SPI_ROLL] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[5 + offset]); // aileron
|
||||
rcData[RC_SPI_PITCH] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[7 + offset]); // elevator
|
||||
rcData[RC_SPI_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle
|
||||
rcData[RC_SPI_YAW] = cx10ConvertToPwmUnsigned(&payload[11 + offset]); // rudder
|
||||
const uint8_t flags1 = payload[13 + offset];
|
||||
const uint8_t rate = flags1 & FLAG_MODE_MASK; // takes values 0, 1, 2
|
||||
if (rate == RATE_LOW) {
|
||||
|
@ -193,12 +193,12 @@ static bool cx10ReadPayloadIfAvailable(uint8_t *payload)
|
|||
|
||||
/*
|
||||
* This is called periodically by the scheduler.
|
||||
* Returns NRF24_RECEIVED_DATA if a data packet was received.
|
||||
* Returns RX_SPI_RECEIVED_DATA if a data packet was received.
|
||||
*/
|
||||
nrf24_received_t cx10Nrf24DataReceived(uint8_t *payload)
|
||||
rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
|
||||
{
|
||||
static uint8_t ackCount;
|
||||
nrf24_received_t ret = NRF24_RECEIVED_NONE;
|
||||
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
|
||||
int totalDelayUs;
|
||||
uint32_t timeNowUs;
|
||||
|
||||
|
@ -209,7 +209,7 @@ nrf24_received_t cx10Nrf24DataReceived(uint8_t *payload)
|
|||
if (bindPacket) {
|
||||
// set the hopping channels as determined by the txId received in the bind packet
|
||||
cx10SetHoppingChannels(txId);
|
||||
ret = NRF24_RECEIVED_BIND;
|
||||
ret = RX_SPI_RECEIVED_BIND;
|
||||
protocolState = STATE_ACK;
|
||||
ackCount = 0;
|
||||
}
|
||||
|
@ -259,7 +259,7 @@ nrf24_received_t cx10Nrf24DataReceived(uint8_t *payload)
|
|||
if (cx10ReadPayloadIfAvailable(payload)) {
|
||||
cx10HopToNextChannel();
|
||||
timeOfLastHop = timeNowUs;
|
||||
ret = NRF24_RECEIVED_DATA;
|
||||
ret = RX_SPI_RECEIVED_DATA;
|
||||
}
|
||||
if (timeNowUs > timeOfLastHop + hopTimeout) {
|
||||
cx10HopToNextChannel();
|
||||
|
@ -269,7 +269,7 @@ nrf24_received_t cx10Nrf24DataReceived(uint8_t *payload)
|
|||
return ret;
|
||||
}
|
||||
|
||||
static void cx10Nrf24Setup(nrf24_protocol_t protocol)
|
||||
static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
cx10Protocol = protocol;
|
||||
protocolState = STATE_BIND;
|
||||
|
@ -295,7 +295,7 @@ static void cx10Nrf24Setup(nrf24_protocol_t protocol)
|
|||
void cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
cx10Nrf24Setup((nrf24_protocol_t)rxConfig->nrf24rx_protocol);
|
||||
cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -24,5 +24,5 @@ struct rxConfig_s;
|
|||
struct rxRuntimeConfig_s;
|
||||
void cx10Nrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
nrf24_received_t cx10Nrf24DataReceived(uint8_t *payload);
|
||||
rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload);
|
||||
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
#include "drivers/rx_xn297.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_h8_3d.h"
|
||||
|
||||
|
||||
|
@ -85,7 +85,7 @@ STATIC_UNIT_TESTED uint8_t payloadSize;
|
|||
STATIC_UNIT_TESTED uint8_t rxTxAddrXN297[RX_TX_ADDR_LEN] = {0x41, 0xbd, 0x42, 0xd4, 0xc2}; // converted XN297 address
|
||||
#define TX_ID_LEN 4
|
||||
STATIC_UNIT_TESTED uint8_t txId[TX_ID_LEN];
|
||||
uint32_t *nrf24rxIdPtr;
|
||||
uint32_t *rxSpiIdPtr;
|
||||
|
||||
// radio channels for frequency hopping
|
||||
#define H8_3D_RF_CHANNEL_COUNT 4
|
||||
|
@ -112,9 +112,9 @@ STATIC_UNIT_TESTED bool h8_3dCheckBindPacket(const uint8_t *payload)
|
|||
txId[1] = payload[2];
|
||||
txId[2] = payload[3];
|
||||
txId[3] = payload[4];
|
||||
if (nrf24rxIdPtr != NULL && *nrf24rxIdPtr == 0) {
|
||||
if (rxSpiIdPtr != NULL && *rxSpiIdPtr == 0) {
|
||||
// copy the txId so it can be saved
|
||||
memcpy(nrf24rxIdPtr, txId, sizeof(uint32_t));
|
||||
memcpy(rxSpiIdPtr, txId, sizeof(uint32_t));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -133,11 +133,11 @@ STATIC_UNIT_TESTED uint16_t h8_3dConvertToPwm(uint8_t val, int16_t _min, int16_t
|
|||
|
||||
void h8_3dNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
||||
{
|
||||
rcData[NRF24_ROLL] = h8_3dConvertToPwm(payload[12], 0xbb, 0x43); // aileron
|
||||
rcData[NRF24_PITCH] = h8_3dConvertToPwm(payload[11], 0x43, 0xbb); // elevator
|
||||
rcData[NRF24_THROTTLE] = h8_3dConvertToPwm(payload[9], 0, 0xff); // throttle
|
||||
rcData[RC_SPI_ROLL] = h8_3dConvertToPwm(payload[12], 0xbb, 0x43); // aileron
|
||||
rcData[RC_SPI_PITCH] = h8_3dConvertToPwm(payload[11], 0x43, 0xbb); // elevator
|
||||
rcData[RC_SPI_THROTTLE] = h8_3dConvertToPwm(payload[9], 0, 0xff); // throttle
|
||||
const int8_t yawByte = payload[10]; // rudder
|
||||
rcData[NRF24_YAW] = yawByte >= 0 ? h8_3dConvertToPwm(yawByte, -0x3c, 0x3c) : h8_3dConvertToPwm(yawByte, 0xbc, 0x44);
|
||||
rcData[RC_SPI_YAW] = yawByte >= 0 ? h8_3dConvertToPwm(yawByte, -0x3c, 0x3c) : h8_3dConvertToPwm(yawByte, 0xbc, 0x44);
|
||||
|
||||
const uint8_t flags = payload[17];
|
||||
const uint8_t flags2 = payload[18];
|
||||
|
@ -156,15 +156,15 @@ void h8_3dNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
rcData[RC_CHANNEL_RTH] = flags & FLAG_RTH ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
|
||||
if (flags2 & FLAG_CAMERA_UP) {
|
||||
rcData[NRF24_AUX7] = PWM_RANGE_MAX;
|
||||
rcData[RC_SPI_AUX7] = PWM_RANGE_MAX;
|
||||
} else if (flags2 & FLAG_CAMERA_DOWN) {
|
||||
rcData[NRF24_AUX7] = PWM_RANGE_MIN;
|
||||
rcData[RC_SPI_AUX7] = PWM_RANGE_MIN;
|
||||
} else {
|
||||
rcData[NRF24_AUX7] = PWM_RANGE_MIDDLE;
|
||||
rcData[RC_SPI_AUX7] = PWM_RANGE_MIDDLE;
|
||||
}
|
||||
rcData[NRF24_AUX8] = h8_3dConvertToPwm(payload[14], 0x10, 0x30);
|
||||
rcData[NRF24_AUX9] = h8_3dConvertToPwm(payload[15], 0x30, 0x10);
|
||||
rcData[NRF24_AUX10] = h8_3dConvertToPwm(payload[16], 0x10, 0x30);
|
||||
rcData[RC_SPI_AUX8] = h8_3dConvertToPwm(payload[14], 0x10, 0x30);
|
||||
rcData[RC_SPI_AUX9] = h8_3dConvertToPwm(payload[15], 0x30, 0x10);
|
||||
rcData[RC_SPI_AUX10] = h8_3dConvertToPwm(payload[16], 0x10, 0x30);
|
||||
}
|
||||
|
||||
static void h8_3dHopToNextChannel(void)
|
||||
|
@ -216,9 +216,9 @@ static bool h8_3dCrcOK(uint16_t crc, const uint8_t *payload)
|
|||
* This is called periodically by the scheduler.
|
||||
* Returns NRF24L01_RECEIVED_DATA if a data packet was received.
|
||||
*/
|
||||
nrf24_received_t h8_3dNrf24DataReceived(uint8_t *payload)
|
||||
rx_spi_received_e h8_3dNrf24DataReceived(uint8_t *payload)
|
||||
{
|
||||
nrf24_received_t ret = NRF24_RECEIVED_NONE;
|
||||
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
|
||||
bool payloadReceived = false;
|
||||
if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize + CRC_LEN)) {
|
||||
const uint16_t crc = XN297_UnscramblePayload(payload, payloadSize, rxTxAddrXN297);
|
||||
|
@ -231,26 +231,26 @@ nrf24_received_t h8_3dNrf24DataReceived(uint8_t *payload)
|
|||
if (payloadReceived) {
|
||||
const bool bindPacket = h8_3dCheckBindPacket(payload);
|
||||
if (bindPacket) {
|
||||
ret = NRF24_RECEIVED_BIND;
|
||||
ret = RX_SPI_RECEIVED_BIND;
|
||||
h8_3dSetBound(txId);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case STATE_DATA:
|
||||
if (payloadReceived) {
|
||||
ret = NRF24_RECEIVED_DATA;
|
||||
ret = RX_SPI_RECEIVED_DATA;
|
||||
}
|
||||
break;
|
||||
}
|
||||
const uint32_t timeNowUs = micros();
|
||||
if ((ret == NRF24_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
|
||||
if ((ret == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
|
||||
h8_3dHopToNextChannel();
|
||||
timeOfLastHop = timeNowUs;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
static void h8_3dNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_id)
|
||||
static void h8_3dNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId)
|
||||
{
|
||||
UNUSED(protocol);
|
||||
protocolState = STATE_BIND;
|
||||
|
@ -261,12 +261,12 @@ static void h8_3dNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_i
|
|||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
// RX_ADDR for pipes P1-P5 are left at default values
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddrXN297, RX_TX_ADDR_LEN);
|
||||
nrf24rxIdPtr = (uint32_t*)nrf24rx_id;
|
||||
if (nrf24rx_id == NULL || *nrf24rx_id == 0) {
|
||||
rxSpiIdPtr = (uint32_t*)rxSpiId;
|
||||
if (rxSpiId == NULL || *rxSpiId == 0) {
|
||||
h8_3dRfChannelIndex = H8_3D_RF_BIND_CHANNEL_START;
|
||||
NRF24L01_SetChannel(H8_3D_RF_BIND_CHANNEL_START);
|
||||
} else {
|
||||
h8_3dSetBound((uint8_t*)nrf24rx_id);
|
||||
h8_3dSetBound((uint8_t*)rxSpiId);
|
||||
}
|
||||
|
||||
payloadSize = H8_3D_PROTOCOL_PAYLOAD_SIZE;
|
||||
|
@ -278,6 +278,6 @@ static void h8_3dNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_i
|
|||
void h8_3dNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
h8_3dNrf24Setup((nrf24_protocol_t)rxConfig->nrf24rx_protocol, &rxConfig->nrf24rx_id);
|
||||
h8_3dNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol, &rxConfig->rx_spi_id);
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -24,4 +24,4 @@ struct rxConfig_s;
|
|||
struct rxRuntimeConfig_s;
|
||||
void h8_3dNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void h8_3dNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
nrf24_received_t h8_3dNrf24DataReceived(uint8_t *payload);
|
||||
rx_spi_received_e h8_3dNrf24DataReceived(uint8_t *payload);
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_inav.h"
|
||||
|
||||
#include "telemetry/ltm.h"
|
||||
|
@ -119,7 +119,7 @@ uint8_t receivedPowerSnapshot;
|
|||
#define RX_TX_ADDR_LEN 5
|
||||
// set rxTxAddr to the bind address
|
||||
STATIC_UNIT_TESTED uint8_t rxTxAddr[RX_TX_ADDR_LEN] = {0x4b,0x5c,0x6d,0x7e,0x8f};
|
||||
uint32_t *nrf24rxIdPtr;
|
||||
uint32_t *rxSpiIdPtr;
|
||||
#define RX_TX_ADDR_4 0xD2 // rxTxAddr[4] always set to this value
|
||||
|
||||
// radio channels for frequency hopping
|
||||
|
@ -149,9 +149,9 @@ STATIC_UNIT_TESTED bool inavCheckBindPacket(const uint8_t *payload)
|
|||
if (inavRfChannelHoppingCount > INAV_RF_CHANNEL_COUNT_MAX) {
|
||||
inavRfChannelHoppingCount = INAV_RF_CHANNEL_COUNT_MAX;
|
||||
}*/
|
||||
if (nrf24rxIdPtr != NULL && *nrf24rxIdPtr == 0) {
|
||||
if (rxSpiIdPtr != NULL && *rxSpiIdPtr == 0) {
|
||||
// copy the rxTxAddr so it can be saved
|
||||
memcpy(nrf24rxIdPtr, rxTxAddr, sizeof(uint32_t));
|
||||
memcpy(rxSpiIdPtr, rxTxAddr, sizeof(uint32_t));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -164,18 +164,18 @@ void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
// payload[0] and payload[1] are zero in DATA state
|
||||
// the AETR channels have 10 bit resolution
|
||||
uint8_t lowBits = payload[6]; // least significant bits for AETR
|
||||
rcData[NRF24_ROLL] = PWM_RANGE_MIN + ((payload[2] << 2) | (lowBits & 0x03)); // Aileron
|
||||
rcData[RC_SPI_ROLL] = PWM_RANGE_MIN + ((payload[2] << 2) | (lowBits & 0x03)); // Aileron
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_PITCH] = PWM_RANGE_MIN + ((payload[3] << 2) | (lowBits & 0x03)); // Elevator
|
||||
rcData[RC_SPI_PITCH] = PWM_RANGE_MIN + ((payload[3] << 2) | (lowBits & 0x03)); // Elevator
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_THROTTLE] = PWM_RANGE_MIN + ((payload[4] << 2) | (lowBits & 0x03)); // Throttle
|
||||
rcData[RC_SPI_THROTTLE] = PWM_RANGE_MIN + ((payload[4] << 2) | (lowBits & 0x03)); // Throttle
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_YAW] = PWM_RANGE_MIN + ((payload[5] << 2) | (lowBits & 0x03)); // Rudder
|
||||
rcData[RC_SPI_YAW] = PWM_RANGE_MIN + ((payload[5] << 2) | (lowBits & 0x03)); // Rudder
|
||||
|
||||
if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MIN) {
|
||||
// small payload variant of protocol, supports 6 channels
|
||||
rcData[NRF24_AUX1] = PWM_RANGE_MIN + (payload[7] << 2);
|
||||
rcData[NRF24_AUX2] = PWM_RANGE_MIN + (payload[1] << 2);
|
||||
rcData[RC_SPI_AUX1] = PWM_RANGE_MIN + (payload[7] << 2);
|
||||
rcData[RC_SPI_AUX2] = PWM_RANGE_MIN + (payload[1] << 2);
|
||||
} else {
|
||||
// channel AUX1 is used for rate, as per the deviation convention
|
||||
const uint8_t rate = payload[7];
|
||||
|
@ -198,24 +198,24 @@ void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
|||
|
||||
// channels AUX7 to AUX10 have 10 bit resolution
|
||||
lowBits = payload[13]; // least significant bits for AUX7 to AUX10
|
||||
rcData[NRF24_AUX7] = PWM_RANGE_MIN + ((payload[9] << 2) | (lowBits & 0x03));
|
||||
rcData[RC_SPI_AUX7] = PWM_RANGE_MIN + ((payload[9] << 2) | (lowBits & 0x03));
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_AUX8] = PWM_RANGE_MIN + ((payload[10] << 2) | (lowBits & 0x03));
|
||||
rcData[RC_SPI_AUX8] = PWM_RANGE_MIN + ((payload[10] << 2) | (lowBits & 0x03));
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_AUX9] = PWM_RANGE_MIN + ((payload[11] << 2) | (lowBits & 0x03));
|
||||
rcData[RC_SPI_AUX9] = PWM_RANGE_MIN + ((payload[11] << 2) | (lowBits & 0x03));
|
||||
lowBits >>= 2;
|
||||
rcData[NRF24_AUX10] = PWM_RANGE_MIN + ((payload[12] << 2) | (lowBits & 0x03));
|
||||
rcData[RC_SPI_AUX10] = PWM_RANGE_MIN + ((payload[12] << 2) | (lowBits & 0x03));
|
||||
lowBits >>= 2;
|
||||
|
||||
// channels AUX11 and AUX12 have 8 bit resolution
|
||||
rcData[NRF24_AUX11] = PWM_RANGE_MIN + (payload[14] << 2);
|
||||
rcData[NRF24_AUX12] = PWM_RANGE_MIN + (payload[15] << 2);
|
||||
rcData[RC_SPI_AUX11] = PWM_RANGE_MIN + (payload[14] << 2);
|
||||
rcData[RC_SPI_AUX12] = PWM_RANGE_MIN + (payload[15] << 2);
|
||||
}
|
||||
if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MAX) {
|
||||
// large payload variant of protocol
|
||||
// channels AUX13 to AUX16 have 8 bit resolution
|
||||
rcData[NRF24_AUX13] = PWM_RANGE_MIN + (payload[16] << 2);
|
||||
rcData[NRF24_AUX14] = PWM_RANGE_MIN + (payload[17] << 2);
|
||||
rcData[RC_SPI_AUX13] = PWM_RANGE_MIN + (payload[16] << 2);
|
||||
rcData[RC_SPI_AUX14] = PWM_RANGE_MIN + (payload[17] << 2);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -320,18 +320,18 @@ static void writeBindAckPayload(uint8_t *payload)
|
|||
|
||||
/*
|
||||
* This is called periodically by the scheduler.
|
||||
* Returns NRF24L01_RECEIVED_DATA if a data packet was received.
|
||||
* Returns RX_SPI_RECEIVED_DATA if a data packet was received.
|
||||
*/
|
||||
nrf24_received_t inavNrf24DataReceived(uint8_t *payload)
|
||||
rx_spi_received_e inavNrf24DataReceived(uint8_t *payload)
|
||||
{
|
||||
nrf24_received_t ret = NRF24_RECEIVED_NONE;
|
||||
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
|
||||
uint32_t timeNowUs;
|
||||
switch (protocolState) {
|
||||
case STATE_BIND:
|
||||
if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) {
|
||||
const bool bindPacket = inavCheckBindPacket(payload);
|
||||
if (bindPacket) {
|
||||
ret = NRF24_RECEIVED_BIND;
|
||||
ret = RX_SPI_RECEIVED_BIND;
|
||||
writeBindAckPayload(payload);
|
||||
// got a bind packet, so set the hopping channels and the rxTxAddr and start listening for data
|
||||
inavSetBound();
|
||||
|
@ -346,14 +346,14 @@ nrf24_received_t inavNrf24DataReceived(uint8_t *payload)
|
|||
const bool bindPacket = inavCheckBindPacket(payload);
|
||||
if (bindPacket) {
|
||||
// transmitter may still continue to transmit bind packets after we have switched to data mode
|
||||
ret = NRF24_RECEIVED_BIND;
|
||||
ret = RX_SPI_RECEIVED_BIND;
|
||||
writeBindAckPayload(payload);
|
||||
} else {
|
||||
ret = NRF24_RECEIVED_DATA;
|
||||
ret = RX_SPI_RECEIVED_DATA;
|
||||
writeTelemetryAckPayload();
|
||||
}
|
||||
}
|
||||
if ((ret == NRF24_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
|
||||
if ((ret == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
|
||||
inavHopToNextChannel();
|
||||
timeOfLastHop = timeNowUs;
|
||||
}
|
||||
|
@ -362,7 +362,7 @@ nrf24_received_t inavNrf24DataReceived(uint8_t *payload)
|
|||
return ret;
|
||||
}
|
||||
|
||||
static void inavNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_id, int rfChannelHoppingCount)
|
||||
static void inavNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId, int rfChannelHoppingCount)
|
||||
{
|
||||
UNUSED(protocol);
|
||||
UNUSED(rfChannelHoppingCount);
|
||||
|
@ -392,19 +392,19 @@ static void inavNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_id
|
|||
|
||||
#ifdef USE_BIND_ADDRESS_FOR_DATA_STATE
|
||||
inavSetBound();
|
||||
UNUSED(nrf24rx_id);
|
||||
UNUSED(rxSpiId);
|
||||
#else
|
||||
nrf24rx_id = NULL; // !!TODO remove this once configurator supports setting rx_id
|
||||
if (nrf24rx_id == NULL || *nrf24rx_id == 0) {
|
||||
nrf24rxIdPtr = NULL;
|
||||
rxSpiId = NULL; // !!TODO remove this once configurator supports setting rx_id
|
||||
if (rxSpiId == NULL || *rxSpiId == 0) {
|
||||
rxSpiIdPtr = NULL;
|
||||
protocolState = STATE_BIND;
|
||||
inavRfChannelCount = 1;
|
||||
inavRfChannelIndex = 0;
|
||||
NRF24L01_SetChannel(INAV_RF_BIND_CHANNEL);
|
||||
} else {
|
||||
nrf24rxIdPtr = (uint32_t*)nrf24rx_id;
|
||||
rxSpiIdPtr = (uint32_t*)rxSpiId;
|
||||
// use the rxTxAddr provided and go straight into DATA_STATE
|
||||
memcpy(rxTxAddr, nrf24rx_id, sizeof(uint32_t));
|
||||
memcpy(rxTxAddr, rxSpiId, sizeof(uint32_t));
|
||||
rxTxAddr[4] = RX_TX_ADDR_4;
|
||||
inavSetBound();
|
||||
}
|
||||
|
@ -418,7 +418,7 @@ static void inavNrf24Setup(nrf24_protocol_t protocol, const uint32_t *nrf24rx_id
|
|||
void inavNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_MAX;
|
||||
inavNrf24Setup((nrf24_protocol_t)rxConfig->nrf24rx_protocol, &rxConfig->nrf24rx_id, rxConfig->nrf24rx_rf_channel_count);
|
||||
inavNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol, &rxConfig->rx_spi_id, rxConfig->rx_spi_rf_channel_count);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -24,5 +24,5 @@ struct rxConfig_s;
|
|||
struct rxRuntimeConfig_s;
|
||||
void inavNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
nrf24_received_t inavNrf24DataReceived(uint8_t *payload);
|
||||
rx_spi_received_e inavNrf24DataReceived(uint8_t *payload);
|
||||
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_syma.h"
|
||||
|
||||
/*
|
||||
|
@ -85,7 +85,7 @@ enum {
|
|||
#define FLAG_VIDEO_X5C 0x10
|
||||
#define FLAG_RATE_X5C 0x04
|
||||
|
||||
STATIC_UNIT_TESTED nrf24_protocol_t symaProtocol;
|
||||
STATIC_UNIT_TESTED rx_spi_protocol_e symaProtocol;
|
||||
|
||||
typedef enum {
|
||||
STATE_BIND = 0,
|
||||
|
@ -159,11 +159,11 @@ STATIC_UNIT_TESTED uint16_t symaConvertToPwmSigned(uint8_t val)
|
|||
|
||||
void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
||||
{
|
||||
rcData[NRF24_THROTTLE] = symaConvertToPwmUnsigned(packet[0]); // throttle
|
||||
rcData[NRF24_ROLL] = symaConvertToPwmSigned(packet[3]); // aileron
|
||||
rcData[RC_SPI_THROTTLE] = symaConvertToPwmUnsigned(packet[0]); // throttle
|
||||
rcData[RC_SPI_ROLL] = symaConvertToPwmSigned(packet[3]); // aileron
|
||||
if (symaProtocol == NRF24RX_SYMA_X) {
|
||||
rcData[NRF24_PITCH] = symaConvertToPwmSigned(packet[1]); // elevator
|
||||
rcData[NRF24_YAW] = symaConvertToPwmSigned(packet[2]); // rudder
|
||||
rcData[RC_SPI_PITCH] = symaConvertToPwmSigned(packet[1]); // elevator
|
||||
rcData[RC_SPI_YAW] = symaConvertToPwmSigned(packet[2]); // rudder
|
||||
const uint8_t rate = (packet[5] & 0xc0) >> 6;
|
||||
if (rate == RATE_LOW) {
|
||||
rcData[RC_CHANNEL_RATE] = PWM_RANGE_MIN;
|
||||
|
@ -177,8 +177,8 @@ void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
|||
rcData[RC_CHANNEL_VIDEO] = packet[4] & FLAG_VIDEO ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
rcData[RC_CHANNEL_HEADLESS] = packet[14] & FLAG_HEADLESS ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
} else {
|
||||
rcData[NRF24_PITCH] = symaConvertToPwmSigned(packet[2]); // elevator
|
||||
rcData[NRF24_YAW] = symaConvertToPwmSigned(packet[1]); // rudder
|
||||
rcData[RC_SPI_PITCH] = symaConvertToPwmSigned(packet[2]); // elevator
|
||||
rcData[RC_SPI_YAW] = symaConvertToPwmSigned(packet[1]); // rudder
|
||||
const uint8_t flags = packet[14];
|
||||
rcData[RC_CHANNEL_RATE] = flags & FLAG_RATE_X5C ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
rcData[RC_CHANNEL_FLIP] = flags & FLAG_FLIP_X5C ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
|
@ -224,18 +224,18 @@ static void setSymaXHoppingChannels(uint32_t addr)
|
|||
|
||||
/*
|
||||
* This is called periodically by the scheduler.
|
||||
* Returns NRF24_RECEIVED_DATA if a data packet was received.
|
||||
* Returns RX_SPI_RECEIVED_DATA if a data packet was received.
|
||||
*/
|
||||
nrf24_received_t symaNrf24DataReceived(uint8_t *payload)
|
||||
rx_spi_received_e symaNrf24DataReceived(uint8_t *payload)
|
||||
{
|
||||
nrf24_received_t ret = NRF24_RECEIVED_NONE;
|
||||
rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
|
||||
|
||||
switch (protocolState) {
|
||||
case STATE_BIND:
|
||||
if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) {
|
||||
const bool bindPacket = symaCheckBindPacket(payload);
|
||||
if (bindPacket) {
|
||||
ret = NRF24_RECEIVED_BIND;
|
||||
ret = RX_SPI_RECEIVED_BIND;
|
||||
protocolState = STATE_DATA;
|
||||
// using protocol NRF24L01_SYMA_X, since NRF24L01_SYMA_X5C went straight into data mode
|
||||
// set the hopping channels as determined by the rxTxAddr received in the bind packet
|
||||
|
@ -253,7 +253,7 @@ nrf24_received_t symaNrf24DataReceived(uint8_t *payload)
|
|||
if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize)) {
|
||||
symaHopToNextChannel();
|
||||
timeOfLastHop = micros();
|
||||
ret = NRF24_RECEIVED_DATA;
|
||||
ret = RX_SPI_RECEIVED_DATA;
|
||||
}
|
||||
if (micros() > timeOfLastHop + hopTimeout) {
|
||||
symaHopToNextChannel();
|
||||
|
@ -264,7 +264,7 @@ nrf24_received_t symaNrf24DataReceived(uint8_t *payload)
|
|||
return ret;
|
||||
}
|
||||
|
||||
static void symaNrf24Setup(nrf24_protocol_t protocol)
|
||||
static void symaNrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
symaProtocol = protocol;
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV( NRF24L01_00_CONFIG_CRCO)); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC
|
||||
|
@ -295,7 +295,7 @@ static void symaNrf24Setup(nrf24_protocol_t protocol)
|
|||
void symaNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
|
||||
symaNrf24Setup((nrf24_protocol_t)rxConfig->nrf24rx_protocol);
|
||||
symaNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -24,5 +24,5 @@ struct rxConfig_s;
|
|||
struct rxRuntimeConfig_s;
|
||||
void symaNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
nrf24_received_t symaNrf24DataReceived(uint8_t *payload);
|
||||
rx_spi_received_e symaNrf24DataReceived(uint8_t *payload);
|
||||
|
||||
|
|
|
@ -31,7 +31,7 @@
|
|||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_v202.h"
|
||||
|
||||
/*
|
||||
|
@ -97,10 +97,10 @@ STATIC_UNIT_TESTED uint8_t bind_phase;
|
|||
static uint32_t packet_timer;
|
||||
STATIC_UNIT_TESTED uint8_t txid[TXIDSIZE];
|
||||
static uint32_t rx_timeout;
|
||||
extern uint16_t nrf24RcData[];
|
||||
extern uint16_t rxSpiRcData[];
|
||||
|
||||
static const unsigned char v2x2_channelindex[] = {NRF24_THROTTLE,NRF24_YAW,NRF24_PITCH,NRF24_ROLL,
|
||||
NRF24_AUX1,NRF24_AUX2,NRF24_AUX3,NRF24_AUX4,NRF24_AUX5,NRF24_AUX6,NRF24_AUX7};
|
||||
static const unsigned char v2x2_channelindex[] = {RC_SPI_THROTTLE,RC_SPI_YAW,RC_SPI_PITCH,RC_SPI_ROLL,
|
||||
RC_SPI_AUX1,RC_SPI_AUX2,RC_SPI_AUX3,RC_SPI_AUX4,RC_SPI_AUX5,RC_SPI_AUX6,RC_SPI_AUX7};
|
||||
|
||||
static void prepare_to_bind(void)
|
||||
{
|
||||
|
@ -147,41 +147,41 @@ static void decode_bind_packet(uint8_t *packet)
|
|||
}
|
||||
|
||||
// Returns whether the data was successfully decoded
|
||||
static nrf24_received_t decode_packet(uint8_t *packet)
|
||||
static rx_spi_received_e decode_packet(uint8_t *packet)
|
||||
{
|
||||
if(bind_phase != PHASE_BOUND) {
|
||||
decode_bind_packet(packet);
|
||||
return NRF24_RECEIVED_BIND;
|
||||
return RX_SPI_RECEIVED_BIND;
|
||||
}
|
||||
// Decode packet
|
||||
if ((packet[14] & V2X2_FLAG_BIND) == V2X2_FLAG_BIND) {
|
||||
return NRF24_RECEIVED_BIND;
|
||||
return RX_SPI_RECEIVED_BIND;
|
||||
}
|
||||
if (packet[7] != txid[0] ||
|
||||
packet[8] != txid[1] ||
|
||||
packet[9] != txid[2]) {
|
||||
return NRF24_RECEIVED_NONE;
|
||||
return RX_SPI_RECEIVED_NONE;
|
||||
}
|
||||
// Restore regular interval
|
||||
rx_timeout = 10000L; // 4ms interval, duplicate packets, (8ms unique) + 25%
|
||||
// TREA order in packet to MultiWii order is handled by
|
||||
// correct assignment to channelindex
|
||||
// Throttle 0..255 to 1000..2000
|
||||
nrf24RcData[v2x2_channelindex[0]] = ((uint16_t)packet[0]) * 1000 / 255 + 1000;
|
||||
rxSpiRcData[v2x2_channelindex[0]] = ((uint16_t)packet[0]) * 1000 / 255 + 1000;
|
||||
for (int i = 1; i < 4; ++i) {
|
||||
uint8_t a = packet[i];
|
||||
nrf24RcData[v2x2_channelindex[i]] = ((uint16_t)(a < 0x80 ? 0x7f - a : a)) * 1000 / 255 + 1000;
|
||||
rxSpiRcData[v2x2_channelindex[i]] = ((uint16_t)(a < 0x80 ? 0x7f - a : a)) * 1000 / 255 + 1000;
|
||||
}
|
||||
const uint8_t flags[] = {V2X2_FLAG_LED, V2X2_FLAG_FLIP, V2X2_FLAG_CAMERA, V2X2_FLAG_VIDEO}; // two more unknown bits
|
||||
for (int i = 4; i < 8; ++i) {
|
||||
nrf24RcData[v2x2_channelindex[i]] = (packet[14] & flags[i-4]) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
rxSpiRcData[v2x2_channelindex[i]] = (packet[14] & flags[i-4]) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
}
|
||||
const uint8_t flags10[] = {V2X2_FLAG_HEADLESS, V2X2_FLAG_MAG_CAL_X, V2X2_FLAG_MAG_CAL_Y};
|
||||
for (int i = 8; i < 11; ++i) {
|
||||
nrf24RcData[v2x2_channelindex[i]] = (packet[10] & flags10[i-8]) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
rxSpiRcData[v2x2_channelindex[i]] = (packet[10] & flags10[i-8]) ? PWM_RANGE_MAX : PWM_RANGE_MIN;
|
||||
}
|
||||
packet_timer = micros();
|
||||
return NRF24_RECEIVED_DATA;
|
||||
return RX_SPI_RECEIVED_DATA;
|
||||
}
|
||||
|
||||
void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
||||
|
@ -191,7 +191,7 @@ void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
|
|||
// Ideally the decoding of the packet should be moved into here, to reduce the overhead of v202DataReceived function.
|
||||
}
|
||||
|
||||
static nrf24_received_t readrx(uint8_t *packet)
|
||||
static rx_spi_received_e readrx(uint8_t *packet)
|
||||
{
|
||||
if (!(NRF24L01_ReadReg(NRF24L01_07_STATUS) & BV(NRF24L01_07_STATUS_RX_DR))) {
|
||||
uint32_t t = micros() - packet_timer;
|
||||
|
@ -199,7 +199,7 @@ static nrf24_received_t readrx(uint8_t *packet)
|
|||
switch_channel();
|
||||
packet_timer = micros();
|
||||
}
|
||||
return NRF24_RECEIVED_NONE;
|
||||
return RX_SPI_RECEIVED_NONE;
|
||||
}
|
||||
packet_timer = micros();
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR)); // clear the RX_DR flag
|
||||
|
@ -212,14 +212,14 @@ static nrf24_received_t readrx(uint8_t *packet)
|
|||
|
||||
/*
|
||||
* This is called periodically by the scheduler.
|
||||
* Returns NRF24_RECEIVED_DATA if a data packet was received.
|
||||
* Returns RX_SPI_RECEIVED_DATA if a data packet was received.
|
||||
*/
|
||||
nrf24_received_t v202Nrf24DataReceived(uint8_t *packet)
|
||||
rx_spi_received_e v202Nrf24DataReceived(uint8_t *packet)
|
||||
{
|
||||
return readrx(packet);
|
||||
}
|
||||
|
||||
static void v202Nrf24Setup(nrf24_protocol_t protocol)
|
||||
static void v202Nrf24Setup(rx_spi_protocol_e protocol)
|
||||
{
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO)); // 2-bytes CRC
|
||||
|
||||
|
@ -253,7 +253,6 @@ static void v202Nrf24Setup(nrf24_protocol_t protocol)
|
|||
void v202Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||
{
|
||||
rxRuntimeConfig->channelCount = V2X2_RC_CHANNEL_COUNT;
|
||||
v202Nrf24Setup((nrf24_protocol_t)rxConfig->nrf24rx_protocol);
|
||||
v202Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -23,5 +23,5 @@
|
|||
struct rxConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
void v202Nrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
|
||||
nrf24_received_t v202Nrf24DataReceived(uint8_t *payload);
|
||||
void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
rx_spi_received_e v202Nrf24DataReceived(uint8_t *payload);
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "drivers/rx_spi.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "rx/pwm.h"
|
||||
|
@ -57,7 +57,7 @@
|
|||
#include "rx/xbus.h"
|
||||
#include "rx/ibus.h"
|
||||
#include "rx/jetiexbus.h"
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
@ -193,13 +193,13 @@ void rxInit(rxConfig_t *rxConfig, modeActivationCondition_t *modeActivationCondi
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_NRF24
|
||||
if (feature(FEATURE_RX_NRF24)) {
|
||||
#ifdef USE_RX_SPI
|
||||
if (feature(FEATURE_RX_SPI)) {
|
||||
rxRefreshRate = 10000;
|
||||
const nfr24l01_spi_type_e spiType = feature(FEATURE_SOFTSPI) ? NFR24L01_SOFTSPI : NFR24L01_SPI;
|
||||
const bool enabled = rxNrf24Init(spiType, rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
const rx_spi_type_e spiType = feature(FEATURE_SOFTSPI) ? RX_SPI_SOFTSPI : RX_SPI_HARDSPI;
|
||||
const bool enabled = rxSpiInit(spiType, rxConfig, &rxRuntimeConfig, &rcReadRawFunc);
|
||||
if (!enabled) {
|
||||
featureClear(FEATURE_RX_NRF24);
|
||||
featureClear(FEATURE_RX_SPI);
|
||||
rcReadRawFunc = nullReadRawRC;
|
||||
}
|
||||
}
|
||||
|
@ -363,9 +363,9 @@ void updateRx(uint32_t currentTime)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RX_NRF24
|
||||
if (feature(FEATURE_RX_NRF24)) {
|
||||
rxDataReceived = rxNrf24DataReceived();
|
||||
#ifdef USE_RX_SPI
|
||||
if (feature(FEATURE_RX_SPI)) {
|
||||
rxDataReceived = rxSpiDataReceived();
|
||||
if (rxDataReceived) {
|
||||
rxSignalReceived = true;
|
||||
rxIsInFailsafeMode = false;
|
||||
|
|
|
@ -113,9 +113,9 @@ typedef struct rxConfig_s {
|
|||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
||||
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||
uint8_t sbus_inversion; // default sbus (Futaba, FrSKY) is inverted. Support for uninverted OpenLRS (and modified FrSKY) receivers.
|
||||
uint8_t nrf24rx_protocol; // type of nrf24 protocol (0 = v202 250kbps). Must be enabled by FEATURE_RX_NRF24 first.
|
||||
uint32_t nrf24rx_id;
|
||||
uint8_t nrf24rx_rf_channel_count;
|
||||
uint8_t rx_spi_protocol; // type of nrf24 protocol (0 = v202 250kbps). Must be enabled by FEATURE_RX_NRF24 first.
|
||||
uint32_t rx_spi_id;
|
||||
uint8_t rx_spi_rf_channel_count;
|
||||
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
|
||||
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
|
||||
uint8_t rssi_channel;
|
||||
|
|
|
@ -20,13 +20,13 @@
|
|||
|
||||
#include <platform.h>
|
||||
|
||||
#ifdef USE_RX_NRF24
|
||||
#ifdef USE_RX_SPI
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "drivers/rx_nrf24l01.h"
|
||||
#include "rx/rx.h"
|
||||
#include "rx/nrf24.h"
|
||||
#include "rx/rx_spi.h"
|
||||
#include "rx/nrf24_cx10.h"
|
||||
#include "rx/nrf24_syma.h"
|
||||
#include "rx/nrf24_v202.h"
|
||||
|
@ -34,31 +34,32 @@
|
|||
#include "rx/nrf24_inav.h"
|
||||
|
||||
|
||||
uint16_t nrf24RcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
STATIC_UNIT_TESTED uint8_t nrf24Payload[NRF24L01_MAX_PAYLOAD_SIZE];
|
||||
STATIC_UNIT_TESTED uint8_t nrf24NewPacketAvailable; // set true when a new packet is received
|
||||
uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||
STATIC_UNIT_TESTED uint8_t rxSpiPayload[RX_SPI_MAX_PAYLOAD_SIZE];
|
||||
STATIC_UNIT_TESTED uint8_t rxSpiNewPacketAvailable; // set true when a new packet is received
|
||||
|
||||
typedef void (*protocolInitPtr)(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
|
||||
typedef nrf24_received_t (*protocolDataReceivedPtr)(uint8_t *payload);
|
||||
typedef rx_spi_received_e (*protocolDataReceivedPtr)(uint8_t *payload);
|
||||
typedef void (*protocolSetRcDataFromPayloadPtr)(uint16_t *rcData, const uint8_t *payload);
|
||||
|
||||
static protocolInitPtr protocolInit;
|
||||
static protocolDataReceivedPtr protocolDataReceived;
|
||||
static protocolSetRcDataFromPayloadPtr protocolSetRcDataFromPayload;
|
||||
|
||||
STATIC_UNIT_TESTED uint16_t rxNrf24ReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
|
||||
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
|
||||
{
|
||||
BUILD_BUG_ON(NRF24L01_MAX_PAYLOAD_SIZE > RX_SPI_MAX_PAYLOAD_SIZE);
|
||||
if (channel >= rxRuntimeConfig->channelCount) {
|
||||
return 0;
|
||||
}
|
||||
if (nrf24NewPacketAvailable) {
|
||||
protocolSetRcDataFromPayload(nrf24RcData, nrf24Payload);
|
||||
nrf24NewPacketAvailable = false;
|
||||
if (rxSpiNewPacketAvailable) {
|
||||
protocolSetRcDataFromPayload(rxSpiRcData, rxSpiPayload);
|
||||
rxSpiNewPacketAvailable = false;
|
||||
}
|
||||
return nrf24RcData[channel];
|
||||
return rxSpiRcData[channel];
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED bool rxNrf24SetProtocol(nrf24_protocol_t protocol)
|
||||
STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
|
||||
{
|
||||
switch (protocol) {
|
||||
default:
|
||||
|
@ -105,33 +106,33 @@ STATIC_UNIT_TESTED bool rxNrf24SetProtocol(nrf24_protocol_t protocol)
|
|||
}
|
||||
|
||||
/*
|
||||
* Returns true if the NRF24L01 has received new data.
|
||||
* Returns true if the RX has received new data.
|
||||
* Called from updateRx in rx.c, updateRx called from taskUpdateRxCheck.
|
||||
* If taskUpdateRxCheck returns true, then taskUpdateRxMain will shortly be called.
|
||||
*/
|
||||
bool rxNrf24DataReceived(void)
|
||||
bool rxSpiDataReceived(void)
|
||||
{
|
||||
if (protocolDataReceived(nrf24Payload) == NRF24_RECEIVED_DATA) {
|
||||
nrf24NewPacketAvailable = true;
|
||||
if (protocolDataReceived(rxSpiPayload) == RX_SPI_RECEIVED_DATA) {
|
||||
rxSpiNewPacketAvailable = true;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
/*
|
||||
* Set and initialize the NRF24 protocol
|
||||
* Set and initialize the RX protocol
|
||||
*/
|
||||
bool rxNrf24Init(nfr24l01_spi_type_e spiType, const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
bool rxSpiInit(rx_spi_type_e spiType, const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||
{
|
||||
bool ret = false;
|
||||
NRF24L01_SpiInit(spiType);
|
||||
if (rxNrf24SetProtocol(rxConfig->nrf24rx_protocol)) {
|
||||
rxSpiDeviceInit(spiType);
|
||||
if (rxSpiSetProtocol(rxConfig->rx_spi_protocol)) {
|
||||
protocolInit(rxConfig, rxRuntimeConfig);
|
||||
ret = true;
|
||||
}
|
||||
nrf24NewPacketAvailable = false;
|
||||
rxSpiNewPacketAvailable = false;
|
||||
if (callback) {
|
||||
*callback = rxNrf24ReadRawRC;
|
||||
*callback = rxSpiReadRawRC;
|
||||
}
|
||||
return ret;
|
||||
}
|
|
@ -32,45 +32,45 @@ typedef enum {
|
|||
NRF24RX_H8_3D,
|
||||
NRF24RX_INAV,
|
||||
NRF24RX_PROTOCOL_COUNT
|
||||
} nrf24_protocol_t;
|
||||
} rx_spi_protocol_e;
|
||||
|
||||
typedef enum {
|
||||
NRF24_RECEIVED_NONE = 0,
|
||||
NRF24_RECEIVED_BIND,
|
||||
NRF24_RECEIVED_DATA
|
||||
} nrf24_received_t;
|
||||
RX_SPI_RECEIVED_NONE = 0,
|
||||
RX_SPI_RECEIVED_BIND,
|
||||
RX_SPI_RECEIVED_DATA
|
||||
} rx_spi_received_e;
|
||||
|
||||
// RC channels in AETR order
|
||||
typedef enum {
|
||||
NRF24_ROLL = 0,
|
||||
NRF24_PITCH,
|
||||
NRF24_THROTTLE,
|
||||
NRF24_YAW,
|
||||
NRF24_AUX1,
|
||||
NRF24_AUX2,
|
||||
NRF24_AUX3,
|
||||
NRF24_AUX4,
|
||||
NRF24_AUX5,
|
||||
NRF24_AUX6,
|
||||
NRF24_AUX7,
|
||||
NRF24_AUX8,
|
||||
NRF24_AUX9,
|
||||
NRF24_AUX10,
|
||||
NRF24_AUX11,
|
||||
NRF24_AUX12,
|
||||
NRF24_AUX13,
|
||||
NRF24_AUX14
|
||||
} nrf24_AETR_t;
|
||||
RC_SPI_ROLL = 0,
|
||||
RC_SPI_PITCH,
|
||||
RC_SPI_THROTTLE,
|
||||
RC_SPI_YAW,
|
||||
RC_SPI_AUX1,
|
||||
RC_SPI_AUX2,
|
||||
RC_SPI_AUX3,
|
||||
RC_SPI_AUX4,
|
||||
RC_SPI_AUX5,
|
||||
RC_SPI_AUX6,
|
||||
RC_SPI_AUX7,
|
||||
RC_SPI_AUX8,
|
||||
RC_SPI_AUX9,
|
||||
RC_SPI_AUX10,
|
||||
RC_SPI_AUX11,
|
||||
RC_SPI_AUX12,
|
||||
RC_SPI_AUX13,
|
||||
RC_SPI_AUX14
|
||||
} rc_spi_aetr_e;
|
||||
|
||||
// RC channels as used by deviation
|
||||
#define RC_CHANNEL_RATE NRF24_AUX1
|
||||
#define RC_CHANNEL_FLIP NRF24_AUX2
|
||||
#define RC_CHANNEL_PICTURE NRF24_AUX3
|
||||
#define RC_CHANNEL_VIDEO NRF24_AUX4
|
||||
#define RC_CHANNEL_HEADLESS NRF24_AUX5
|
||||
#define RC_CHANNEL_RTH NRF24_AUX6 // return to home
|
||||
#define RC_CHANNEL_RATE RC_SPI_AUX1
|
||||
#define RC_CHANNEL_FLIP RC_SPI_AUX2
|
||||
#define RC_CHANNEL_PICTURE RC_SPI_AUX3
|
||||
#define RC_CHANNEL_VIDEO RC_SPI_AUX4
|
||||
#define RC_CHANNEL_HEADLESS RC_SPI_AUX5
|
||||
#define RC_CHANNEL_RTH RC_SPI_AUX6 // return to home
|
||||
|
||||
bool rxNrf24DataReceived(void);
|
||||
bool rxSpiDataReceived(void);
|
||||
struct rxConfig_s;
|
||||
struct rxRuntimeConfig_s;
|
||||
bool rxNrf24Init(nfr24l01_spi_type_e spiType, const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
||||
bool rxSpiInit(rx_spi_type_e spiType, const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig, rcReadRawDataPtr *callback);
|
|
@ -79,19 +79,20 @@
|
|||
#endif
|
||||
|
||||
#ifdef USE_RX_NRF24
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
|
||||
#define USE_RX_SPI
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
|
||||
#define DEFAULT_FEATURES FEATURE_SOFTSPI
|
||||
#define USE_RX_SYMA
|
||||
//#define USE_RX_V202
|
||||
#define USE_RX_CX10
|
||||
//#define USE_RX_H8_3D
|
||||
#define USE_RX_INAV
|
||||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
||||
#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
||||
|
||||
#define USE_SOFTSPI
|
||||
#define USE_NRF24_SOFTSPI
|
||||
#define USE_RX_SOFTSPI
|
||||
|
||||
// RC pinouts
|
||||
// RC1 GND
|
||||
|
@ -104,14 +105,14 @@
|
|||
// RC8 PA1/TIM2 CE / RX_PPM
|
||||
|
||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
#define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CSN_PIN PA0
|
||||
#define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CE_PIN PA1
|
||||
#define NRF24_CSN_PIN PA0
|
||||
#define NRF24_SCK_PIN PB5
|
||||
#define NRF24_MOSI_PIN PB1
|
||||
#define NRF24_MISO_PIN PB0
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA0
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_CE_PIN PA1
|
||||
#define RX_NSS_PIN PA0
|
||||
#define RX_SCK_PIN PB5
|
||||
#define RX_MOSI_PIN PB1
|
||||
#define RX_MISO_PIN PB0
|
||||
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
|
|
|
@ -48,42 +48,42 @@
|
|||
#define USE_RX_NRF24
|
||||
#ifdef USE_RX_NRF24
|
||||
|
||||
#define NRF24_SPI_INSTANCE SPI1
|
||||
#define USE_NRF24_SPI1
|
||||
#define USE_RX_SPI
|
||||
#define RX_SPI_INSTANCE SPI1
|
||||
|
||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
#define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CE_PIN PA4
|
||||
#define NRF24_CSN_PIN PA11
|
||||
#define NRF24_SCK_PIN PA5
|
||||
#define NRF24_MISO_PIN PA6
|
||||
#define NRF24_MOSI_PIN PA7
|
||||
#define NRF24_IRQ_PIN PA8
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_CE_PIN PA4
|
||||
#define RX_NSS_PIN PA11
|
||||
#define RX_SCK_PIN PA5
|
||||
#define RX_MISO_PIN PA6
|
||||
#define RX_MOSI_PIN PA7
|
||||
#define RX_IRQ_PIN PA8
|
||||
// CJMCU has NSS on PA11, rather than the standard PA4
|
||||
#define SPI1_NSS_PIN NRF24_CSN_PIN
|
||||
#define SPI1_SCK_PIN NRF24_SCK_PIN
|
||||
#define SPI1_MISO_PIN NRF24_MISO_PIN
|
||||
#define SPI1_MOSI_PIN NRF24_MOSI_PIN
|
||||
#define SPI1_NSS_PIN RX_NSS_PIN
|
||||
#define SPI1_SCK_PIN RX_SCK_PIN
|
||||
#define SPI1_MISO_PIN RX_MISO_PIN
|
||||
#define SPI1_MOSI_PIN RX_MOSI_PIN
|
||||
|
||||
#define USE_RX_NRF24
|
||||
#define USE_RX_CX10
|
||||
//#define USE_RX_H8_3D
|
||||
#define USE_RX_H8_3D
|
||||
#define USE_RX_INAV
|
||||
#define USE_RX_SYMA
|
||||
//#define USE_RX_V202
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
||||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_INAV
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_CX10A
|
||||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
#define USE_RX_V202
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
|
||||
#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_INAV
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_H8_3D
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_CX10A
|
||||
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
|
||||
#define TELEMETRY
|
||||
#define TELEMETRY_LTM
|
||||
#define TELEMETRY_NRF24_LTM
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
|
||||
//#define TELEMETRY
|
||||
//#define TELEMETRY_LTM
|
||||
//#define TELEMETRY_NRF24_LTM
|
||||
#define SKIP_RX_PWM_PPM
|
||||
#undef SERIAL_RX
|
||||
//#undef SKIP_TASK_STATISTICS
|
||||
|
|
|
@ -46,7 +46,11 @@
|
|||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_NRF24
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define USE_RX_SPI
|
||||
#define RX_SPI_INSTANCE SPI1
|
||||
#define USE_RX_NRF24
|
||||
//#define USE_RX_CX10
|
||||
//#define USE_RX_H8_3D
|
||||
|
@ -54,19 +58,14 @@
|
|||
#define USE_RX_V202
|
||||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
||||
#define NRF24_SPI_INSTANCE SPI1
|
||||
#define USE_NRF24_SPI1
|
||||
|
||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
#define NRF24_CE_PIN PA12
|
||||
#define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CSN_PIN PA4
|
||||
#define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_IRQ_PIN PA15
|
||||
#define NRF24_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_CE_PIN PA12
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA4
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_IRQ_PIN PA15
|
||||
#define RX_IRQ_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
|
||||
#define SKIP_RX_MSP
|
||||
#define SKIP_INFLIGHT_ADJUSTMENTS
|
||||
|
@ -74,6 +73,8 @@
|
|||
#undef SERIAL_RX
|
||||
#undef BLACKBOX
|
||||
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
|
||||
|
||||
// Since the CrazePony MINI PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
|
||||
#undef USE_SERVOS
|
||||
#define USE_QUAD_MIXER_ONLY
|
||||
|
|
|
@ -138,6 +138,7 @@
|
|||
|
||||
//#define USE_RX_NRF24
|
||||
#ifdef USE_RX_NRF24
|
||||
#define USE_RX_SPI
|
||||
|
||||
#define USE_RX_CX10
|
||||
#define USE_RX_H8_3D
|
||||
|
@ -151,7 +152,8 @@
|
|||
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
|
||||
#define USE_SOFTSPI
|
||||
#define USE_NRF24_SOFTSPI
|
||||
#define USE_RX_SOFTSPI
|
||||
|
||||
// RC pinouts
|
||||
// RC1 GND
|
||||
// RC2 power
|
||||
|
@ -165,13 +167,13 @@
|
|||
// RC10 PB1/TIM3 MOSI /softserial2 TX / sonar echo / current
|
||||
|
||||
// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
|
||||
#define NRF24_CE_PIN PA1
|
||||
#define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CSN_PIN PA6
|
||||
#define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_SCK_PIN PA7
|
||||
#define NRF24_MOSI_PIN PB1
|
||||
#define NRF24_MISO_PIN PB0
|
||||
#define RX_CE_PIN PA1
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA6
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_SCK_PIN PA7
|
||||
#define RX_MOSI_PIN PB1
|
||||
#define RX_MISO_PIN PB0
|
||||
#endif // USE_NRF24
|
||||
|
||||
#define USE_ADC
|
||||
|
|
|
@ -103,11 +103,11 @@
|
|||
#define USE_RX_INAV
|
||||
#define USE_RX_SYMA
|
||||
#define USE_RX_V202
|
||||
#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
#define NRF24_CSN_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CSN_PIN PA0
|
||||
#define NRF24_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define NRF24_CE_PIN PA1
|
||||
#define RX_DEFAULT_PROTOCOL NRF24RX_V202_1M
|
||||
#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_NSS_PIN PA0
|
||||
#define RX_CE_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOA
|
||||
#define RX_CE_PIN PA1
|
||||
|
||||
#define USE_I2C
|
||||
#define I2C_DEVICE (I2CDEV_1)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue