Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / rx / nrf24_cx10.c
blob4b8a24393e083b1a2719a5a9690eb8f861eaa8d6
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 // This file borrows heavily from project Deviation,
22 // see http://deviationtx.com
24 #include <stdbool.h>
25 #include <stdint.h>
26 #include <string.h>
28 #include "platform.h"
30 #ifdef USE_RX_CX10
32 #include "build/build_config.h"
34 #include "pg/rx.h"
36 #include "drivers/io.h"
37 #include "drivers/rx/rx_nrf24l01.h"
38 #include "drivers/rx/rx_xn297.h"
39 #include "drivers/time.h"
41 #include "rx/rx.h"
42 #include "rx/rx_spi.h"
43 #include "rx/nrf24_cx10.h"
46 * Deviation transmitter
47 * Bind phase lasts 6 seconds for CX10, for CX10A it lasts until an acknowledgment is received.
48 * Other transmitters may vary but should have similar characteristics.
49 * For CX10A protocol: after receiving a bind packet, the receiver must send back a data packet with byte[9] = 1 as acknowledgment
53 * CX10 Protocol
54 * No auto acknowledgment
55 * Payload size is 19 and static for CX10A variant, 15 and static for CX10 variant.
56 * Data rate is 1Mbps
57 * Bind Phase
58 * uses address {0xcc, 0xcc, 0xcc, 0xcc, 0xcc}, converted by XN297
59 * uses channel 0x02
60 * Data phase
61 * uses same address as bind phase
62 * hops between 4 channels that are set from the txId sent in the bind packet
65 #define RC_CHANNEL_COUNT 9
67 enum {
68 RATE_LOW = 0,
69 RATE_MID = 1,
70 RATE_HIGH= 2
73 #define FLAG_FLIP 0x10 // goes to rudder channel
74 // flags1
75 #define FLAG_MODE_MASK 0x03
76 #define FLAG_HEADLESS 0x04
77 // flags2
78 #define FLAG_VIDEO 0x02
79 #define FLAG_PICTURE 0x04
81 static rx_spi_protocol_e cx10Protocol;
83 typedef enum {
84 STATE_BIND = 0,
85 STATE_ACK,
86 STATE_DATA
87 } protocol_state_t;
89 STATIC_UNIT_TESTED protocol_state_t protocolState;
91 #define CX10_PROTOCOL_PAYLOAD_SIZE 15
92 #define CX10A_PROTOCOL_PAYLOAD_SIZE 19
93 static uint8_t payloadSize;
94 #define ACK_TO_SEND_COUNT 8
96 #define CRC_LEN 2
97 #define RX_TX_ADDR_LEN 5
98 STATIC_UNIT_TESTED uint8_t txAddr[RX_TX_ADDR_LEN] = {0x55, 0x0F, 0x71, 0x0C, 0x00}; // converted XN297 address, 0xC710F55 (28 bit)
99 STATIC_UNIT_TESTED uint8_t rxAddr[RX_TX_ADDR_LEN] = {0x49, 0x26, 0x87, 0x7d, 0x2f}; // converted XN297 address
100 #define TX_ID_LEN 4
101 STATIC_UNIT_TESTED uint8_t txId[TX_ID_LEN];
103 #define CX10_RF_BIND_CHANNEL 0x02
104 #define RF_CHANNEL_COUNT 4
105 STATIC_UNIT_TESTED uint8_t cx10RfChannelIndex = 0;
106 STATIC_UNIT_TESTED uint8_t cx10RfChannels[RF_CHANNEL_COUNT]; // channels are set using txId from bind packet
108 #define CX10_PROTOCOL_HOP_TIMEOUT 1500 // 1.5ms
109 #define CX10A_PROTOCOL_HOP_TIMEOUT 6500 // 6.5ms
110 static uint32_t hopTimeout;
111 static uint32_t timeOfLastHop;
114 * Returns true if it is a bind packet.
116 STATIC_UNIT_TESTED bool cx10CheckBindPacket(const uint8_t *packet)
118 const bool bindPacket = (packet[0] == 0xaa); // 10101010
119 if (bindPacket) {
120 txId[0] = packet[1];
121 txId[1] = packet[2];
122 txId[2] = packet[3];
123 txId[3] = packet[4];
124 return true;
126 return false;
129 STATIC_UNIT_TESTED uint16_t cx10ConvertToPwmUnsigned(const uint8_t *pVal)
131 uint16_t ret = (*(pVal + 1)) & 0x7f; // mask out top bit which is used for a flag for the rudder
132 ret = (ret << 8) | *pVal;
133 return ret;
136 void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
138 const uint8_t offset = (cx10Protocol == RX_SPI_NRF24_CX10) ? 0 : 4;
139 rcData[RC_SPI_ROLL] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[5 + offset]); // aileron
140 rcData[RC_SPI_PITCH] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[7 + offset]); // elevator
141 rcData[RC_SPI_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle
142 rcData[RC_SPI_YAW] = cx10ConvertToPwmUnsigned(&payload[11 + offset]); // rudder
143 const uint8_t flags1 = payload[13 + offset];
144 const uint8_t rate = flags1 & FLAG_MODE_MASK; // takes values 0, 1, 2
145 if (rate == RATE_LOW) {
146 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MIN;
147 } else if (rate == RATE_MID) {
148 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MIDDLE;
149 } else {
150 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MAX;
152 // flip flag is in YAW byte
153 rcData[RC_CHANNEL_FLIP] = payload[12 + offset] & FLAG_FLIP ? PWM_RANGE_MAX : PWM_RANGE_MIN;
154 const uint8_t flags2 = payload[14 + offset];
155 rcData[RC_CHANNEL_PICTURE] = flags2 & FLAG_PICTURE ? PWM_RANGE_MAX : PWM_RANGE_MIN;
156 rcData[RC_CHANNEL_VIDEO] = flags2 & FLAG_VIDEO ? PWM_RANGE_MAX : PWM_RANGE_MIN;
157 rcData[RC_CHANNEL_HEADLESS] = flags1 & FLAG_HEADLESS ? PWM_RANGE_MAX : PWM_RANGE_MIN;
160 static void cx10HopToNextChannel(void)
162 ++cx10RfChannelIndex;
163 if (cx10RfChannelIndex >= RF_CHANNEL_COUNT) {
164 cx10RfChannelIndex = 0;
166 NRF24L01_SetChannel(cx10RfChannels[cx10RfChannelIndex]);
169 // The hopping channels are determined by the txId
170 STATIC_UNIT_TESTED void cx10SetHoppingChannels(const uint8_t *txId)
172 cx10RfChannelIndex = 0;
173 cx10RfChannels[0] = 0x03 + (txId[0] & 0x0F);
174 cx10RfChannels[1] = 0x16 + (txId[0] >> 4);
175 cx10RfChannels[2] = 0x2D + (txId[1] & 0x0F);
176 cx10RfChannels[3] = 0x40 + (txId[1] >> 4);
179 static bool cx10CrcOK(uint16_t crc, const uint8_t *payload)
181 if (payload[payloadSize] != (crc >> 8)) {
182 return false;
184 if (payload[payloadSize + 1] != (crc & 0xff)) {
185 return false;
187 return true;
190 static bool cx10ReadPayloadIfAvailable(uint8_t *payload)
192 if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize + CRC_LEN)) {
193 const uint16_t crc = XN297_UnscramblePayload(payload, payloadSize, rxAddr);
194 if (cx10CrcOK(crc, payload)) {
195 return true;
198 return false;
202 * This is called periodically by the scheduler.
203 * Returns RX_SPI_RECEIVED_DATA if a data packet was received.
205 rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
207 static uint8_t ackCount;
208 rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
209 int totalDelayUs;
210 uint32_t timeNowUs;
212 switch (protocolState) {
213 case STATE_BIND:
214 if (cx10ReadPayloadIfAvailable(payload)) {
215 const bool bindPacket = cx10CheckBindPacket(payload);
216 if (bindPacket) {
217 // set the hopping channels as determined by the txId received in the bind packet
218 cx10SetHoppingChannels(txId);
219 ret = RX_SPI_RECEIVED_BIND;
220 protocolState = STATE_ACK;
221 ackCount = 0;
224 break;
225 case STATE_ACK:
226 // transmit an ACK packet
227 ++ackCount;
228 totalDelayUs = 0;
229 // send out an ACK on the bind channel, required by deviationTx
230 payload[9] = 0x01;
231 NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL);
232 NRF24L01_FlushTx();
233 XN297_WritePayload(payload, payloadSize, rxAddr);
234 NRF24L01_SetTxMode();// enter transmit mode to send the packet
235 // wait for the ACK packet to send before changing channel
236 static const int fifoDelayUs = 100;
237 while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BIT(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
238 delayMicroseconds(fifoDelayUs);
239 totalDelayUs += fifoDelayUs;
241 // send out an ACK on each of the hopping channels, required by CX10 transmitter
242 for (int ii = 0; ii < RF_CHANNEL_COUNT; ++ii) {
243 NRF24L01_SetChannel(cx10RfChannels[ii]);
244 XN297_WritePayload(payload, payloadSize, rxAddr);
245 NRF24L01_SetTxMode();// enter transmit mode to send the packet
246 // wait for the ACK packet to send before changing channel
247 while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BIT(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
248 delayMicroseconds(fifoDelayUs);
249 totalDelayUs += fifoDelayUs;
252 static const int delayBetweenPacketsUs = 1000;
253 if (totalDelayUs < delayBetweenPacketsUs) {
254 delayMicroseconds(delayBetweenPacketsUs - totalDelayUs);
256 NRF24L01_SetRxMode();//reenter receive mode after sending ACKs
257 if (ackCount > ACK_TO_SEND_COUNT) {
258 NRF24L01_SetChannel(cx10RfChannels[0]);
259 // and go into data state to wait for first data packet
260 protocolState = STATE_DATA;
262 break;
263 case STATE_DATA:
264 timeNowUs = micros();
265 // read the payload, processing of payload is deferred
266 if (cx10ReadPayloadIfAvailable(payload)) {
267 cx10HopToNextChannel();
268 timeOfLastHop = timeNowUs;
269 ret = RX_SPI_RECEIVED_DATA;
271 if (timeNowUs > timeOfLastHop + hopTimeout) {
272 cx10HopToNextChannel();
273 timeOfLastHop = timeNowUs;
276 return ret;
279 static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
281 cx10Protocol = protocol;
282 protocolState = STATE_BIND;
283 payloadSize = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_PAYLOAD_SIZE : CX10A_PROTOCOL_PAYLOAD_SIZE;
284 hopTimeout = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_HOP_TIMEOUT : CX10A_PROTOCOL_HOP_TIMEOUT;
286 NRF24L01_Initialize(0); // sets PWR_UP, no CRC
287 NRF24L01_SetupBasic();
289 NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL);
291 NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
292 // RX_ADDR for pipes P2 to P5 are left at default values
293 NRF24L01_FlushRx();
294 NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, txAddr, RX_TX_ADDR_LEN);
295 NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxAddr, RX_TX_ADDR_LEN);
297 NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize + CRC_LEN); // payload + 2 bytes CRC
299 NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
302 bool cx10Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState, rxSpiExtiConfig_t *extiConfig)
304 UNUSED(extiConfig);
306 rxRuntimeState->channelCount = RC_CHANNEL_COUNT;
307 cx10Nrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
309 return true;
311 #endif