1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

Split off xn297 code.

This commit is contained in:
Martin Budden 2016-05-25 10:41:31 +01:00
parent 430924fb63
commit 04205e2cda
8 changed files with 134 additions and 106 deletions

View file

@ -427,6 +427,11 @@ COMMON_SRC = \
io/statusindicator.c \ io/statusindicator.c \
rx/ibus.c \ rx/ibus.c \
rx/msp.c \ rx/msp.c \
rx/nrf24.c \
rx/nrf24_cx10.c \
rx/nrf24_syma.c \
rx/nrf24_v202.c \
rx/nrf24_h8_3d.c \
rx/pwm.c \ rx/pwm.c \
rx/rx.c \ rx/rx.c \
rx/sbus.c \ rx/sbus.c \

View file

@ -439,3 +439,17 @@ void sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu
result[i] = sqrtf(beta[i]); result[i] = sqrtf(beta[i]);
} }
} }
uint16_t crc16_ccitt(uint16_t crc, unsigned char a)
{
crc ^= a << 8;
for (int ii = 0; ii < 8; ++ii) {
if (crc & 0x8000) {
crc = (crc << 1) ^ 0x1021;
} else {
crc = crc << 1;
}
}
return crc;
}

View file

@ -168,3 +168,4 @@ float acos_approx(float x);
#endif #endif
void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count); void arraySubInt32(int32_t *dest, int32_t *array1, int32_t *array2, int count);
uint16_t crc16_ccitt(uint16_t crc, unsigned char a);

View file

@ -0,0 +1,77 @@
/*
* 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 borrows heavily from project Deviation,
// see http://deviationtx.com
#include <stdbool.h>
#include <stdint.h>
#include "drivers/rx_nrf24l01.h"
#include "common/maths.h"
static const uint8_t xn297_data_scramble[30] = {
0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12,
0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b,
0x79, 0xca, 0xcc, 0x1b, 0x5d, 0x19, 0x10, 0x24,
0xd3, 0xdc, 0x3f, 0x8e, 0xc5, 0x2f
};
static uint8_t bitReverse(uint8_t bIn)
{
uint8_t bOut = 0;
for (int ii = 0; ii < 8; ++ii) {
bOut = (bOut << 1) | (bIn & 1);
bIn >>= 1;
}
return bOut;
}
void XN297_UnscramblePayload(uint8_t* data, int len)
{
for (uint8_t ii = 0; ii < len; ++ii) {
data[ii] = bitReverse(data[ii] ^ xn297_data_scramble[ii]);
}
}
#define RX_TX_ADDR_LEN 5
#define PROTOCOL_PAYLOAD_SIZE_15 15
#define PROTOCOL_PAYLOAD_SIZE_19 19
uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr)
{
uint8_t packet[NRF24L01_MAX_PAYLOAD_SIZE];
uint16_t crc = 0xb5d2;
for (int ii = 0; ii < RX_TX_ADDR_LEN; ++ii) {
packet[ii] = rxAddr[RX_TX_ADDR_LEN - 1 - ii];
crc = crc16_ccitt(crc, packet[ii]);
}
for (int ii = 0; ii < len; ++ii) {
// bit-reverse bytes in packet
const uint8_t bOut = bitReverse(data[ii]);
packet[ii + RX_TX_ADDR_LEN] = bOut ^ xn297_data_scramble[ii];
crc = crc16_ccitt(crc, packet[ii + RX_TX_ADDR_LEN]);
}
const uint16_t crcXor = (len == PROTOCOL_PAYLOAD_SIZE_15) ? 0x9BA7 : 0x61B1;
crc ^= crcXor;
packet[RX_TX_ADDR_LEN + len] = crc >> 8;
packet[RX_TX_ADDR_LEN + len + 1] = crc & 0xff;
return NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2);
}

View file

@ -0,0 +1,25 @@
/*
* 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 <stdbool.h>
#include <stdint.h>
void XN297_UnscramblePayload(uint8_t* data, int len);
uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr);

View file

@ -28,6 +28,7 @@
#ifdef USE_RX_CX10 #ifdef USE_RX_CX10
#include "drivers/rx_nrf24l01.h" #include "drivers/rx_nrf24l01.h"
#include "drivers/rx_xn297.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "rx/nrf24.h" #include "rx/nrf24.h"
@ -68,10 +69,6 @@
#define FLAG_VIDEO 0x02 #define FLAG_VIDEO 0x02
#define FLAG_PICTURE 0x04 #define FLAG_PICTURE 0x04
// XN297 emulation layer
STATIC_UNIT_TESTED uint8_t XN297_WritePayload(uint8_t* data, int len);
STATIC_UNIT_TESTED void XN297_UnscramblePayload(uint8_t* data, int len);
static nrf24_protocol_t cx10Protocol; static nrf24_protocol_t cx10Protocol;
typedef enum { typedef enum {
@ -227,7 +224,7 @@ nrf24_received_t cx10DataReceived(uint8_t *payload)
payload[9] = 0x01; payload[9] = 0x01;
NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL); NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL);
NRF24L01_FlushTx(); NRF24L01_FlushTx();
XN297_WritePayload(payload, payloadSize); XN297_WritePayload(payload, payloadSize, rxAddr);
NRF24L01_SetTxMode();// enter transmit mode to send the packet NRF24L01_SetTxMode();// enter transmit mode to send the packet
// wait for the ACK packet to send before changing channel // wait for the ACK packet to send before changing channel
static const int fifoDelayUs = 100; static const int fifoDelayUs = 100;
@ -238,7 +235,7 @@ nrf24_received_t cx10DataReceived(uint8_t *payload)
// send out an ACK on each of the hopping channels, required by CX10 transmitter // send out an ACK on each of the hopping channels, required by CX10 transmitter
for (uint8_t ii = 0; ii < RF_CHANNEL_COUNT; ++ii) { for (uint8_t ii = 0; ii < RF_CHANNEL_COUNT; ++ii) {
NRF24L01_SetChannel(cx10RfChannels[ii]); NRF24L01_SetChannel(cx10RfChannels[ii]);
XN297_WritePayload(payload, payloadSize); XN297_WritePayload(payload, payloadSize, rxAddr);
NRF24L01_SetTxMode();// enter transmit mode to send the packet NRF24L01_SetTxMode();// enter transmit mode to send the packet
// wait for the ACK packet to send before changing channel // wait for the ACK packet to send before changing channel
while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) { while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
@ -279,70 +276,5 @@ void cx10Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
rxRuntimeConfig->channelCount = CX10_RC_CHANNEL_COUNT; rxRuntimeConfig->channelCount = CX10_RC_CHANNEL_COUNT;
cx10Nrf24Init((nrf24_protocol_t)rxConfig->nrf24rx_protocol); cx10Nrf24Init((nrf24_protocol_t)rxConfig->nrf24rx_protocol);
} }
// XN297 emulation layer
static const uint8_t xn297_data_scramble[30] = {
0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12,
0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b,
0x79, 0xca, 0xcc, 0x1b, 0x5d, 0x19, 0x10, 0x24,
0xd3, 0xdc, 0x3f, 0x8e, 0xc5, 0x2f
};
static uint8_t bitReverse(uint8_t bIn)
{
uint8_t bOut = 0;
for (int ii = 0; ii < 8; ++ii) {
bOut = (bOut << 1) | (bIn & 1);
bIn >>= 1;
}
return bOut;
}
static uint16_t crc16_update(uint16_t crc, unsigned char a)
{
static const uint16_t crcPolynomial = 0x1021;
crc ^= a << 8;
for (int ii = 0; ii < 8; ++ii) {
if (crc & 0x8000) {
crc = (crc << 1) ^ crcPolynomial;
} else {
crc = crc << 1;
}
}
return crc;
}
STATIC_UNIT_TESTED uint8_t XN297_WritePayload(uint8_t* data, int len)
{
uint8_t packet[NRF24L01_MAX_PAYLOAD_SIZE];
uint16_t crc = 0xb5d2;
for (int ii = 0; ii < RX_TX_ADDR_LEN; ++ii) {
packet[ii] = rxAddr[RX_TX_ADDR_LEN - 1 - ii];
crc = crc16_update(crc, packet[ii]);
}
for (int ii = 0; ii < len; ++ii) {
// bit-reverse bytes in packet
const uint8_t bOut = bitReverse(data[ii]);
packet[ii + RX_TX_ADDR_LEN] = bOut ^ xn297_data_scramble[ii];
crc = crc16_update(crc, packet[ii + RX_TX_ADDR_LEN]);
}
const uint16_t crcXor = (len == CX10_PROTOCOL_PAYLOAD_SIZE) ? 0x9BA7 : 0x61B1;
crc ^= crcXor;
packet[RX_TX_ADDR_LEN + len] = crc >> 8;
packet[RX_TX_ADDR_LEN + len + 1] = crc & 0xff;
return NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2);
}
STATIC_UNIT_TESTED void XN297_UnscramblePayload(uint8_t* data, int len)
{
for (uint8_t ii = 0; ii < len; ++ii) {
data[ii] = bitReverse(data[ii] ^ xn297_data_scramble[ii]);
}
}
// End of XN297 emulation
#endif #endif

View file

@ -28,6 +28,7 @@
#ifdef USE_RX_H8_3D #ifdef USE_RX_H8_3D
#include "drivers/rx_nrf24l01.h" #include "drivers/rx_nrf24l01.h"
#include "drivers/rx_xn297.h"
#include "drivers/system.h" #include "drivers/system.h"
#include "rx/nrf24.h" #include "rx/nrf24.h"
@ -71,9 +72,6 @@
#define FLAG_CAMERA_UP 0x04 // on payload[18] #define FLAG_CAMERA_UP 0x04 // on payload[18]
#define FLAG_CAMERA_DOWN 0x08 // on payload[18] #define FLAG_CAMERA_DOWN 0x08 // on payload[18]
// XN297 emulation layer
static void XN297_UnscramblePayload(uint8_t* data, int len);
typedef enum { typedef enum {
STATE_BIND = 0, STATE_BIND = 0,
STATE_DATA STATE_DATA
@ -101,7 +99,7 @@ STATIC_UNIT_TESTED uint8_t h8_3dRfChannels[H8_3D_RF_CHANNEL_COUNT];
static uint32_t hopTimeout = BIND_HOP_TIMEOUT; static uint32_t hopTimeout = BIND_HOP_TIMEOUT;
static uint32_t timeOfLastHop; static uint32_t timeOfLastHop;
void setBound(const uint8_t* txId); void h8_3dSetBound(const uint8_t* txId);
void h8_3dNrf24Init(nrf24_protocol_t protocol, const uint8_t* nrf24_id) void h8_3dNrf24Init(nrf24_protocol_t protocol, const uint8_t* nrf24_id)
{ {
@ -120,7 +118,7 @@ void h8_3dNrf24Init(nrf24_protocol_t protocol, const uint8_t* nrf24_id)
h8_3dRfChannelIndex = H8_3D_RF_BIND_CHANNEL_START; h8_3dRfChannelIndex = H8_3D_RF_BIND_CHANNEL_START;
NRF24L01_SetChannel(H8_3D_RF_BIND_CHANNEL_START); NRF24L01_SetChannel(H8_3D_RF_BIND_CHANNEL_START);
} else { } else {
setBound(nrf24_id); h8_3dSetBound(nrf24_id);
} }
NRF24L01_WriteReg(NRF24L01_08_OBSERVE_TX, 0x00); NRF24L01_WriteReg(NRF24L01_08_OBSERVE_TX, 0x00);
@ -206,7 +204,7 @@ static void hopToNextChannel(void)
} }
// The hopping channels are determined by the txId // The hopping channels are determined by the txId
void setHoppingChannels(const uint8_t* txId) void h8_3dSetHoppingChannels(const uint8_t* txId)
{ {
h8_3dRfChannels[0] = 0x06 + ((txId[0]>>4) +(txId[0] & 0x0f)) % 0x0f; h8_3dRfChannels[0] = 0x06 + ((txId[0]>>4) +(txId[0] & 0x0f)) % 0x0f;
h8_3dRfChannels[1] = 0x15 + ((txId[1]>>4) +(txId[1] & 0x0f)) % 0x0f; h8_3dRfChannels[1] = 0x15 + ((txId[1]>>4) +(txId[1] & 0x0f)) % 0x0f;
@ -217,9 +215,9 @@ void setHoppingChannels(const uint8_t* txId)
h8_3dRfChannels[3] = 0x15 + ((txId[1]>>8) +(txId[1] & 0x0f)) % 0x0f; h8_3dRfChannels[3] = 0x15 + ((txId[1]>>8) +(txId[1] & 0x0f)) % 0x0f;
} }
void setBound(const uint8_t* txId) void h8_3dSetBound(const uint8_t* txId)
{ {
setHoppingChannels(txId); h8_3dSetHoppingChannels(txId);
protocolState = STATE_DATA; protocolState = STATE_DATA;
hopTimeout = DATA_HOP_TIMEOUT; hopTimeout = DATA_HOP_TIMEOUT;
h8_3dRfChannelIndex = 0; h8_3dRfChannelIndex = 0;
@ -244,7 +242,7 @@ nrf24_received_t h8_3dDataReceived(uint8_t *payload)
const bool bindPacket = h8_3dCheckBindPacket(payload); const bool bindPacket = h8_3dCheckBindPacket(payload);
if (bindPacket) { if (bindPacket) {
ret = NRF24_RECEIVED_BIND; ret = NRF24_RECEIVED_BIND;
setBound(txId); h8_3dSetBound(txId);
} }
} }
break; break;
@ -266,28 +264,4 @@ void h8_3dInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
rxRuntimeConfig->channelCount = H8_3D_RC_CHANNEL_COUNT; rxRuntimeConfig->channelCount = H8_3D_RC_CHANNEL_COUNT;
h8_3dNrf24Init((nrf24_protocol_t)rxConfig->nrf24rx_protocol, rxConfig->nrf24rx_id); h8_3dNrf24Init((nrf24_protocol_t)rxConfig->nrf24rx_protocol, rxConfig->nrf24rx_id);
} }
static const uint8_t xn297_data_scramble[30] = {
0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12,
0x69, 0xee, 0x1f, 0xc7, 0x62, 0x97, 0xd5, 0x0b,
0x79, 0xca, 0xcc, 0x1b, 0x5d, 0x19, 0x10, 0x24,
0xd3, 0xdc, 0x3f, 0x8e, 0xc5, 0x2f
};
static uint8_t bitReverse(uint8_t bIn)
{
uint8_t bOut = 0;
for (int ii = 0; ii < 8; ++ii) {
bOut = (bOut << 1) | (bIn & 1);
bIn >>= 1;
}
return bOut;
}
static void XN297_UnscramblePayload(uint8_t* data, int len)
{
for (uint8_t ii = 0; ii < len; ++ii) {
data[ii] = bitReverse(data[ii] ^ xn297_data_scramble[ii]);
}
}
#endif #endif

View file

@ -104,9 +104,9 @@
#define USE_RX_CX10 #define USE_RX_CX10
#define USE_RX_H8_3D #define USE_RX_H8_3D
#endif #endif
#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C //#define NRF24_DEFAULT_PROTOCOL NRF24RX_SYMA_X5C
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M //#define NRF24_DEFAULT_PROTOCOL NRF24RX_V202_1M
//#define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D #define NRF24_DEFAULT_PROTOCOL NRF24RX_H8_3D
#define USE_SOFTSPI #define USE_SOFTSPI
#define USE_NRF24_SOFTSPI #define USE_NRF24_SOFTSPI