forked from nRF24/RF24
-
Notifications
You must be signed in to change notification settings - Fork 0
/
RF24.cpp
1640 lines (1298 loc) · 45.6 KB
/
RF24.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
Copyright (C) 2011 J. Coliz <[email protected]>
This program is free software; you can redistribute it and/or
modify it under the terms of the GNU General Public License
version 2 as published by the Free Software Foundation.
*/
#include "nRF24L01.h"
#include "RF24_config.h"
#include "RF24.h"
/****************************************************************************/
void RF24::csn(bool mode)
{
// Minimum ideal SPI bus speed is 2x data rate
// If we assume 2Mbs data rate and 16Mhz clock, a
// divider of 4 is the minimum we want.
// CLK:BUS 8Mhz:2Mhz, 16Mhz:4Mhz, or 20Mhz:5Mhz
#ifdef ARDUINO
#if ( !defined(RF24_TINY) && !defined (__arm__) && !defined (SOFTSPI)) || defined (CORE_TEENSY)
_SPI.setBitOrder(MSBFIRST);
_SPI.setDataMode(SPI_MODE0);
_SPI.setClockDivider(SPI_CLOCK_DIV2);
#endif
#endif
#if defined (RF24_LINUX)
//if(!mode){
bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST);
bcm2835_spi_setDataMode(BCM2835_SPI_MODE0);
bcm2835_spi_setClockDivider(spi_speed);
bcm2835_spi_chipSelect(csn_pin);
delayMicroseconds(5);
#elif defined (RF24_TINY)
if (ce_pin != csn_pin) {
digitalWrite(csn_pin,mode);
}
else {
if (mode == HIGH) {
PORTB |= (1<<PINB2); // SCK->CSN HIGH
delayMicroseconds(100); // allow csn to settle.
}
else {
PORTB &= ~(1<<PINB2); // SCK->CSN LOW
delayMicroseconds(11); // allow csn to settle
}
}
#elif !defined (__arm__) || defined (CORE_TEENSY)
digitalWrite(csn_pin,mode);
delayMicroseconds(5);
#endif
}
/****************************************************************************/
void RF24::ce(bool level)
{
#if defined (RF24_LINUX)
bcm2835_gpio_write(ce_pin, level);
#else
//Allow for 3-pin use on ATTiny
if (ce_pin != csn_pin) digitalWrite(ce_pin,level);
#endif
}
/****************************************************************************/
uint8_t RF24::read_register(uint8_t reg, uint8_t* buf, uint8_t len)
{
uint8_t status;
#if defined (RF24_LINUX)
csn(LOW); //In this case, calling csn(LOW) configures the spi settings
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
uint8_t size = len + 1; // Add register value to transmit buffer
*ptx++ = ( R_REGISTER | ( REGISTER_MASK & reg ) );
while (len--){ *ptx++ = NOP; } // Dummy operation, just for reading
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, size);
status = *prx++; // status is 1st byte of receive buffer
// decrement before to skip status byte
while ( --size ){ *buf++ = *prx++; }
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, R_REGISTER | ( REGISTER_MASK & reg ), SPI_CONTINUE );
while ( len-- > 1 ){
*buf++ = _SPI.transfer(csn_pin,0xff, SPI_CONTINUE);
}
*buf++ = _SPI.transfer(csn_pin,0xff);
#else
csn(LOW);
status = _SPI.transfer( R_REGISTER | ( REGISTER_MASK & reg ) );
while ( len-- ){
*buf++ = _SPI.transfer(0xff);
}
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::read_register(uint8_t reg)
{
uint8_t result;
#if defined (RF24_LINUX)
csn(LOW);
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
*ptx++ = ( R_REGISTER | ( REGISTER_MASK & reg ) );
*ptx++ = NOP ; // Dummy operation, just for reading
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, 2);
result = *++prx; // result is 2nd byte of receive buffer
#elif defined (__arm__) && !defined ( CORE_TEENSY )
_SPI.transfer(csn_pin, R_REGISTER | ( REGISTER_MASK & reg ) , SPI_CONTINUE);
result = _SPI.transfer(csn_pin,0xff);
#else
csn(LOW);
_SPI.transfer( R_REGISTER | ( REGISTER_MASK & reg ) );
result = _SPI.transfer(0xff);
csn(HIGH);
#endif
return result;
}
/****************************************************************************/
uint8_t RF24::write_register(uint8_t reg, const uint8_t* buf, uint8_t len)
{
uint8_t status;
#if defined (RF24_LINUX)
csn(LOW);
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
uint8_t size = len + 1; // Add register value to transmit buffer
*ptx++ = ( W_REGISTER | ( REGISTER_MASK & reg ) );
while ( len-- )
*ptx++ = *buf++;
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, size);
status = *prx; // status is 1st byte of receive buffer
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, W_REGISTER | ( REGISTER_MASK & reg ), SPI_CONTINUE );
while ( --len){
_SPI.transfer(csn_pin,*buf++, SPI_CONTINUE);
}
_SPI.transfer(csn_pin,*buf++);
#else
csn(LOW);
status = _SPI.transfer( W_REGISTER | ( REGISTER_MASK & reg ) );
while ( len-- )
_SPI.transfer(*buf++);
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::write_register(uint8_t reg, uint8_t value)
{
uint8_t status;
IF_SERIAL_DEBUG(printf_P(PSTR("write_register(%02x,%02x)\r\n"),reg,value));
#if defined (RF24_LINUX)
csn(LOW);
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
*ptx++ = ( W_REGISTER | ( REGISTER_MASK & reg ) );
*ptx = value ;
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, 2);
status = *prx++; // status is 1st byte of receive buffer
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, W_REGISTER | ( REGISTER_MASK & reg ), SPI_CONTINUE);
_SPI.transfer(csn_pin,value);
#else
csn(LOW);
status = _SPI.transfer( W_REGISTER | ( REGISTER_MASK & reg ) );
_SPI.transfer(value);
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::write_payload(const void* buf, uint8_t data_len, const uint8_t writeType)
{
uint8_t status;
const uint8_t* current = reinterpret_cast<const uint8_t*>(buf);
data_len = rf24_min(data_len, payload_size);
uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len;
//printf("[Writing %u bytes %u blanks]",data_len,blank_len);
IF_SERIAL_DEBUG( printf("[Writing %u bytes %u blanks]\n",data_len,blank_len); );
#if defined (RF24_LINUX)
csn(LOW);
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
uint8_t size;
size = data_len + blank_len + 1 ; // Add register value to transmit buffer
*ptx++ = writeType;
while ( data_len-- )
*ptx++ = *current++;
while ( blank_len-- )
*ptx++ = 0;
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, size);
status = *prx; // status is 1st byte of receive buffer
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, writeType , SPI_CONTINUE);
if(blank_len){
while ( data_len--){
_SPI.transfer(csn_pin,*current++, SPI_CONTINUE);
}
while ( --blank_len ){
_SPI.transfer(csn_pin,0, SPI_CONTINUE);
}
_SPI.transfer(csn_pin,0);
}else{
while( --data_len ){
_SPI.transfer(csn_pin,*current++, SPI_CONTINUE);
}
_SPI.transfer(csn_pin,*current);
}
#else
csn(LOW);
status = _SPI.transfer( writeType );
while ( data_len-- ) {
_SPI.transfer(*current++);
}
while ( blank_len-- ) {
_SPI.transfer(0);
}
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::read_payload(void* buf, uint8_t data_len)
{
uint8_t status;
uint8_t* current = reinterpret_cast<uint8_t*>(buf);
if(data_len > payload_size) data_len = payload_size;
uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len;
//printf("[Reading %u bytes %u blanks]",data_len,blank_len);
IF_SERIAL_DEBUG( printf("[Reading %u bytes %u blanks]\n",data_len,blank_len); );
#if defined (RF24_LINUX)
csn(LOW);
uint8_t * prx = spi_rxbuff;
uint8_t * ptx = spi_txbuff;
uint8_t size;
size = data_len + blank_len + 1; // Add register value to transmit buffer
*ptx++ = R_RX_PAYLOAD;
while(size--)
*ptx++ = NOP;
size = data_len + blank_len + 1; // Size has been lost during while, re affect
bcm2835_spi_transfernb( (char *) spi_txbuff, (char *) spi_rxbuff, size);
status = *prx++; // 1st byte is status
while ( --data_len ) // Decrement before to skip 1st status byte
*current++ = *prx++;
*current = *prx;
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, R_RX_PAYLOAD, SPI_CONTINUE );
if( blank_len ){
while ( data_len-- ){
*current++ = _SPI.transfer(csn_pin,0xFF, SPI_CONTINUE);
}
while ( --blank_len ){
_SPI.transfer(csn_pin,0xFF, SPI_CONTINUE);
}
_SPI.transfer(csn_pin,0xFF);
}else{
while ( --data_len ){
*current++ = _SPI.transfer(csn_pin,0xFF, SPI_CONTINUE);
}
*current = _SPI.transfer(csn_pin,0xFF);
}
#else
csn(LOW);
status = _SPI.transfer( R_RX_PAYLOAD );
while ( data_len-- ) {
*current++ = _SPI.transfer(0xFF);
}
while ( blank_len-- ) {
_SPI.transfer(0xff);
}
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::flush_rx(void)
{
return spiTrans( FLUSH_RX );
}
/****************************************************************************/
uint8_t RF24::flush_tx(void)
{
return spiTrans( FLUSH_TX );
}
/****************************************************************************/
uint8_t RF24::spiTrans(uint8_t cmd){
uint8_t status;
#if defined (RF24_LINUX)
csn(LOW);
status = bcm2835_spi_transfer( cmd );
#elif defined (__arm__) && !defined ( CORE_TEENSY )
status = _SPI.transfer(csn_pin, cmd );
#else
csn(LOW);
status = _SPI.transfer( cmd );
csn(HIGH);
#endif
return status;
}
/****************************************************************************/
uint8_t RF24::get_status(void)
{
return spiTrans(NOP);
}
/****************************************************************************/
#if !defined (MINIMAL)
void RF24::print_status(uint8_t status)
{
printf_P(PSTR("STATUS\t\t = 0x%02x RX_DR=%x TX_DS=%x MAX_RT=%x RX_P_NO=%x TX_FULL=%x\r\n"),
status,
(status & _BV(RX_DR))?1:0,
(status & _BV(TX_DS))?1:0,
(status & _BV(MAX_RT))?1:0,
((status >> RX_P_NO) & 0b111),
(status & _BV(TX_FULL))?1:0
);
}
/****************************************************************************/
void RF24::print_observe_tx(uint8_t value)
{
printf_P(PSTR("OBSERVE_TX=%02x: POLS_CNT=%x ARC_CNT=%x\r\n"),
value,
(value >> PLOS_CNT) & 0b1111,
(value >> ARC_CNT) & 0b1111
);
}
/****************************************************************************/
void RF24::print_byte_register(const char* name, uint8_t reg, uint8_t qty)
{
//char extra_tab = strlen_P(name) < 8 ? '\t' : '\a';
//printf_P(PSTR(PRIPSTR"\t%c ="),name,extra_tab);
#if defined (RF24_LINUX)
char extra_tab = strlen_P(name) < 8 ? '\t' : 0;
printf("%s\t%c =", name, extra_tab);
#else
char extra_tab = strlen_P(name) < 8 ? '\t' : '\a';
printf_P(PSTR(PRIPSTR"\t%c ="),name,extra_tab);
#endif
while (qty--)
printf_P(PSTR(" 0x%02x"),read_register(reg++));
printf_P(PSTR("\r\n"));
}
/****************************************************************************/
void RF24::print_address_register(const char* name, uint8_t reg, uint8_t qty)
{
#if defined (RF24_LINUX)
char extra_tab = strlen_P(name) < 8 ? '\t' : 0;
printf("%s\t%c =",name,extra_tab);
#else
char extra_tab = strlen_P(name) < 8 ? '\t' : '\a';
printf_P(PSTR(PRIPSTR"\t%c ="),name,extra_tab);
#endif
while (qty--)
{
uint8_t buffer[addr_width];
read_register(reg++,buffer,sizeof buffer);
printf_P(PSTR(" 0x"));
uint8_t* bufptr = buffer + sizeof buffer;
while( --bufptr >= buffer )
printf_P(PSTR("%02x"),*bufptr);
}
printf_P(PSTR("\r\n"));
}
#endif
/****************************************************************************/
RF24::RF24(uint8_t _cepin, uint8_t _cspin):
ce_pin(_cepin), csn_pin(_cspin), p_variant(false),
payload_size(32), dynamic_payloads_enabled(false), addr_width(5)//,pipe0_reading_address(0)
{
}
/****************************************************************************/
#if defined (RF24_LINUX)//RPi constructor
RF24::RF24(uint8_t _cepin, uint8_t _cspin, uint32_t _spi_speed):
ce_pin(_cepin),csn_pin(_cspin),spi_speed(_spi_speed),p_variant(false), payload_size(32), dynamic_payloads_enabled(false),addr_width(5)//,pipe0_reading_address(0)
{
}
#endif
/****************************************************************************/
void RF24::setChannel(uint8_t channel)
{
const uint8_t max_channel = 127;
write_register(RF_CH,rf24_min(channel,max_channel));
}
/****************************************************************************/
void RF24::setPayloadSize(uint8_t size)
{
payload_size = rf24_min(size,32);
}
/****************************************************************************/
uint8_t RF24::getPayloadSize(void)
{
return payload_size;
}
/****************************************************************************/
#if !defined (MINIMAL)
static const char rf24_datarate_e_str_0[] PROGMEM = "1MBPS";
static const char rf24_datarate_e_str_1[] PROGMEM = "2MBPS";
static const char rf24_datarate_e_str_2[] PROGMEM = "250KBPS";
static const char * const rf24_datarate_e_str_P[] PROGMEM = {
rf24_datarate_e_str_0,
rf24_datarate_e_str_1,
rf24_datarate_e_str_2,
};
static const char rf24_model_e_str_0[] PROGMEM = "nRF24L01";
static const char rf24_model_e_str_1[] PROGMEM = "nRF24L01+";
static const char * const rf24_model_e_str_P[] PROGMEM = {
rf24_model_e_str_0,
rf24_model_e_str_1,
};
static const char rf24_crclength_e_str_0[] PROGMEM = "Disabled";
static const char rf24_crclength_e_str_1[] PROGMEM = "8 bits";
static const char rf24_crclength_e_str_2[] PROGMEM = "16 bits" ;
static const char * const rf24_crclength_e_str_P[] PROGMEM = {
rf24_crclength_e_str_0,
rf24_crclength_e_str_1,
rf24_crclength_e_str_2,
};
static const char rf24_pa_dbm_e_str_0[] PROGMEM = "PA_MIN";
static const char rf24_pa_dbm_e_str_1[] PROGMEM = "PA_LOW";
static const char rf24_pa_dbm_e_str_2[] PROGMEM = "PA_HIGH";
static const char rf24_pa_dbm_e_str_3[] PROGMEM = "PA_MAX";
static const char * const rf24_pa_dbm_e_str_P[] PROGMEM = {
rf24_pa_dbm_e_str_0,
rf24_pa_dbm_e_str_1,
rf24_pa_dbm_e_str_2,
rf24_pa_dbm_e_str_3,
};
#if defined (RF24_LINUX)
static const char rf24_csn_e_str_0[] = "CE0 (PI Hardware Driven)";
static const char rf24_csn_e_str_1[] = "CE1 (PI Hardware Driven)";
static const char rf24_csn_e_str_2[] = "CE2 (PI Hardware Driven)";
static const char rf24_csn_e_str_3[] = "Custom GPIO Software Driven";
static const char * const rf24_csn_e_str_P[] = {
rf24_csn_e_str_0,
rf24_csn_e_str_1,
rf24_csn_e_str_2,
rf24_csn_e_str_3,
};
#endif
void RF24::printDetails(void)
{
#if defined (RF24_LINUX)
printf("================ SPI Configuration ================\n" );
if (csn_pin < BCM2835_SPI_CS_NONE ){
printf("CSN Pin \t = %s\n",rf24_csn_e_str_P[csn_pin]);
}else{
printf("CSN Pin \t = Custom GPIO%d%s\n", csn_pin,
csn_pin==RPI_V2_GPIO_P1_26 ? " (CE1) Software Driven" : "" );
}
printf("CE Pin \t = Custom GPIO%d\n", ce_pin );
printf("Clock Speed\t = " );
switch (spi_speed)
{
case BCM2835_SPI_SPEED_64MHZ : printf("64 Mhz"); break ;
case BCM2835_SPI_SPEED_32MHZ : printf("32 Mhz"); break ;
case BCM2835_SPI_SPEED_16MHZ : printf("16 Mhz"); break ;
case BCM2835_SPI_SPEED_8MHZ : printf("8 Mhz"); break ;
case BCM2835_SPI_SPEED_4MHZ : printf("4 Mhz"); break ;
case BCM2835_SPI_SPEED_2MHZ : printf("2 Mhz"); break ;
case BCM2835_SPI_SPEED_1MHZ : printf("1 Mhz"); break ;
case BCM2835_SPI_SPEED_512KHZ: printf("512 KHz"); break ;
case BCM2835_SPI_SPEED_256KHZ: printf("256 KHz"); break ;
case BCM2835_SPI_SPEED_128KHZ: printf("128 KHz"); break ;
case BCM2835_SPI_SPEED_64KHZ : printf("64 KHz"); break ;
case BCM2835_SPI_SPEED_32KHZ : printf("32 KHz"); break ;
case BCM2835_SPI_SPEED_16KHZ : printf("16 KHz"); break ;
case BCM2835_SPI_SPEED_8KHZ : printf("8 KHz"); break ;
default : printf("Probably Bad !!!"); break ;
}
printf("\n================ NRF Configuration ================\n");
#endif //Linux
print_status(get_status());
print_address_register(PSTR("RX_ADDR_P0-1"),RX_ADDR_P0,2);
print_byte_register(PSTR("RX_ADDR_P2-5"),RX_ADDR_P2,4);
print_address_register(PSTR("TX_ADDR"),TX_ADDR);
print_byte_register(PSTR("RX_PW_P0-6"),RX_PW_P0,6);
print_byte_register(PSTR("EN_AA"),EN_AA);
print_byte_register(PSTR("EN_RXADDR"),EN_RXADDR);
print_byte_register(PSTR("RF_CH"),RF_CH);
print_byte_register(PSTR("RF_SETUP"),RF_SETUP);
print_byte_register(PSTR("CONFIG"),CONFIG);
print_byte_register(PSTR("DYNPD/FEATURE"),DYNPD,2);
#if defined(__arm__) || defined (RF24_LINUX) || defined (__ARDUINO_X86__) || defined(LITTLEWIRE)
printf_P(PSTR("Data Rate\t = %s\r\n"),pgm_read_word(&rf24_datarate_e_str_P[getDataRate()]));
printf_P(PSTR("Model\t\t = %s\r\n"),pgm_read_word(&rf24_model_e_str_P[isPVariant()]));
printf_P(PSTR("CRC Length\t = %s\r\n"),pgm_read_word(&rf24_crclength_e_str_P[getCRCLength()]));
printf_P(PSTR("PA Power\t = %s\r\n"), pgm_read_word(&rf24_pa_dbm_e_str_P[getPALevel()]));
#else
printf_P(PSTR("Data Rate\t = %S\r\n"), pgm_read_word(&rf24_datarate_e_str_P[getDataRate()]));
printf_P(PSTR("Model\t\t = %S\r\n"), pgm_read_word(&rf24_model_e_str_P[isPVariant()]));
printf_P(PSTR("CRC Length\t = %S\r\n"),pgm_read_word(&rf24_crclength_e_str_P[getCRCLength()]));
printf_P(PSTR("PA Power\t = %S\r\n"), pgm_read_word(&rf24_pa_dbm_e_str_P[getPALevel()]));
#endif
}
#endif
/****************************************************************************/
void RF24::begin(void)
{
#if defined(RF24_LINUX)
// Init BCM2835 chipset for talking with us
if (!bcm2835_init()){
return;
}
switch(csn_pin){ //Ensure valid hardware CS pin
case 0: break;
case 1: break;
case 8: csn_pin = 0; break;
case 7: csn_pin = 1; break;
default: csn_pin = 0; break;
}
bcm2835_spi_begin();
// Initialise the CE pin of NRF24 (chip enable) after the CSN pin, so that
// The input mode is not changed if using one of the hardware CE pins
bcm2835_gpio_fsel(ce_pin, BCM2835_GPIO_FSEL_OUTP);
ce(LOW);
delay(100);
#elif defined(LITTLEWIRE)
pinMode(csn_pin,OUTPUT);
_SPI.begin();
csn(HIGH);
#else
// Initialize pins
if (ce_pin != csn_pin) pinMode(ce_pin,OUTPUT);
#if defined(__arm__) && ! defined( CORE_TEENSY )
_SPI.begin(csn_pin); // Using the extended SPI features of the DUE
_SPI.setClockDivider(csn_pin, 11); // Set the bus speed to just under 8mhz on Due
_SPI.setBitOrder(csn_pin,MSBFIRST); // Set the bit order and mode specific to this device
_SPI.setDataMode(csn_pin,SPI_MODE0);
ce(LOW);
//csn(HIGH);
#else
#if ! defined(LITTLEWIRE)
if (ce_pin != csn_pin)
#endif
pinMode(csn_pin,OUTPUT);
_SPI.begin();
ce(LOW);
csn(HIGH);
#if defined (__ARDUINO_X86__)
delay(100);
#endif
#endif
#endif //Linux
// Must allow the radio time to settle else configuration bits will not necessarily stick.
// This is actually only required following power up but some settling time also appears to
// be required after resets too. For full coverage, we'll always assume the worst.
// Enabling 16b CRC is by far the most obvious case if the wrong timing is used - or skipped.
// Technically we require 4.5ms + 14us as a worst case. We'll just call it 5ms for good measure.
// WARNING: Delay is based on P-variant whereby non-P *may* require different timing.
delay( 5 ) ;
// Reset CONFIG and enable 16-bit CRC.
write_register( CONFIG, 0b00001100 ) ;
// Set 1500uS (minimum for 32B payload in ESB@250KBPS) timeouts, to make testing a little easier
// WARNING: If this is ever lowered, either 250KBS mode with AA is broken or maximum packet
// sizes must never be used. See documentation for a more complete explanation.
setRetries(5,15);
// Reset value is MAX
//setPALevel( RF24_PA_MAX ) ;
// Determine if this is a p or non-p RF24 module and then
// reset our data rate back to default value. This works
// because a non-P variant won't allow the data rate to
// be set to 250Kbps.
if( setDataRate( RF24_250KBPS ) )
{
p_variant = true ;
}
// Then set the data rate to the slowest (and most reliable) speed supported by all
// hardware.
setDataRate( RF24_1MBPS ) ;
// Initialize CRC and request 2-byte (16bit) CRC
//setCRCLength( RF24_CRC_16 ) ;
// Disable dynamic payloads, to match dynamic_payloads_enabled setting - Reset value is 0
toggle_features();
write_register(FEATURE,0 );
write_register(DYNPD,0);
// Reset current status
// Notice reset and flush is the last thing we do
write_register(STATUS,_BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT) );
// Set up default configuration. Callers can always change it later.
// This channel should be universally safe and not bleed over into adjacent
// spectrum.
setChannel(76);
// Flush buffers
flush_rx();
flush_tx();
powerUp(); //Power up by default when begin() is called
// Enable PTX, do not write CE high so radio will remain in standby I mode ( 130us max to transition to RX or TX instead of 1500us from powerUp )
// PTX should use only 22uA of power
write_register(CONFIG, ( read_register(CONFIG) ) & ~_BV(PRIM_RX) );
}
/****************************************************************************/
void RF24::startListening(void)
{
#if !defined (RF24_TINY) && ! defined(LITTLEWIRE)
powerUp();
#endif
write_register(CONFIG, read_register(CONFIG) | _BV(PRIM_RX));
write_register(STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT) );
ce(HIGH);
// Restore the pipe0 adddress, if exists
if (pipe0_reading_address[0] > 0){
write_register(RX_ADDR_P0, pipe0_reading_address, addr_width);
}else{
closeReadingPipe(0);
}
// Flush buffers
//flush_rx();
if(read_register(FEATURE) & _BV(EN_ACK_PAY)){
flush_tx();
}
// Go!
//delayMicroseconds(100);
}
/****************************************************************************/
static const uint8_t child_pipe_enable[] PROGMEM =
{
ERX_P0, ERX_P1, ERX_P2, ERX_P3, ERX_P4, ERX_P5
};
void RF24::stopListening(void)
{
ce(LOW);
delayMicroseconds(txRxDelay);
if(read_register(FEATURE) & _BV(EN_ACK_PAY)){
delayMicroseconds(txRxDelay); //200
flush_tx();
}
//flush_rx();
write_register(CONFIG, ( read_register(CONFIG) ) & ~_BV(PRIM_RX) );
#if defined (RF24_TINY) || defined (LITTLEWIRE)
// for 3 pins solution TX mode is only left with additonal powerDown/powerUp cycle
if (ce_pin == csn_pin) {
powerDown();
powerUp();
}
#endif
write_register(EN_RXADDR,read_register(EN_RXADDR) | _BV(pgm_read_byte(&child_pipe_enable[0]))); // Enable RX on pipe0
//delayMicroseconds(100);
}
/****************************************************************************/
void RF24::powerDown(void)
{
ce(LOW); // Guarantee CE is low on powerDown
write_register(CONFIG,read_register(CONFIG) & ~_BV(PWR_UP));
}
/****************************************************************************/
//Power up now. Radio will not power down unless instructed by MCU for config changes etc.
void RF24::powerUp(void)
{
uint8_t cfg = read_register(CONFIG);
// if not powered up then power up and wait for the radio to initialize
if (!(cfg & _BV(PWR_UP))){
write_register(CONFIG,read_register(CONFIG) | _BV(PWR_UP));
// For nRF24L01+ to go from power down mode to TX or RX mode it must first pass through stand-by mode.
// There must be a delay of Tpd2stby (see Table 16.) after the nRF24L01+ leaves power down mode before
// the CEis set high. - Tpd2stby can be up to 5ms per the 1.0 datasheet
delay(5);
}
}
/******************************************************************/
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
void RF24::errNotify(){
#if defined (SERIAL_DEBUG) || defined (RF24_LINUX)
printf_P(PSTR("RF24 HARDWARE FAIL: Radio not responding, verify pin connections, wiring, etc.\r\n"));
#endif
#if defined (FAILURE_HANDLING)
failureDetected = 1;
#else
delay(5000);
#endif
}
#endif
/******************************************************************/
//Similar to the previous write, clears the interrupt flags
bool RF24::write( const void* buf, uint8_t len, const bool multicast )
{
//Start Writing
startFastWrite(buf,len,multicast);
//Wait until complete or failed
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
uint32_t timer = millis();
#endif
while( ! ( get_status() & ( _BV(TX_DS) | _BV(MAX_RT) ))) {
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
if(millis() - timer > 85){
errNotify();
#if defined (FAILURE_HANDLING)
return 0;
#else
delay(100);
#endif
}
#endif
}
ce(LOW);
uint8_t status = write_register(STATUS,_BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT) );
//Max retries exceeded
if( status & _BV(MAX_RT)){
flush_tx(); //Only going to be 1 packet int the FIFO at a time using this method, so just flush
return 0;
}
//TX OK 1 or 0
return 1;
}
bool RF24::write( const void* buf, uint8_t len ){
return write(buf,len,0);
}
/****************************************************************************/
//For general use, the interrupt flags are not important to clear
bool RF24::writeBlocking( const void* buf, uint8_t len, uint32_t timeout )
{
//Block until the FIFO is NOT full.
//Keep track of the MAX retries and set auto-retry if seeing failures
//This way the FIFO will fill up and allow blocking until packets go through
//The radio will auto-clear everything in the FIFO as long as CE remains high
uint32_t timer = millis(); //Get the time that the payload transmission started
while( ( get_status() & ( _BV(TX_FULL) ))) { //Blocking only if FIFO is full. This will loop and block until TX is successful or timeout
if( get_status() & _BV(MAX_RT)){ //If MAX Retries have been reached
reUseTX(); //Set re-transmit and clear the MAX_RT interrupt flag
if(millis() - timer > timeout){ return 0; } //If this payload has exceeded the user-defined timeout, exit and return 0
}
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
if(millis() - timer > (timeout+85) ){
errNotify();
#if defined (FAILURE_HANDLING)
return 0;
#endif
}
#endif
}
//Start Writing
startFastWrite(buf,len,0); //Write the payload if a buffer is clear
return 1; //Return 1 to indicate successful transmission
}
/****************************************************************************/
void RF24::reUseTX(){
write_register(STATUS,_BV(MAX_RT) ); //Clear max retry flag
spiTrans( REUSE_TX_PL );
ce(LOW); //Re-Transfer packet
ce(HIGH);
}
/****************************************************************************/
bool RF24::writeFast( const void* buf, uint8_t len, const bool multicast )
{
//Block until the FIFO is NOT full.
//Keep track of the MAX retries and set auto-retry if seeing failures
//Return 0 so the user can control the retrys and set a timer or failure counter if required
//The radio will auto-clear everything in the FIFO as long as CE remains high
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
uint32_t timer = millis();
#endif
while( ( get_status() & ( _BV(TX_FULL) ))) { //Blocking only if FIFO is full. This will loop and block until TX is successful or fail
if( get_status() & _BV(MAX_RT)){
//reUseTX(); //Set re-transmit
write_register(STATUS,_BV(MAX_RT) ); //Clear max retry flag
return 0; //Return 0. The previous payload has been retransmitted
//From the user perspective, if you get a 0, just keep trying to send the same payload
}
#if defined (FAILURE_HANDLING) || defined (RF24_LINUX)
if(millis() - timer > 85 ){
errNotify();
#if defined (FAILURE_HANDLING)
return 0;
#endif
}
#endif
}
//Start Writing
startFastWrite(buf,len,multicast);
return 1;
}
bool RF24::writeFast( const void* buf, uint8_t len ){
return writeFast(buf,len,0);
}
/****************************************************************************/
//Per the documentation, we want to set PTX Mode when not listening. Then all we do is write data and set CE high
//In this mode, if we can keep the FIFO buffers loaded, packets will transmit immediately (no 130us delay)
//Otherwise we enter Standby-II mode, which is still faster than standby mode
//Also, we remove the need to keep writing the config register over and over and delaying for 150 us each time if sending a stream of data
void RF24::startFastWrite( const void* buf, uint8_t len, const bool multicast, bool startTx){ //TMRh20
//write_payload( buf,len);
write_payload( buf, len,multicast ? W_TX_PAYLOAD_NO_ACK : W_TX_PAYLOAD ) ;
if(startTx){
ce(HIGH);
}
}
/****************************************************************************/
//Added the original startWrite back in so users can still use interrupts, ack payloads, etc
//Allows the library to pass all tests
void RF24::startWrite( const void* buf, uint8_t len, const bool multicast ){
// Send the payload
//write_payload( buf, len );
write_payload( buf, len,multicast? W_TX_PAYLOAD_NO_ACK : W_TX_PAYLOAD ) ;
ce(HIGH);
#if defined(CORE_TEENSY) || !defined(ARDUINO)
delayMicroseconds(10);
#endif
ce(LOW);
}
/****************************************************************************/
bool RF24::rxFifoFull(){
return read_register(FIFO_STATUS) & _BV(RX_FULL);
}
/****************************************************************************/
bool RF24::txStandBy(){