Removed excess trailing spaces before new lines on licenses.
[betaflight.git] / src / main / rx / nrf24_cx10.c
blob68e8099c93ca30c87fe3d283bc04acbf719f3436
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 "drivers/io.h"
35 #include "drivers/rx/rx_nrf24l01.h"
36 #include "drivers/rx/rx_xn297.h"
37 #include "drivers/time.h"
39 #include "rx/rx.h"
40 #include "rx/rx_spi.h"
41 #include "rx/nrf24_cx10.h"
44 * Deviation transmitter
45 * Bind phase lasts 6 seconds for CX10, for CX10A it lasts until an acknowledgment is received.
46 * Other transmitters may vary but should have similar characteristics.
47 * For CX10A protocol: after receiving a bind packet, the receiver must send back a data packet with byte[9] = 1 as acknowledgment
51 * CX10 Protocol
52 * No auto acknowledgment
53 * Payload size is 19 and static for CX10A variant, 15 and static for CX10 variant.
54 * Data rate is 1Mbps
55 * Bind Phase
56 * uses address {0xcc, 0xcc, 0xcc, 0xcc, 0xcc}, converted by XN297
57 * uses channel 0x02
58 * Data phase
59 * uses same address as bind phase
60 * hops between 4 channels that are set from the txId sent in the bind packet
63 #define RC_CHANNEL_COUNT 9
65 enum {
66 RATE_LOW = 0,
67 RATE_MID = 1,
68 RATE_HIGH= 2
71 #define FLAG_FLIP 0x10 // goes to rudder channel
72 // flags1
73 #define FLAG_MODE_MASK 0x03
74 #define FLAG_HEADLESS 0x04
75 // flags2
76 #define FLAG_VIDEO 0x02
77 #define FLAG_PICTURE 0x04
79 static rx_spi_protocol_e cx10Protocol;
81 typedef enum {
82 STATE_BIND = 0,
83 STATE_ACK,
84 STATE_DATA
85 } protocol_state_t;
87 STATIC_UNIT_TESTED protocol_state_t protocolState;
89 #define CX10_PROTOCOL_PAYLOAD_SIZE 15
90 #define CX10A_PROTOCOL_PAYLOAD_SIZE 19
91 static uint8_t payloadSize;
92 #define ACK_TO_SEND_COUNT 8
94 #define CRC_LEN 2
95 #define RX_TX_ADDR_LEN 5
96 STATIC_UNIT_TESTED uint8_t txAddr[RX_TX_ADDR_LEN] = {0x55, 0x0F, 0x71, 0x0C, 0x00}; // converted XN297 address, 0xC710F55 (28 bit)
97 STATIC_UNIT_TESTED uint8_t rxAddr[RX_TX_ADDR_LEN] = {0x49, 0x26, 0x87, 0x7d, 0x2f}; // converted XN297 address
98 #define TX_ID_LEN 4
99 STATIC_UNIT_TESTED uint8_t txId[TX_ID_LEN];
101 #define CX10_RF_BIND_CHANNEL 0x02
102 #define RF_CHANNEL_COUNT 4
103 STATIC_UNIT_TESTED uint8_t cx10RfChannelIndex = 0;
104 STATIC_UNIT_TESTED uint8_t cx10RfChannels[RF_CHANNEL_COUNT]; // channels are set using txId from bind packet
106 #define CX10_PROTOCOL_HOP_TIMEOUT 1500 // 1.5ms
107 #define CX10A_PROTOCOL_HOP_TIMEOUT 6500 // 6.5ms
108 static uint32_t hopTimeout;
109 static uint32_t timeOfLastHop;
112 * Returns true if it is a bind packet.
114 STATIC_UNIT_TESTED bool cx10CheckBindPacket(const uint8_t *packet)
116 const bool bindPacket = (packet[0] == 0xaa); // 10101010
117 if (bindPacket) {
118 txId[0] = packet[1];
119 txId[1] = packet[2];
120 txId[2] = packet[3];
121 txId[3] = packet[4];
122 return true;
124 return false;
127 STATIC_UNIT_TESTED uint16_t cx10ConvertToPwmUnsigned(const uint8_t *pVal)
129 uint16_t ret = (*(pVal + 1)) & 0x7f; // mask out top bit which is used for a flag for the rudder
130 ret = (ret << 8) | *pVal;
131 return ret;
134 void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
136 const uint8_t offset = (cx10Protocol == RX_SPI_NRF24_CX10) ? 0 : 4;
137 rcData[RC_SPI_ROLL] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[5 + offset]); // aileron
138 rcData[RC_SPI_PITCH] = (PWM_RANGE_MAX + PWM_RANGE_MIN) - cx10ConvertToPwmUnsigned(&payload[7 + offset]); // elevator
139 rcData[RC_SPI_THROTTLE] = cx10ConvertToPwmUnsigned(&payload[9 + offset]); // throttle
140 rcData[RC_SPI_YAW] = cx10ConvertToPwmUnsigned(&payload[11 + offset]); // rudder
141 const uint8_t flags1 = payload[13 + offset];
142 const uint8_t rate = flags1 & FLAG_MODE_MASK; // takes values 0, 1, 2
143 if (rate == RATE_LOW) {
144 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MIN;
145 } else if (rate == RATE_MID) {
146 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MIDDLE;
147 } else {
148 rcData[RC_CHANNEL_RATE] = PWM_RANGE_MAX;
150 // flip flag is in YAW byte
151 rcData[RC_CHANNEL_FLIP] = payload[12 + offset] & FLAG_FLIP ? PWM_RANGE_MAX : PWM_RANGE_MIN;
152 const uint8_t flags2 = payload[14 + offset];
153 rcData[RC_CHANNEL_PICTURE] = flags2 & FLAG_PICTURE ? PWM_RANGE_MAX : PWM_RANGE_MIN;
154 rcData[RC_CHANNEL_VIDEO] = flags2 & FLAG_VIDEO ? PWM_RANGE_MAX : PWM_RANGE_MIN;
155 rcData[RC_CHANNEL_HEADLESS] = flags1 & FLAG_HEADLESS ? PWM_RANGE_MAX : PWM_RANGE_MIN;
158 static void cx10HopToNextChannel(void)
160 ++cx10RfChannelIndex;
161 if (cx10RfChannelIndex >= RF_CHANNEL_COUNT) {
162 cx10RfChannelIndex = 0;
164 NRF24L01_SetChannel(cx10RfChannels[cx10RfChannelIndex]);
167 // The hopping channels are determined by the txId
168 STATIC_UNIT_TESTED void cx10SetHoppingChannels(const uint8_t *txId)
170 cx10RfChannelIndex = 0;
171 cx10RfChannels[0] = 0x03 + (txId[0] & 0x0F);
172 cx10RfChannels[1] = 0x16 + (txId[0] >> 4);
173 cx10RfChannels[2] = 0x2D + (txId[1] & 0x0F);
174 cx10RfChannels[3] = 0x40 + (txId[1] >> 4);
177 static bool cx10CrcOK(uint16_t crc, const uint8_t *payload)
179 if (payload[payloadSize] != (crc >> 8)) {
180 return false;
182 if (payload[payloadSize + 1] != (crc & 0xff)) {
183 return false;
185 return true;
188 static bool cx10ReadPayloadIfAvailable(uint8_t *payload)
190 if (NRF24L01_ReadPayloadIfAvailable(payload, payloadSize + CRC_LEN)) {
191 const uint16_t crc = XN297_UnscramblePayload(payload, payloadSize, rxAddr);
192 if (cx10CrcOK(crc, payload)) {
193 return true;
196 return false;
200 * This is called periodically by the scheduler.
201 * Returns RX_SPI_RECEIVED_DATA if a data packet was received.
203 rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload)
205 static uint8_t ackCount;
206 rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
207 int totalDelayUs;
208 uint32_t timeNowUs;
210 switch (protocolState) {
211 case STATE_BIND:
212 if (cx10ReadPayloadIfAvailable(payload)) {
213 const bool bindPacket = cx10CheckBindPacket(payload);
214 if (bindPacket) {
215 // set the hopping channels as determined by the txId received in the bind packet
216 cx10SetHoppingChannels(txId);
217 ret = RX_SPI_RECEIVED_BIND;
218 protocolState = STATE_ACK;
219 ackCount = 0;
222 break;
223 case STATE_ACK:
224 // transmit an ACK packet
225 ++ackCount;
226 totalDelayUs = 0;
227 // send out an ACK on the bind channel, required by deviationTx
228 payload[9] = 0x01;
229 NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL);
230 NRF24L01_FlushTx();
231 XN297_WritePayload(payload, payloadSize, rxAddr);
232 NRF24L01_SetTxMode();// enter transmit mode to send the packet
233 // wait for the ACK packet to send before changing channel
234 static const int fifoDelayUs = 100;
235 while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
236 delayMicroseconds(fifoDelayUs);
237 totalDelayUs += fifoDelayUs;
239 // send out an ACK on each of the hopping channels, required by CX10 transmitter
240 for (int ii = 0; ii < RF_CHANNEL_COUNT; ++ii) {
241 NRF24L01_SetChannel(cx10RfChannels[ii]);
242 XN297_WritePayload(payload, payloadSize, rxAddr);
243 NRF24L01_SetTxMode();// enter transmit mode to send the packet
244 // wait for the ACK packet to send before changing channel
245 while (!(NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_TX_EMPTY))) {
246 delayMicroseconds(fifoDelayUs);
247 totalDelayUs += fifoDelayUs;
250 static const int delayBetweenPacketsUs = 1000;
251 if (totalDelayUs < delayBetweenPacketsUs) {
252 delayMicroseconds(delayBetweenPacketsUs - totalDelayUs);
254 NRF24L01_SetRxMode();//reenter receive mode after sending ACKs
255 if (ackCount > ACK_TO_SEND_COUNT) {
256 NRF24L01_SetChannel(cx10RfChannels[0]);
257 // and go into data state to wait for first data packet
258 protocolState = STATE_DATA;
260 break;
261 case STATE_DATA:
262 timeNowUs = micros();
263 // read the payload, processing of payload is deferred
264 if (cx10ReadPayloadIfAvailable(payload)) {
265 cx10HopToNextChannel();
266 timeOfLastHop = timeNowUs;
267 ret = RX_SPI_RECEIVED_DATA;
269 if (timeNowUs > timeOfLastHop + hopTimeout) {
270 cx10HopToNextChannel();
271 timeOfLastHop = timeNowUs;
274 return ret;
277 static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
279 cx10Protocol = protocol;
280 protocolState = STATE_BIND;
281 payloadSize = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_PAYLOAD_SIZE : CX10A_PROTOCOL_PAYLOAD_SIZE;
282 hopTimeout = (protocol == RX_SPI_NRF24_CX10) ? CX10_PROTOCOL_HOP_TIMEOUT : CX10A_PROTOCOL_HOP_TIMEOUT;
284 NRF24L01_Initialize(0); // sets PWR_UP, no CRC
285 NRF24L01_SetupBasic();
287 NRF24L01_SetChannel(CX10_RF_BIND_CHANNEL);
289 NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_1Mbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
290 // RX_ADDR for pipes P2 to P5 are left at default values
291 NRF24L01_FlushRx();
292 NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, txAddr, RX_TX_ADDR_LEN);
293 NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxAddr, RX_TX_ADDR_LEN);
295 NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize + CRC_LEN); // payload + 2 bytes CRC
297 NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
300 bool cx10Nrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
302 rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
303 cx10Nrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
305 return true;
307 #endif