APM:Libraries
RC_NRF_parser.cpp
Go to the documentation of this file.
1 /*
2  (c) 2017 night_ghost@ykoctpa.ru
3 
4 based on: BetaFlight NRF driver
5 */
6 
7 #include <exti.h>
8 #include <timer.h>
9 #include "RCInput.h"
10 #include <pwm_in.h>
11 #include <AP_HAL/utility/dsm.h>
12 #include "sbus.h"
13 #include "GPIO.h"
14 #include "ring_buffer_pulse.h"
15 #include "RC_NRF_parser.h"
16 
17 
18 using namespace F4Light;
19 
20 
21 extern const AP_HAL::HAL& hal;
22 
23 #if defined(BOARD_NRF_CS_PIN) && defined(BOARD_NRF_NAME)
24 
25 
26 static uint8_t NRF_Buffer[NRF_MAX_PAYLOAD_SIZE];
27 static uint8_t ackPayload[NRF24L01_MAX_PAYLOAD_SIZE];
28 
29 NRF_parser::uint8_t rxTxAddr[RX_TX_ADDR_LEN] = {0x4b,0x5c,0x6d,0x7e,0x8f};
30 
31 static const uint8_t inavRfChannelHoppingCount = INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT;
32 static uint8_t inavRfChannelCount;
33 static uint8_t inavRfChannelIndex;
34 static uint8_t inavRfChannels[INAV_RF_CHANNEL_COUNT_MAX];
35 
36 void NRF_parser::init(uint8_t ch){
37 
38  memset((void *)&val[0], 0, sizeof(val));
39 
40  _last_signal=0;
41  _last_change =0;
42 
43 
44  GPIO::_pinMode(BOARD_NRF24_CS_PIN, OUTPUT);
45  GPIO::_write(BOARD_NRF24_CS_PIN, 1);
46 
47  nrf = hal.spi->get_device(BOARD_NRF_NAME);
48 
49  nrf->register_periodic_callback(FUNCTOR_BIND_MEMBER(&NRF_parser::_timer, bool), 100);
50 
51 }
52 
53 void NRF_parser::_timer() {
54 
55  uint32_t timeNowUs;
56  switch (protocolState) {
57  case STATE_BIND:
58  if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
59  whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
60  const bool bindPacket = checkBindPacket(NRF_Buffer);
61  if (bindPacket) {
62  state = RX_SPI_RECEIVED_BIND;
63  writeBindAckPayload(NRF_Buffer);
64  // got a bind packet, so set the hopping channels and the rxTxAddr and start listening for data
65  inavSetBound();
66  }
67  }
68  break;
69 
70  case STATE_DATA:
71  timeNowUs = micros();
72  // read the payload, processing of payload is deferred
73  if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
74  whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
75  receivedPowerSnapshot = NRF24L01_ReadReg(NRF24L01_09_RPD); // set to 1 if received power > -64dBm
76  const bool bindPacket = checkBindPacket(NRF_Buffer);
77  if (bindPacket) {
78  // transmitter may still continue to transmit bind packets after we have switched to data mode
79  state = RX_SPI_RECEIVED_BIND;
80  writeBindAckPayload(NRF_Buffer);
81  } else {
82  state = RX_SPI_RECEIVED_DATA;
83  writeTelemetryAckPayload();
84  }
85  }
86  if ((state == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
87  inavHopToNextChannel();
88  timeOfLastHop = timeNowUs;
89  }
90  break;
91  }
92 
93 
94 }
95 
96 bool NRF_parser::checkBindPacket(const uint8_t *payload)
97 {
98  bool bindPacket = false;
99  if (payload[0] == BIND_PAYLOAD0 && payload[1] == BIND_PAYLOAD1) {
100  bindPacket = true;
101  if (protocolState ==STATE_BIND) {
102  rxTxAddr[0] = payload[2];
103  rxTxAddr[1] = payload[3];
104  rxTxAddr[2] = payload[4];
105  rxTxAddr[3] = payload[5];
106  rxTxAddr[4] = payload[6];
107  /*inavRfChannelHoppingCount = payload[7]; // !!TODO not yet implemented on transmitter
108  if (inavRfChannelHoppingCount > INAV_RF_CHANNEL_COUNT_MAX) {
109  inavRfChannelHoppingCount = INAV_RF_CHANNEL_COUNT_MAX;
110  }*/
111  if (fixedIdPtr != NULL && *fixedIdPtr == 0) {
112  // copy the rxTxAddr so it can be saved
113  memcpy(fixedIdPtr, rxTxAddr, sizeof(uint32_t));
114  }
115  }
116  }
117  return bindPacket;
118 }
119 
120 
121 void NRF_parser::whitenPayload(uint8_t *payload, uint8_t len)
122 {
123 #ifdef USE_WHITENING
124  uint8_t whitenCoeff = 0x6b; // 01101011
125  while (len--) {
126  for (uint8_t m = 1; m; m <<= 1) {
127  if (whitenCoeff & 0x80) {
128  whitenCoeff ^= 0x11;
129  (*payload) ^= m;
130  }
131  whitenCoeff <<= 1;
132  }
133  payload++;
134  }
135 #else
136  UNUSED(payload);
137  UNUSED(len);
138 #endif
139 }
140 
141 void NRF_parser::inavSetBound(void)
142 {
143  protocolState = STATE_DATA;
144  NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
145  NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
146 
147  timeOfLastHop = micros();
148  inavRfChannelIndex = 0;
149  inavSetHoppingChannels();
150  NRF24L01_SetChannel(inavRfChannels[0]);
151 #ifdef DEBUG_NRF24_INAV
152  debug[0] = inavRfChannels[inavRfChannelIndex];
153 #endif
154 }
155 
156 void NRF_parser::writeAckPayload(uint8_t *data, uint8_t length)
157 {
158  whitenPayload(data, length);
159  NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_MAX_RT));
160  NRF24L01_WriteAckPayload(data, length, NRF24L01_PIPE0);
161 }
162 
163 void NRF_parser::writeTelemetryAckPayload(void)
164 {
165 #ifdef TELEMETRY_NRF24_LTM
166  // set up telemetry data, send back telemetry data in the ACK packet
167  static uint8_t sequenceNumber = 0;
168  static ltm_frame_e ltmFrameType = LTM_FRAME_START;
169 
170  ackPayload[0] = TELEMETRY_ACK_PAYLOAD0;
171  ackPayload[1] = sequenceNumber++;
172  const int ackPayloadSize = getLtmFrame(&ackPayload[2], ltmFrameType) + 2;
173 
174  ++ltmFrameType;
175  if (ltmFrameType > LTM_FRAME_COUNT) {
176  ltmFrameType = LTM_FRAME_START;
177  }
178  writeAckPayload(ackPayload, ackPayloadSize);
179 #ifdef DEBUG_NRF24_INAV
180  debug[1] = ackPayload[1]; // sequenceNumber
181  debug[2] = ackPayload[2]; // frame type, 'A', 'S' etc
182  debug[3] = ackPayload[3]; // pitch for AFrame
183 #endif
184 #endif
185 }
186 
187 
188 void NRF_parser::writeBindAckPayload(uint8_t *payload)
189 {
190 #ifdef USE_AUTO_ACKKNOWLEDGEMENT
191  memcpy(ackPayload, payload, BIND_PAYLOAD_SIZE);
192  // send back the payload with the first two bytes set to zero as the ack
193  ackPayload[0] = BIND_ACK_PAYLOAD0;
194  ackPayload[1] = BIND_ACK_PAYLOAD1;
195  // respond to request for rfChannelCount;
196  ackPayload[7] = inavRfChannelHoppingCount;
197  // respond to request for payloadSize
198  switch (payloadSize) {
199  case INAV_PROTOCOL_PAYLOAD_SIZE_MIN:
200  case INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT:
201  case INAV_PROTOCOL_PAYLOAD_SIZE_MAX:
202  ackPayload[8] = payloadSize;
203  break;
204  default:
205  ackPayload[8] = INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT;
206  break;
207  }
208  writeAckPayload(ackPayload, BIND_PAYLOAD_SIZE);
209 #else
210  UNUSED(payload);
211 #endif
212 }
213 
214 
215 void NRF_parser::inavHopToNextChannel(void)
216 {
217  ++inavRfChannelIndex;
218  if (inavRfChannelIndex >= inavRfChannelCount) {
219  inavRfChannelIndex = 0;
220  }
221  NRF24L01_SetChannel(inavRfChannels[inavRfChannelIndex]);
222 #ifdef DEBUG_NRF24_INAV
223  debug[0] = inavRfChannels[inavRfChannelIndex];
224 #endif
225 }
226 
227 // The hopping channels are determined by the low bits of rxTxAddr
228 void NRF_parser::inavSetHoppingChannels(void)
229 {
230 #ifdef NO_RF_CHANNEL_HOPPING
231  // just stay on bind channel, useful for debugging
232  inavRfChannelCount = 1;
233  inavRfChannels[0] = INAV_RF_BIND_CHANNEL;
234 #else
235  inavRfChannelCount = inavRfChannelHoppingCount;
236  const uint8_t addr = rxTxAddr[0];
237  uint8_t ch = 0x10 + (addr & 0x07);
238  for (int ii = 0; ii < INAV_RF_CHANNEL_COUNT_MAX; ++ii) {
239  inavRfChannels[ii] = ch;
240  ch += 0x0c;
241  }
242 #endif
243 }
244 
245 void NRF_parser::set_val(uint8_t ch, uint16_t val){
246  if(_val[ch] != val) {
247  _val[ch] = val;
248  _last_change = systick_uptime();
249  }
250 
251 }
252 
253 void NRF_parser::inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
254 {
255  memset(_val, 0, sizeof(_val));
256  // payload[0] and payload[1] are zero in DATA state
257  // the AETR channels have 10 bit resolution
258  uint8_t lowBits = payload[6]; // least significant bits for AETR
259  set_val(RC_SPI_ROLL, PWM_RANGE_MIN + ((payload[2] << 2) | (lowBits & 0x03)) ); // Aileron
260  lowBits >>= 2;
261  set_val(RC_SPI_PITCH, PWM_RANGE_MIN + ((payload[3] << 2) | (lowBits & 0x03)) ); // Elevator
262  lowBits >>= 2;
263  set_val(RC_SPI_THROTTLE, PWM_RANGE_MIN + ((payload[4] << 2) | (lowBits & 0x03)) ); // Throttle
264  lowBits >>= 2;
265  set_val(RC_SPI_YAW, PWM_RANGE_MIN + ((payload[5] << 2) | (lowBits & 0x03)) ); // Rudder
266 
267  if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MIN) {
268  // small payload variant of protocol, supports 6 channels
269  set_val(RC_SPI_AUX1, PWM_RANGE_MIN + (payload[7] << 2) );
270  set_val(RC_SPI_AUX2, PWM_RANGE_MIN + (payload[1] << 2) );
271  _channels = RC_SPI_AUX2+1;
272  } else {
273  // channel AUX1 is used for rate, as per the deviation convention
274  const uint8_t rate = payload[7];
275  // AUX1
276  if (rate == RATE_HIGH) {
277  set_val(RC_CHANNEL_RATE, PWM_RANGE_MAX);
278  } else if (rate == RATE_MID) {
279  set_val(RC_CHANNEL_RATE, PWM_RANGE_MIDDLE);
280  } else {
281  set_val(RC_CHANNEL_RATE, PWM_RANGE_MIN);
282  }
283 
284  // channels AUX2 to AUX7 use the deviation convention
285  const uint8_t flags = payload[8];
286  set_val(RC_CHANNEL_FLIP, (flags & FLAG_FLIP) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX2
287  set_val(RC_CHANNEL_PICTURE, (flags & FLAG_PICTURE) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX3
288  set_val(RC_CHANNEL_VIDEO, (flags & FLAG_VIDEO) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX4
289  set_val(RC_CHANNEL_HEADLESS, (flags & FLAG_HEADLESS) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); //AUX5
290  set_val(RC_CHANNEL_RTH, (flags & FLAG_RTH) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX6
291 
292  // channels AUX7 to AUX10 have 10 bit resolution
293  lowBits = payload[13]; // least significant bits for AUX7 to AUX10
294  set_val(RC_SPI_AUX7, PWM_RANGE_MIN + ((payload[9] << 2) | (lowBits & 0x03)) );
295  lowBits >>= 2;
296  set_val(RC_SPI_AUX8, PWM_RANGE_MIN + ((payload[10] << 2) | (lowBits & 0x03)) );
297  lowBits >>= 2;
298  set_val(RC_SPI_AUX9, PWM_RANGE_MIN + ((payload[11] << 2) | (lowBits & 0x03)) );
299  lowBits >>= 2;
300  set_val(RC_SPI_AUX10, PWM_RANGE_MIN + ((payload[12] << 2) | (lowBits & 0x03)) );
301  lowBits >>= 2;
302 
303  // channels AUX11 and AUX12 have 8 bit resolution
304  set_val(RC_SPI_AUX11, PWM_RANGE_MIN + (payload[14] << 2) );
305  set_val(RC_SPI_AUX12, PWM_RANGE_MIN + (payload[15] << 2) );
306 
307  _channels = RC_SPI_AUX12+1;
308  }
309  if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MAX) {
310  // large payload variant of protocol
311  // channels AUX13 to AUX16 have 8 bit resolution
312  set_val(RC_SPI_AUX13, PWM_RANGE_MIN + (payload[16] << 2) );
313  set_val(RC_SPI_AUX14, PWM_RANGE_MIN + (payload[17] << 2) );
314  _channels = RC_SPI_AUX14+1;
315  }
316 
317  _last_signal = systick_uptime();
318 }
319 
320 void NRF_parser::inavNrf24Setup(const uint32_t *fixedId)
321 {
322 
323  // sets PWR_UP, EN_CRC, CRCO - 2 byte CRC, only get IRQ pin interrupt on RX_DR
324  NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO) | BV(NRF24L01_00_CONFIG_MASK_MAX_RT) | BV(NRF24L01_00_CONFIG_MASK_TX_DS));
325 
326 #ifdef USE_AUTO_ACKKNOWLEDGEMENT
327  NRF24L01_WriteReg(NRF24L01_01_EN_AA, BV(NRF24L01_01_EN_AA_ENAA_P0)); // auto acknowledgment on P0
328  NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
329  NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
330  NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0);
331  NRF24L01_Activate(0x73); // activate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
332  NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BV(NRF24L01_1D_FEATURE_EN_DPL));
333  NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BV(NRF24L01_1C_DYNPD_DPL_P0)); // enable dynamic payload length on P0
334  //NRF24L01_Activate(0x73); // deactivate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
335 
336  NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
337 #else
338  NRF24L01_SetupBasic();
339 #endif
340 
341  NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
342  // RX_ADDR for pipes P1-P5 are left at default values
343  NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
344  NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize);
345 
346 #ifdef USE_BIND_ADDRESS_FOR_DATA_STATE
347  inavSetBound();
348  UNUSED(fixedId);
349 #else
350  fixedId = NULL; // !!TODO remove this once configurator supports setting rx_id
351  if (fixedId == NULL || *fixedId == 0) {
352  fixedIdPtr = NULL;
353  protocolState = STATE_BIND;
354  inavRfChannelCount = 1;
355  inavRfChannelIndex = 0;
356  NRF24L01_SetChannel(INAV_RF_BIND_CHANNEL);
357  } else {
358  fixedIdPtr = (uint32_t*)fixedId;
359  // use the rxTxAddr provided and go straight into DATA_STATE
360  memcpy(rxTxAddr, fixedId, sizeof(uint32_t));
361  rxTxAddr[4] = RX_TX_ADDR_4;
362  inavSetBound();
363  }
364 #endif
365 
366  NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
367  // put a null packet in the transmit buffer to be sent as ACK on first receive
368  writeAckPayload(ackPayload, payloadSize);
369 }
370 
371 
372 
373 
375 
376 #define NRF24_CE_HI() cs_assert()
377 #define NRF24_CE_LO() cs_release()
378 
379 // Instruction Mnemonics
380 // nRF24L01: Table 16. Command set for the nRF24L01 SPI. Product Specification, p46
381 // nRF24L01+: Table 20. Command set for the nRF24L01+ SPI. Product Specification, p51
382 #define R_REGISTER 0x00
383 #define W_REGISTER 0x20
384 #define REGISTER_MASK 0x1F
385 #define ACTIVATE 0x50
386 #define R_RX_PL_WID 0x60
387 #define R_RX_PAYLOAD 0x61
388 #define W_TX_PAYLOAD 0xA0
389 #define W_ACK_PAYLOAD 0xA8
390 #define FLUSH_TX 0xE1
391 #define FLUSH_RX 0xE2
392 #define REUSE_TX_PL 0xE3
393 #define NOP 0xFF
394 
395 uint8_t rxSpiTransferByte(uint8_t data){
396  uint8_t bt;
397  // const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len
398  nrf->transfer(&data,1,&bt,1);
399  return bt;
400 }
401 
402 uint8_t rxSpiWriteByte(uint8_t data)
403 {
404  ENABLE_RX();
405  const uint8_t ret = rxSpiTransferByte(data);
406  DISABLE_RX();
407  return ret;
408 }
409 
410 void rxSpiWriteCommand(uint8_t reg, uint8_t data){
411  uint8_t bt[2] = {reg, data };
412 
413  nrf->transfer(&bt,2,NULL,0);
414 }
415 
416 
417 void rxSpiWriteCommandMulti(uint8_t reg, const uint8_t *data, uint8_t length){
418  uint8_t bt[length+1];
419  bt[0]=reg;
420  for(uint8_t i=0;i<length;i++) {
421  bt[i+1] = data[i];
422  }
423  nrf->transfer(&bt,length,NULL,0);
424 }
425 
426 void rxSpiReadCommand(uint8_t reg, uint8_t bt){
427  nrf->transfer(reg);
428  return nrf->transfer(bt);
429 }
430 
431 
432 bool rxSpiReadCommandMulti(uint8_t reg, uint8_t op, uint8_t *data, uint8_t length)
433  const uint8_t ret = rxSpiTransferByte(reg);
434  for (uint8_t i = 0; i < length; i++) {
435  data[i] = rxSpiTransferByte(op);
436  }
437  return ret;
438 }
439 
440 
441 void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
442 {
443  rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
444 }
445 
446 void NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length)
447 {
448  rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
449 }
450 
451 /*
452  * Transfer the payload to the nRF24L01 TX FIFO
453  * Packets in the TX FIFO are transmitted when the
454  * nRF24L01 next enters TX mode
455  */
456 uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length)
457 {
458  return rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
459 }
460 
461 uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe)
462 {
463  return rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
464 }
465 
466 uint8_t NRF24L01_ReadReg(uint8_t reg)
467 {
468  return rxSpiReadCommand(R_REGISTER | (REGISTER_MASK & reg), NOP);
469 }
470 
471 uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
472 {
473  return rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
474 }
475 
476 /*
477  * Read a packet from the nRF24L01 RX FIFO.
478  */
479 uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
480 {
481  return rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
482 }
483 
484 
485 
486 /*
487  * Empty the transmit FIFO buffer.
488  */
489 void NRF24L01_FlushTx()
490 {
491  rxSpiWriteByte(FLUSH_TX);
492 }
493 
494 /*
495  * Empty the receive FIFO buffer.
496  */
497 void NRF24L01_FlushRx()
498 {
499  rxSpiWriteByte(FLUSH_RX);
500 }
501 
502 uint8_t NRF24L01_Activate(uint8_t code)
503 {
504  return rxSpiWriteCommand(ACTIVATE, code);
505 }
506 
507 // standby configuration, used to simplify switching between RX, TX, and Standby modes
508 static uint8_t standbyConfig;
509 
510 void NRF24L01_Initialize(uint8_t baseConfig)
511 {
512  standbyConfig = BV(NRF24L01_00_CONFIG_PWR_UP) | baseConfig;
513  NRF24_CE_LO();
514  // nRF24L01+ needs 100 milliseconds settling time from PowerOnReset to PowerDown mode
515  static const timeUs_t settlingTimeUs = 100000;
516  const timeUs_t currentTimeUs = micros();
517  if (currentTimeUs < settlingTimeUs) {
518  delayMicroseconds(settlingTimeUs - currentTimeUs);
519  }
520  // now in PowerDown mode
521  NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig); // set PWR_UP to enter Standby mode
522  // nRF24L01+ needs 4500 microseconds from PowerDown mode to Standby mode, for crystal oscillator startup
523  delayMicroseconds(4500);
524  // now in Standby mode
525 }
526 
527 /*
528  * Common setup of registers
529  */
530 void NRF24L01_SetupBasic(void)
531 {
532  NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No auto acknowledgment
533  NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
534  NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
535  NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
536 }
537 
538 
539 /*
540  * Enter standby mode
541  */
542 void NRF24L01_SetStandbyMode(void)
543 {
544  // set CE low and clear the PRIM_RX bit to enter standby mode
545  NRF24_CE_LO();
546  NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig);
547 }
548 
549 /*
550  * Enter receive mode
551  */
552 void NRF24L01_SetRxMode(void)
553 {
554  NRF24_CE_LO(); // drop into standby mode
555  // set the PRIM_RX bit
556  NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BV(NRF24L01_00_CONFIG_PRIM_RX));
557  NRF24L01_ClearAllInterrupts();
558  // finally set CE high to start enter RX mode
559  NRF24_CE_HI();
560  // nRF24L01+ will now transition from Standby mode to RX mode after 130 microseconds settling time
561 }
562 
563 /*
564  * Enter transmit mode. Anything in the transmit FIFO will be transmitted.
565  */
566 void NRF24L01_SetTxMode(void)
567 {
568  // Ensure in standby mode, since can only enter TX mode from standby mode
569  NRF24L01_SetStandbyMode();
570  NRF24L01_ClearAllInterrupts();
571  // pulse CE for 10 microseconds to enter TX mode
572  NRF24_CE_HI();
573  delayMicroseconds(10);
574  NRF24_CE_LO();
575  // nRF24L01+ will now transition from Standby mode to TX mode after 130 microseconds settling time.
576  // Transmission will then begin and continue until TX FIFO is empty.
577 }
578 
579 void NRF24L01_ClearAllInterrupts(void)
580 {
581  // Writing to the STATUS register clears the specified interrupt bits
582  NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT));
583 }
584 
585 
586 bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length)
587 {
588  if (NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_RX_EMPTY)) {
589  return false;
590  }
591  NRF24L01_ReadPayload(data, length);
592  return true;
593 }
594 
595 
596 
597 #endif // BOARD_NRF24_CS_PIN
598 
static void _pinMode(uint8_t pin, uint8_t output)
Definition: GPIO.cpp:21
static void delayMicroseconds(uint16_t us)
Definition: compat.h:82
Simple circular buffer for PEM input.
static void _write(uint8_t pin, uint8_t value)
Definition: GPIO.h:165
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
Definition: GPIO.h:35
timer interface.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#define debug(fmt, args ...)
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
static int state
Definition: Util.cpp:20
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
#define NULL
Definition: hal_types.h:59
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void init()
Generic board initialization function.
Definition: system.cpp:136
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
uint32_t micros()
Definition: system.cpp:152