1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

Merge pull request #1902 from martinbudden/bf_nrf_tidy

Tidied RX_SPI enums
This commit is contained in:
Martin Budden 2016-12-27 19:34:51 +01:00 committed by GitHub
commit 1771a97d86
7 changed files with 32 additions and 32 deletions

View file

@ -98,7 +98,7 @@ uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
/* /*
* Empty the transmit FIFO buffer. * Empty the transmit FIFO buffer.
*/ */
void NRF24L01_FlushTx() void NRF24L01_FlushTx(void)
{ {
rxSpiWriteByte(FLUSH_TX); rxSpiWriteByte(FLUSH_TX);
} }
@ -106,7 +106,7 @@ void NRF24L01_FlushTx()
/* /*
* Empty the receive FIFO buffer. * Empty the receive FIFO buffer.
*/ */
void NRF24L01_FlushRx() void NRF24L01_FlushRx(void)
{ {
rxSpiWriteByte(FLUSH_RX); rxSpiWriteByte(FLUSH_RX);
} }

View file

@ -129,7 +129,7 @@ STATIC_UNIT_TESTED uint16_t cx10ConvertToPwmUnsigned(const uint8_t *pVal)
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload) void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
{ {
const uint8_t offset = (cx10Protocol == NRF24RX_CX10) ? 0 : 4; const uint8_t offset = (cx10Protocol == RX_SPI_NRF24_CX10) ? 0 : 4;
rcData[RC_SPI_ROLL] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[5 + offset]); // aileron 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_PITCH] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[7 + offset]); // elevator
rcData[RC_SPI_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle rcData[RC_SPI_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle
@ -274,8 +274,8 @@ static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
{ {
cx10Protocol = protocol; cx10Protocol = protocol;
protocolState = STATE_BIND; protocolState = STATE_BIND;
payloadSize = (protocol == NRF24RX_CX10) ? CX10_PROTOCOL_PAYLOAD_SIZE : CX10A_PROTOCOL_PAYLOAD_SIZE; payloadSize = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_PAYLOAD_SIZE : CX10A_PROTOCOL_PAYLOAD_SIZE;
hopTimeout = (protocol == NRF24RX_CX10) ? CX10_PROTOCOL_HOP_TIMEOUT : CX10A_PROTOCOL_HOP_TIMEOUT; hopTimeout = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_HOP_TIMEOUT : CX10A_PROTOCOL_HOP_TIMEOUT;
NRF24L01_Initialize(0); // sets PWR_UP, no CRC NRF24L01_Initialize(0); // sets PWR_UP, no CRC
NRF24L01_SetupBasic(); NRF24L01_SetupBasic();

View file

@ -124,7 +124,7 @@ static uint32_t hopTimeout = 10000; // 10ms
STATIC_UNIT_TESTED bool symaCheckBindPacket(const uint8_t *packet) STATIC_UNIT_TESTED bool symaCheckBindPacket(const uint8_t *packet)
{ {
bool bindPacket = false; bool bindPacket = false;
if (symaProtocol == NRF24RX_SYMA_X) { if (symaProtocol == RX_SPI_NRF24_SYMA_X) {
if ((packet[5] == 0xaa) && (packet[6] == 0xaa) && (packet[7] == 0xaa)) { if ((packet[5] == 0xaa) && (packet[6] == 0xaa) && (packet[7] == 0xaa)) {
bindPacket = true; bindPacket = true;
rxTxAddr[4] = packet[0]; rxTxAddr[4] = packet[0];
@ -162,7 +162,7 @@ void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *packet)
{ {
rcData[RC_SPI_THROTTLE] = symaConvertToPwmUnsigned(packet[0]); // throttle rcData[RC_SPI_THROTTLE] = symaConvertToPwmUnsigned(packet[0]); // throttle
rcData[RC_SPI_ROLL] = symaConvertToPwmSigned(packet[3]); // aileron rcData[RC_SPI_ROLL] = symaConvertToPwmSigned(packet[3]); // aileron
if (symaProtocol == NRF24RX_SYMA_X) { if (symaProtocol == RX_SPI_NRF24_SYMA_X) {
rcData[RC_SPI_PITCH] = symaConvertToPwmSigned(packet[1]); // elevator rcData[RC_SPI_PITCH] = symaConvertToPwmSigned(packet[1]); // elevator
rcData[RC_SPI_YAW] = symaConvertToPwmSigned(packet[2]); // rudder rcData[RC_SPI_YAW] = symaConvertToPwmSigned(packet[2]); // rudder
const uint8_t rate = (packet[5] & 0xc0) >> 6; const uint8_t rate = (packet[5] & 0xc0) >> 6;
@ -271,7 +271,7 @@ static void symaNrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV( NRF24L01_00_CONFIG_CRCO)); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV( NRF24L01_00_CONFIG_CRCO)); // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC
NRF24L01_SetupBasic(); NRF24L01_SetupBasic();
if (symaProtocol == NRF24RX_SYMA_X) { if (symaProtocol == RX_SPI_NRF24_SYMA_X) {
payloadSize = SYMA_X_PROTOCOL_PAYLOAD_SIZE; payloadSize = SYMA_X_PROTOCOL_PAYLOAD_SIZE;
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
protocolState = STATE_BIND; protocolState = STATE_BIND;

View file

@ -230,7 +230,7 @@ static void v202Nrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0 NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0)); // Enable data pipe 0
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xFF); // 4ms retransmit t/o, 15 tries NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0xFF); // 4ms retransmit t/o, 15 tries
if (protocol == NRF24RX_V202_250K) { if (protocol == RX_SPI_NRF24_V202_250K) {
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
} else { } else {
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm); NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);

View file

@ -69,38 +69,38 @@ STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
switch (protocol) { switch (protocol) {
default: default:
#ifdef USE_RX_V202 #ifdef USE_RX_V202
case NRF24RX_V202_250K: case RX_SPI_NRF24_V202_250K:
case NRF24RX_V202_1M: case RX_SPI_NRF24_V202_1M:
protocolInit = v202Nrf24Init; protocolInit = v202Nrf24Init;
protocolDataReceived = v202Nrf24DataReceived; protocolDataReceived = v202Nrf24DataReceived;
protocolSetRcDataFromPayload = v202Nrf24SetRcDataFromPayload; protocolSetRcDataFromPayload = v202Nrf24SetRcDataFromPayload;
break; break;
#endif #endif
#ifdef USE_RX_SYMA #ifdef USE_RX_SYMA
case NRF24RX_SYMA_X: case RX_SPI_NRF24_SYMA_X:
case NRF24RX_SYMA_X5C: case RX_SPI_NRF24_SYMA_X5C:
protocolInit = symaNrf24Init; protocolInit = symaNrf24Init;
protocolDataReceived = symaNrf24DataReceived; protocolDataReceived = symaNrf24DataReceived;
protocolSetRcDataFromPayload = symaNrf24SetRcDataFromPayload; protocolSetRcDataFromPayload = symaNrf24SetRcDataFromPayload;
break; break;
#endif #endif
#ifdef USE_RX_CX10 #ifdef USE_RX_CX10
case NRF24RX_CX10: case RX_SPI_NRF24_CX10:
case NRF24RX_CX10A: case RX_SPI_NRF24_CX10A:
protocolInit = cx10Nrf24Init; protocolInit = cx10Nrf24Init;
protocolDataReceived = cx10Nrf24DataReceived; protocolDataReceived = cx10Nrf24DataReceived;
protocolSetRcDataFromPayload = cx10Nrf24SetRcDataFromPayload; protocolSetRcDataFromPayload = cx10Nrf24SetRcDataFromPayload;
break; break;
#endif #endif
#ifdef USE_RX_H8_3D #ifdef USE_RX_H8_3D
case NRF24RX_H8_3D: case RX_SPI_NRF24_H8_3D:
protocolInit = h8_3dNrf24Init; protocolInit = h8_3dNrf24Init;
protocolDataReceived = h8_3dNrf24DataReceived; protocolDataReceived = h8_3dNrf24DataReceived;
protocolSetRcDataFromPayload = h8_3dNrf24SetRcDataFromPayload; protocolSetRcDataFromPayload = h8_3dNrf24SetRcDataFromPayload;
break; break;
#endif #endif
#ifdef USE_RX_INAV #ifdef USE_RX_INAV
case NRF24RX_INAV: case RX_SPI_NRF24_INAV:
protocolInit = inavNrf24Init; protocolInit = inavNrf24Init;
protocolDataReceived = inavNrf24DataReceived; protocolDataReceived = inavNrf24DataReceived;
protocolSetRcDataFromPayload = inavNrf24SetRcDataFromPayload; protocolSetRcDataFromPayload = inavNrf24SetRcDataFromPayload;

View file

@ -21,15 +21,15 @@
#include <stdint.h> #include <stdint.h>
typedef enum { typedef enum {
NRF24RX_V202_250K = 0, RX_SPI_NRF24_V202_250K = 0,
NRF24RX_V202_1M, RX_SPI_NRF24_V202_1M,
NRF24RX_SYMA_X, RX_SPI_NRF24_SYMA_X,
NRF24RX_SYMA_X5C, RX_SPI_NRF24_SYMA_X5C,
NRF24RX_CX10, RX_SPI_NRF24_CX10,
NRF24RX_CX10A, RX_SPI_NRF24_CX10A,
NRF24RX_H8_3D, RX_SPI_NRF24_H8_3D,
NRF24RX_INAV, RX_SPI_NRF24_INAV,
NRF24RX_PROTOCOL_COUNT RX_SPI_PROTOCOL_COUNT
} rx_spi_protocol_e; } rx_spi_protocol_e;
typedef enum { typedef enum {

View file

@ -81,12 +81,12 @@
#define USE_RX_INAV #define USE_RX_INAV
#define USE_RX_SYMA #define USE_RX_SYMA
#define USE_RX_V202 #define USE_RX_V202
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5 //#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_SYMA_X5
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C //#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_SYMA_X5C
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_INAV //#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_INAV
#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_H8_3D #define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_H8_3D
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_CX10A //#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_CX10A
//#define RX_SPI_DEFAULT_PROTOCOL NRF24RX_V202_1M //#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_V202_1M
#define DEFAULT_RX_FEATURE FEATURE_RX_SPI #define DEFAULT_RX_FEATURE FEATURE_RX_SPI
//#define TELEMETRY //#define TELEMETRY