-
-
Notifications
You must be signed in to change notification settings - Fork 37
/
RC_Transmitter.ino
1227 lines (1029 loc) · 41 KB
/
RC_Transmitter.ino
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
// Micro RC Project. A tiny little 2.4GHz and LEGO "Power Functions" / "MECCANO" IR RC transmitter!
// 3.3V, 8MHz Pro Mini
// STM32F103C8T6 ARM version see: https://github.com/TheDIYGuy999/RC_Transmitter_STM32
// 2.4GHz NRF24L01 radio module
// SSD 1306 128 x 63 0.96" OLED
// Custom PCB from OSH Park
// Menu for the following adjustments:
// -Channel reversing
// -Channel travel limitation adjustable in steps of 5%
// -Value changes are stored in EEPROM, individually per vehicle
// Radio transmitter tester included (press "Select" button during power up)
// NRF24L01+PA+LNA SMA radio modules with power amplifier are supported from board version 1.1
// ATARI PONG game :-) Press the "Back" button during power on to start it
const float codeVersion = 2.51; // Software revision
//
// =======================================================================================================
// BUILD OPTIONS (comment out unneeded options)
// =======================================================================================================
//
//#define DEBUG // if not commented out, Serial.print() is active! For debugging only!!
//#define OLED_DEBUG // if not commented out, an additional diagnostics screen is shown during startup
//
// =======================================================================================================
// INCLUDE LIRBARIES & TABS
// =======================================================================================================
//
// Libraries
#include <SPI.h>
#include <RF24.h> // Installed via Sketch > Include Library > Manage Libraries > Type "RF24" (use V1.3.3!)
#include <printf.h>
#include <EEPROMex.h> // https://github.com/thijse/Arduino-EEPROMEx
#include <LegoIr.h> // https://github.com/TheDIYGuy999/LegoIr
#include <statusLED.h> // https://github.com/TheDIYGuy999/statusLED
#include <U8glib.h> // Installed via Sketch > Include Library > Manage Libraries > Type "U8glib"
// Tabs
#include "transmitterConfig.h"
// More tabs (.h files in the sketch directory) see further down
//
// =======================================================================================================
// PIN ASSIGNMENTS & GLOBAL VARIABLES
// =======================================================================================================
//
// Is the radio or IR transmission mode active?
byte transmissionMode = 1; // Radio mode is active by default
// Select trannsmitter operation mode
byte operationMode = 0; // Start in transmitter mode (0 = transmitter mode, 1 = tester mode, 2 = game mode)
// Vehicle address
int vehicleNumber = 1; // Vehicle number one is active by default
// Radio channels (126 channels are supported)
byte chPointer = 0; // Channel 1 (the first entry of the array) is active by default
const byte NRFchannel[] {
1, 2
};
// the ID number of the used "radio pipe" must match with the selected ID on the transmitter!
// 20 ID's are available @ the moment
const uint64_t pipeOut[] PROGMEM = {
0xE9E8F0F0B1LL, 0xE9E8F0F0B2LL, 0xE9E8F0F0B3LL, 0xE9E8F0F0B4LL, 0xE9E8F0F0B5LL,
0xE9E8F0F0B6LL, 0xE9E8F0F0B7LL, 0xE9E8F0F0B8LL, 0xE9E8F0F0B9LL, 0xE9E8F0F0B0LL,
0xE9E8F0F0C1LL, 0xE9E8F0F0C2LL, 0xE9E8F0F0C3LL, 0xE9E8F0F0C4LL, 0xE9E8F0F0C5LL,
0xE9E8F0F0C6LL, 0xE9E8F0F0C7LL, 0xE9E8F0F0C8LL, 0xE9E8F0F0C9LL, 0xE9E8F0F0C0LL
};
const int maxVehicleNumber = (sizeof(pipeOut) / (sizeof(uint64_t)));
// Hardware configuration: Set up nRF24L01 radio on hardware SPI bus & pins 7 (CE) & 8 (CSN)
RF24 radio(7, 8);
// The size of this struct should not exceed 32 bytes
struct RcData {
byte axis1; // Aileron (Steering for car)
byte axis2; // Elevator
byte axis3; // Throttle
byte axis4; // Rudder
boolean mode1 = false; // Mode1 (toggle speed limitation)
boolean mode2 = false; // Mode2 (toggle acc. / dec. limitation)
boolean momentary1 = false; // Momentary push button
byte pot1; // Potentiometer
};
RcData data;
// This struct defines data, which are embedded inside the ACK payload
struct ackPayload {
float vcc; // vehicle vcc voltage
float batteryVoltage; // vehicle battery voltage
boolean batteryOk; // the vehicle battery voltage is OK!
byte channel = 1; // the channel number
};
ackPayload payload;
// Did the receiver acknowledge the sent data?
boolean transmissionState;
// LEGO powerfunctions IR
LegoIr pf;
int pfChannel;
const int pfMaxAddress = 3;
// TX voltages
boolean batteryOkTx = false;
#define BATTERY_DETECT_PIN A7 // The 20k & 10k battery detection voltage divider is connected to pin A7
float txVcc;
float txBatt;
//Joystick reversing
boolean joystickReversed[maxVehicleNumber + 1][4] = { // 1 + 10 Vehicle Addresses, 4 Servos
{false, false, false, false}, // Address 0 used for EEPROM initialisation
{false, false, false, false}, // Address 1
{false, false, false, false}, // Address 2
{false, false, false, false}, // Address 3
{false, false, false, false}, // Address 4
{false, false, false, false}, // Address 5
{false, false, false, false}, // Address 6
{false, false, false, false}, // Address 7
{false, false, false, false}, // Address 8
{false, false, false, false}, // Address 9
{false, false, false, false}, // Address 10
};
//Joystick percent negative
byte joystickPercentNegative[maxVehicleNumber + 1][4] = { // 1 + 10 Vehicle Addresses, 4 Servos
{100, 100, 100, 100}, // Address 0 not used
{100, 100, 100, 100}, // Address 1
{100, 100, 100, 100}, // Address 2
{100, 100, 100, 100}, // Address 3
{100, 100, 100, 100}, // Address 4
{100, 100, 100, 100}, // Address 5
{100, 100, 100, 100}, // Address 6
{100, 100, 100, 100}, // Address 7
{100, 100, 100, 100}, // Address 8
{100, 100, 100, 100}, // Address 9
{100, 100, 100, 100}, // Address 10
};
//Joystick percent positive
byte joystickPercentPositive[maxVehicleNumber + 1][4] = { // 1 + 10 Vehicle Addresses, 4 Channels
{100, 100, 100, 100}, // Address 0 not used
{100, 100, 100, 100}, // Address 1
{100, 100, 100, 100}, // Address 2
{100, 100, 100, 100}, // Address 3
{100, 100, 100, 100}, // Address 4
{100, 100, 100, 100}, // Address 5
{100, 100, 100, 100}, // Address 6
{100, 100, 100, 100}, // Address 7
{100, 100, 100, 100}, // Address 8
{100, 100, 100, 100}, // Address 9
{100, 100, 100, 100}, // Address 10
};
// Joysticks
#define JOYSTICK_1 A1
#define JOYSTICK_2 A0
#define JOYSTICK_3 A3
#define JOYSTICK_4 A2
// Joystick push buttons
#define JOYSTICK_BUTTON_LEFT 4
#define JOYSTICK_BUTTON_RIGHT 2
byte leftJoystickButtonState;
byte rightJoystickButtonState;
// Buttons
#define BUTTON_LEFT 1 // - or channel select
#define BUTTON_RIGHT 10 // + or transmission mode select
#define BUTTON_SEL 0 // select button for menu
#define BUTTON_BACK 9 // back button for menu
byte leftButtonState = 7; // init states with 7 (see macro below)!
byte rightButtonState = 7;
byte selButtonState = 7;
byte backButtonState = 7;
// macro for detection of rising edge and debouncing
/*the state argument (which must be a variable) records the current and the last 3 reads
by shifting one bit to the left at each read and bitwise anding with 15 (=0b1111).
If the value is 7(=0b0111) we have one raising edge followed by 3 consecutive 1's.
That would qualify as a debounced raising edge*/
#define DRE(signal, state) (state=(state<<1)|(signal&1)&15)==7
// Status LED objects (false = logic not inverted)
#ifdef ledInversed // inversed logic
statusLED greenLED(true); // green: ON = transmitter ON, flashing = Communication with vehicle OK
statusLED redLED(true); // red: ON = battery empty
#endif
#ifndef ledInversed // not inversed logic
statusLED greenLED(false); // green: ON = transmitter ON, flashing = Communication with vehicle OK
statusLED redLED(false); // red: ON = battery empty
#endif
// OLED display. Select the one you have! Otherwise sthe sreen could be slightly offset sideways!
//U8GLIB_SH1106_128X64 u8g(U8G_I2C_OPT_FAST); // I2C / TWI FAST instead of NONE = 400kHz I2C!
U8GLIB_SSD1306_128X64 u8g(U8G_I2C_OPT_FAST); // I2C / TWI FAST instead of NONE = 400kHz I2C!
int activeScreen = 0; // the currently displayed screen number (0 = splash screen)
boolean displayLocked = true;
byte menuRow = 0; // Menu active cursor line
// EEPROM (max. total size is 512 bytes)
// Always get the adresses first and in the same order
// Blocks of 21 x 4 bytes = 84 bytes each!
int addressReverse = EEPROM.getAddress(sizeof(byte) * 84);
int addressNegative = EEPROM.getAddress(sizeof(byte) * 84);
int addressPositive = EEPROM.getAddress(sizeof(byte) * 84);
//
// =======================================================================================================
// INCLUDE TABS (header files in sketch directory)
// =======================================================================================================
//
// Tabs (header files in sketch directory)
#include "readVCC.h"
//#include "transmitterConfig.h"
#include "MeccanoIr.h" // https://github.com/TheDIYGuy999/MeccanoIr
#include "pong.h" // A little pong game :-)
#include "pgmRead64.h" // Read 64 bit blocks from PROGMEM
//
// =======================================================================================================
// RADIO SETUP
// =======================================================================================================
//
void setupRadio() {
radio.begin();
radio.setChannel(NRFchannel[chPointer]);
radio.powerUp();
// Set Power Amplifier (PA) level to one of four levels: RF24_PA_MIN, RF24_PA_LOW, RF24_PA_HIGH and RF24_PA_MAX
if (boardVersion < 1.1 ) radio.setPALevel(RF24_PA_MIN); // No independent NRF24L01 3.3V PSU, so only "MIN" transmission level allowed
else radio.setPALevel(RF24_PA_MAX); // Independent NRF24L01 3.3V PSU, so "FULL" transmission level allowed
radio.setDataRate(RF24_250KBPS);
//radio.setAutoAck(pipeOut[vehicleNumber - 1], true); // Ensure autoACK is enabled
radio.setAutoAck(pgm_read_64(&pipeOut, vehicleNumber - 1), true); // Ensure autoACK is enabled
radio.enableAckPayload();
radio.enableDynamicPayloads();
radio.setRetries(5, 5); // 5x250us delay (blocking!!), max. 5 retries
//radio.setCRCLength(RF24_CRC_8); // Use 8-bit CRC for performance*/
#ifdef DEBUG
radio.printDetails();
delay(1800);
#endif
// All axes to neutral position
data.axis1 = 50;
data.axis2 = 50;
data.axis3 = 50;
data.axis4 = 50;
// Transmitter
if (operationMode == 0) {
//radio.openWritingPipe(pipeOut[vehicleNumber - 1]); // Vehicle Number 1 = Array number 0, so -1!
radio.openWritingPipe(pgm_read_64(&pipeOut, vehicleNumber - 1)); // Vehicle Number 1 = Array number 0, so -1!
radio.write(&data, sizeof(RcData));
}
// Receiver (radio tester mode)
if (operationMode == 1) {
//radio.openReadingPipe(1, pipeOut[vehicleNumber - 1]);
radio.openReadingPipe(1, pgm_read_64(&pipeOut, vehicleNumber - 1));
radio.startListening();
}
}
//
// =======================================================================================================
// LEGO POWERFUNCTIONS SETUP
// =======================================================================================================
//
void setupPowerfunctions() {
pfChannel = vehicleNumber - 1; // channel 0 - 3 is labelled as 1 - 4 on the LEGO devices!
if (pfChannel > pfMaxAddress) pfChannel = pfMaxAddress;
pf.begin(3, pfChannel); // Pin 3, channel 0 - 3
}
//
// =======================================================================================================
// MAIN ARDUINO SETUP (1x during startup)
// =======================================================================================================
//
void setup() {
#ifdef DEBUG
Serial.begin(115200);
printf_begin();
delay(3000);
#endif
// LED setup
greenLED.begin(6); // Green LED on pin 5
redLED.begin(5); // Red LED on pin 6
// Pinmodes (all other pinmodes are handled inside libraries)
pinMode(JOYSTICK_BUTTON_LEFT, INPUT_PULLUP);
pinMode(JOYSTICK_BUTTON_RIGHT, INPUT_PULLUP);
pinMode(BUTTON_LEFT, INPUT_PULLUP);
pinMode(BUTTON_RIGHT, INPUT_PULLUP);
pinMode(BUTTON_SEL, INPUT_PULLUP);
pinMode(BUTTON_BACK, INPUT_PULLUP);
// EEPROM setup
EEPROM.readBlock(addressReverse, joystickReversed); // restore all arrays from the EEPROM
EEPROM.readBlock(addressNegative, joystickPercentNegative);
EEPROM.readBlock(addressPositive, joystickPercentPositive);
if (joystickReversed[0][0] || (!digitalRead(BUTTON_BACK) && !digitalRead(BUTTON_SEL))) { // 255 is EEPROM default after a program download,
// this indicates that we have to initialise the EEPROM with our default values! Or manually triggered with
// both "SEL" & "BACK" buttons pressed during switching on!
memset(joystickReversed, 0, sizeof(joystickReversed)); // init arrays first
memset(joystickPercentNegative, 100, sizeof(joystickPercentNegative));
memset(joystickPercentPositive, 100, sizeof(joystickPercentPositive));
EEPROM.updateBlock(addressReverse, joystickReversed); // then write defaults to EEPROM
EEPROM.updateBlock(addressNegative, joystickPercentNegative);
EEPROM.updateBlock(addressPositive, joystickPercentPositive);
}
// Switch to radio tester mode, if "Select" button is pressed
if (digitalRead(BUTTON_BACK) && !digitalRead(BUTTON_SEL)) {
operationMode = 1;
}
// Switch to game mode, if "Back" button is pressed
if (!digitalRead(BUTTON_BACK) && digitalRead(BUTTON_SEL)) {
operationMode = 2;
}
// Joystick setup
JoystickOffset(); // Compute all joystick center points
readJoysticks(); // Then do the first jocstick read
// Radio setup
setupRadio();
// LEGO Powerfunctions setup
setupPowerfunctions();
// Display setup
u8g.setFontRefHeightExtendedText();
u8g.setDefaultForegroundColor();
u8g.setFontPosTop();
u8g.setFont(u8g_font_6x10);
// Splash screen
checkBattery();
activeScreen = 0; // 0 = splash screen active
drawDisplay();
#ifdef OLED_DEBUG
activeScreen = 100; // switch to the diagnostics screen
delay(1500);
drawDisplay();
#endif
activeScreen = 1; // switch to the main screen
delay(1500);
}
//
// =======================================================================================================
// BUTTONS
// =======================================================================================================
//
// Sub function for channel travel adjustment and limitation --------------------------------------
void travelAdjust(boolean upDn) {
byte inc = 5;
if (upDn) inc = 5; // Direction +
else inc = -5; // -
if ( (menuRow & 0x01) == 0) { // even (2nd column)
joystickPercentPositive[vehicleNumber][(menuRow - 6) / 2 ] += inc; // row 6 - 12 = 0 - 3
}
else { // odd (1st column)
joystickPercentNegative[vehicleNumber][(menuRow - 5) / 2 ] += inc; // row 5 - 11 = 0 - 3
}
joystickPercentPositive[vehicleNumber][(menuRow - 6) / 2 ] = constrain(joystickPercentPositive[vehicleNumber][(menuRow - 6) / 2 ], 20, 100);
joystickPercentNegative[vehicleNumber][(menuRow - 5) / 2 ] = constrain(joystickPercentNegative[vehicleNumber][(menuRow - 5) / 2 ], 20, 100);
}
// Main buttons function --------------------------------------------------------------------------
void readButtons() {
// Every 10 ms
static unsigned long lastTrigger;
if (millis() - lastTrigger >= 10) {
lastTrigger = millis();
// Left joystick button (Mode 1)
if (DRE(digitalRead(JOYSTICK_BUTTON_LEFT), leftJoystickButtonState) && (transmissionMode == 1)) {
data.mode1 = !data.mode1;
drawDisplay();
}
// Right joystick button (Mode 2)
if (DRE(digitalRead(JOYSTICK_BUTTON_RIGHT), rightJoystickButtonState) && (transmissionMode == 1)) {
data.mode2 = !data.mode2;
drawDisplay();
}
if (activeScreen <= 10) { // if menu is not displayed ----------
// Left button: Channel selection +
if (DRE(digitalRead(BUTTON_LEFT), leftButtonState) && (transmissionMode < 3)) {
vehicleNumber ++;
if (vehicleNumber > maxVehicleNumber) vehicleNumber = 1;
setupRadio(); // Re-initialize the radio with the new pipe address
setupPowerfunctions(); // Re-initialize the LEGO IR transmitter with the new channel address
drawDisplay();
}
// Right button: Change transmission mode. Radio <> IR
if (infrared) { // only, if transmitter has IR option
if (DRE(digitalRead(BUTTON_RIGHT), rightButtonState)) {
if (transmissionMode < 3) transmissionMode ++;
else {
transmissionMode = 1;
setupRadio(); // Re-initialize radio, if we switch back to radio mode!
}
drawDisplay();
}
}
else { // only, if transmitter has no IR option
// Right button: Channel selection -
if (DRE(digitalRead(BUTTON_RIGHT), rightButtonState) && (transmissionMode < 3)) {
vehicleNumber --;
if (vehicleNumber < 1) vehicleNumber = maxVehicleNumber;
setupRadio(); // Re-initialize the radio with the new pipe address
setupPowerfunctions(); // Re-initialize the LEGO IR transmitter with the new channel address
drawDisplay();
}
}
}
else { // if menu is displayed -----------
// Right button: Value -
if (DRE(digitalRead(BUTTON_RIGHT), rightButtonState)) {
if (activeScreen == 11) {
joystickReversed[vehicleNumber][menuRow - 1] = false;
}
if (activeScreen == 12) {
travelAdjust(false); // -
}
drawDisplay();
}
// Left button: Value +
if (DRE(digitalRead(BUTTON_LEFT), leftButtonState)) {
if (activeScreen == 11) {
joystickReversed[vehicleNumber][menuRow - 1] = true;
}
if (activeScreen == 12) {
travelAdjust(true); // +
}
drawDisplay();
}
}
// Menu buttons:
// Select button: opens the menu and scrolls through menu entries
if (DRE(digitalRead(BUTTON_SEL), selButtonState) && (transmissionMode == 1)) {
activeScreen = 11; // 11 = Menu screen 1
menuRow ++;
if (menuRow > 4) activeScreen = 12; // 12 = Menu screen 2
if (menuRow > 12) {
activeScreen = 11; // Back to menu 1, entry 1
menuRow = 1;
}
drawDisplay();
}
// Back / Momentary button:
if (activeScreen <= 10) { // Momentary button, if menu is NOT displayed
if (!digitalRead(BUTTON_BACK)) data.momentary1 = true;
else data.momentary1 = false;
}
else { // Goes back to the main screen & saves the changed entries in the EEPROM
if (DRE(digitalRead(BUTTON_BACK), backButtonState)) {
activeScreen = 1; // 1 = Main screen
menuRow = 0;
drawDisplay();
EEPROM.updateBlock(addressReverse, joystickReversed); // update changed values in EEPROM
EEPROM.updateBlock(addressNegative, joystickPercentNegative);
EEPROM.updateBlock(addressPositive, joystickPercentPositive);
}
}
}
}
//
// =======================================================================================================
// JOYSTICKS
// =======================================================================================================
//
int offset[4]; // the auto calibration offset of each joystick
// Auto-zero subfunction (called during setup, if a pot and no 3 position switch is connected) ----
void JoystickOffset() {
#ifndef CH1Switch
offset[0] = 512 - analogRead(JOYSTICK_1);
#endif
#ifndef CH2Switch
offset[1] = 512 - analogRead(JOYSTICK_2);
#endif
#ifndef CH3Switch
offset[2] = 512 - analogRead(JOYSTICK_3);
#endif
#ifndef CH4Switch
offset[3] = 512 - analogRead(JOYSTICK_4);
#endif
}
// Mapping and reversing subfunction ----
byte mapJoystick(byte input, byte arrayNo) {
int reading[4];
reading[arrayNo] = analogRead(input) + offset[arrayNo]; // read joysticks and add the offset
reading[arrayNo] = constrain(reading[arrayNo], (1023 - range[arrayNo]), range[arrayNo]); // then limit the result before we do more calculations below
#ifndef CONFIG_4_CH // In most "car style" transmitters, less than one half of the throttle potentiometer range is used for the reverse. So we have to enhance this range!
if (reading[2] < (range[2] / 2) ) {
reading[2] = constrain(reading[2], reverseEndpoint, (range[2] / 2)); // limit reverse range, which will be mapped later on
reading[2] = map(reading[2], reverseEndpoint, (range[2] / 2), 0, (range[2] / 2)); // reverse range mapping (adjust reverse endpoint in transmitterConfig.h)
}
#endif
if (transmissionMode == 1 && operationMode != 2 ) { // Radio mode and not game mode
if (joystickReversed[vehicleNumber][arrayNo]) { // reversed
return map(reading[arrayNo], (1023 - range[arrayNo]), range[arrayNo], (joystickPercentPositive[vehicleNumber][arrayNo] / 2 + 50), (50 - joystickPercentNegative[vehicleNumber][arrayNo] / 2));
}
else { // not reversed
return map(reading[arrayNo], (1023 - range[arrayNo]), range[arrayNo], (50 - joystickPercentNegative[vehicleNumber][arrayNo] / 2), (joystickPercentPositive[vehicleNumber][arrayNo] / 2 + 50));
}
}
else { // IR mode
return map(reading[arrayNo], (1023 - range[arrayNo]), range[arrayNo], 0, 100);
}
}
// Main Joystick function ----
void readJoysticks() {
// save previous joystick positions
byte previousAxis1 = data.axis1;
byte previousAxis2 = data.axis2;
byte previousAxis3 = data.axis3;
byte previousAxis4 = data.axis4;
// Read current joystick positions, then scale and reverse output signals, if necessary (only for the channels we have)
#ifdef CH1
data.axis1 = mapJoystick(JOYSTICK_1, 0); // Aileron (Steering for car)
#endif
#ifdef CH2
data.axis2 = mapJoystick(JOYSTICK_2, 1); // Elevator
#endif
#ifdef CH3
data.axis3 = mapJoystick(JOYSTICK_3, 2); // Throttle
#endif
#ifdef CH4
data.axis4 = mapJoystick(JOYSTICK_4, 3); // Rudder
#endif
// in case of an overflow, set axis to zero (prevent it from overflowing < 0)
if (data.axis1 > 150) data.axis1 = 0;
if (data.axis2 > 150) data.axis2 = 0;
if (data.axis3 > 150) data.axis3 = 0;
if (data.axis4 > 150) data.axis4 = 0;
// Only allow display refresh, if no value has changed!
if (previousAxis1 != data.axis1 ||
previousAxis2 != data.axis2 ||
previousAxis3 != data.axis3 ||
previousAxis4 != data.axis4) {
displayLocked = true;
}
else {
displayLocked = false;
}
}
//
// =======================================================================================================
// POTENTIOMETER
// =======================================================================================================
//
void readPotentiometer() {
data.pot1 = map(analogRead(A6), 0, 1023, 0, 100);
data.pot1 = constrain(data.pot1, 0, 100);
}
//
// =======================================================================================================
// TRANSMIT LEGO POWERFUNCTIONS IR SIGNAL
// =======================================================================================================
//
void transmitLegoIr() {
static byte speedOld[2];
static byte speed[2];
static byte pwm[2];
static unsigned long previousMillis;
unsigned long currentMillis = millis();
// Flash green LED
greenLED.flash(30, 2000, 0, 0);
// store joystick positions into an array-----
speed[0] = data.axis3;
speed[1] = data.axis2;
// compute pwm value for "red" and "blue" motor, if speed has changed more than +/- 3, or every 0.6s
// NOTE: one IR pulse at least every 1.2 s is required in order to prevent the vehivle from stopping
// due to a signal timeout!
for (int i = 0; i <= 1; i++) {
if ((speedOld[i] - 3) > speed[i] || (speedOld[i] + 3) < speed[i] || currentMillis - previousMillis >= 600) {
speedOld[i] = speed[i];
previousMillis = currentMillis;
if (speed[i] >= 0 && speed[i] < 6) pwm[i] = PWM_REV7;
else if (speed[i] >= 6 && speed[i] < 12) pwm[i] = PWM_REV6;
else if (speed[i] >= 12 && speed[i] < 18) pwm[i] = PWM_REV5;
else if (speed[i] >= 18 && speed[i] < 24) pwm[i] = PWM_REV4;
else if (speed[i] >= 24 && speed[i] < 30) pwm[i] = PWM_REV3;
else if (speed[i] >= 30 && speed[i] < 36) pwm[i] = PWM_REV2;
else if (speed[i] >= 36 && speed[i] < 42) pwm[i] = PWM_REV1;
else if (speed[i] >= 42 && speed[i] < 58) pwm[i] = PWM_BRK;
else if (speed[i] >= 58 && speed[i] < 64) pwm[i] = PWM_FWD1;
else if (speed[i] >= 64 && speed[i] < 70) pwm[i] = PWM_FWD2;
else if (speed[i] >= 70 && speed[i] < 76) pwm[i] = PWM_FWD3;
else if (speed[i] >= 76 && speed[i] < 82) pwm[i] = PWM_FWD4;
else if (speed[i] >= 82 && speed[i] < 88) pwm[i] = PWM_FWD5;
else if (speed[i] >= 88 && speed[i] < 94) pwm[i] = PWM_FWD6;
else if (speed[i] >= 94) pwm[i] = PWM_FWD7;
// then transmit IR data
pf.combo_pwm(pwm[1], pwm[0]); // red and blue in one IR package
}
}
}
//
// =======================================================================================================
// TRANSMIT MECCANO / ERECTOR IR SIGNAL
// =======================================================================================================
//
void transmitMeccanoIr() {
static boolean A;
static boolean B;
static boolean C;
static boolean D;
// Flash green LED
greenLED.flash(30, 1000, 0, 0);
// Channel A ----
if (data.axis1 > 90) { // A +
buildIrSignal(1);
A = true;
}
if (data.axis1 < 10) { // A -
buildIrSignal(2), A = true;
A = true;
}
if (data.axis1 < 90 && data.axis1 > 10 && A) { // A OFF
buildIrSignal(3);
A = false;
}
// Channel B ----
if (data.axis2 > 90) { // B +
buildIrSignal(4);
B = true;
}
if (data.axis2 < 10) { // B -
buildIrSignal(5), A = true;
B = true;
}
if (data.axis2 < 90 && data.axis2 > 10 && B) { // B OFF
buildIrSignal(6);
B = false;
}
// Channel C ----
if (data.axis3 > 90) { // C +
buildIrSignal(7);
C = true;
}
if (data.axis3 < 10) { // C -
buildIrSignal(8), A = true;
C = true;
}
if (data.axis3 < 90 && data.axis3 > 10 && C) { // C OFF
buildIrSignal(9);
C = false;
}
// Channel D ----
if (data.axis4 > 90) { // D +
buildIrSignal(10);
D = true;
}
if (data.axis4 < 10) { // D -
buildIrSignal(11), A = true;
D = true;
}
if (data.axis4 < 90 && data.axis4 > 10 && D) { // D OFF
buildIrSignal(12);
D = false;
}
}
//
// =======================================================================================================
// TRANSMIT RADIO DATA
// =======================================================================================================
//
void transmitRadio() {
static boolean previousTransmissionState;
static float previousRxVcc;
static float previousRxVbatt;
static boolean previousBattState;
static unsigned long previousSuccessfulTransmission;
if (transmissionMode == 1) { // If radio mode is active: ----
// Send radio data and check if transmission was successful
if (radio.write(&data, sizeof(struct RcData)) ) {
if (radio.isAckPayloadAvailable()) {
radio.read(&payload, sizeof(struct ackPayload)); // read the payload, if available
previousSuccessfulTransmission = millis();
}
}
// Switch channel for next transmission
chPointer ++;
if (chPointer >= sizeof((*NRFchannel) / sizeof(byte))) chPointer = 0;
radio.setChannel(NRFchannel[chPointer]);
// if the transmission was not confirmed (from the receiver) after > 1s...
if (millis() - previousSuccessfulTransmission > 1000) {
greenLED.on();
transmissionState = false;
memset(&payload, 0, sizeof(payload)); // clear the payload array, if transmission error
#ifdef DEBUG
Serial.println("Data transmission error, check receiver!");
#endif
}
else {
greenLED.flash(30, 100, 0, 0); //30, 100
transmissionState = true;
#ifdef DEBUG
Serial.println("Data successfully transmitted");
#endif
}
if (!displayLocked) { // Only allow display refresh, if not locked ----
// refresh transmission state on the display, if changed
if (transmissionState != previousTransmissionState) {
previousTransmissionState = transmissionState;
drawDisplay();
}
// refresh Rx Vcc on the display, if changed more than +/- 0.05V
if (payload.vcc - 0.05 >= previousRxVcc || payload.vcc + 0.05 <= previousRxVcc) {
previousRxVcc = payload.vcc;
drawDisplay();
}
// refresh Rx V Batt on the display, if changed more than +/- 0.3V
if (payload.batteryVoltage - 0.3 >= previousRxVbatt || payload.batteryVoltage + 0.3 <= previousRxVbatt) {
previousRxVbatt = payload.batteryVoltage;
drawDisplay();
}
// refresh battery state on the display, if changed
if (payload.batteryOk != previousBattState) {
previousBattState = payload.batteryOk;
drawDisplay();
}
}
#ifdef DEBUG
Serial.print(data.axis1);
Serial.print("\t");
Serial.print(data.axis2);
Serial.print("\t");
Serial.print(data.axis3);
Serial.print("\t");
Serial.print(data.axis4);
Serial.print("\t");
Serial.println(F_CPU / 1000000, DEC);
#endif
}
else { // else infrared mode is active: ----
radio.powerDown();
}
}
//
// =======================================================================================================
// READ RADIO DATA (for radio tester mode)
// =======================================================================================================
//
void readRadio() {
static unsigned long lastRecvTime = 0;
byte pipeNo;
payload.batteryVoltage = txBatt; // store the battery voltage for sending
payload.vcc = txVcc; // store the vcc voltage for sending
payload.batteryOk = batteryOkTx; // store the battery state for sending
if (radio.available(&pipeNo)) {
radio.writeAckPayload(pipeNo, &payload, sizeof(struct ackPayload) ); // prepare the ACK payload
radio.read(&data, sizeof(struct RcData)); // read the radia data and send out the ACK payload
lastRecvTime = millis();
#ifdef DEBUG
Serial.print(data.axis1);
Serial.print("\t");
Serial.print(data.axis2);
Serial.print("\t");
Serial.print(data.axis3);
Serial.print("\t");
Serial.print(data.axis4);
Serial.println("\t");
#endif
}
// Switch channel
if (millis() - lastRecvTime > 500) {
chPointer ++;
if (chPointer >= sizeof((*NRFchannel) / sizeof(byte))) chPointer = 0;
radio.setChannel(NRFchannel[chPointer]);
payload.channel = NRFchannel[chPointer];
}
if (millis() - lastRecvTime > 1000) { // set all analog values to their middle position, if no RC signal is received during 1s!
data.axis1 = 50; // Aileron (Steering for car)
data.axis2 = 50; // Elevator
data.axis3 = 50; // Throttle
data.axis4 = 50; // Rudder
payload.batteryOk = true; // Clear low battery alert (allows to re-enable the vehicle, if you switch off the transmitter)
#ifdef DEBUG
Serial.println("No Radio Available - Check Transmitter!");
#endif
}
if (millis() - lastRecvTime > 2000) {
setupRadio(); // re-initialize radio
lastRecvTime = millis();
}
}
//
// =======================================================================================================
// LED
// =======================================================================================================
//
void led() {
// Red LED (ON = battery empty, number of pulses are indicating the vehicle number)
if (batteryOkTx && (payload.batteryOk || transmissionMode > 1 || !transmissionState) ) {
if (transmissionMode == 1) redLED.flash(140, 150, 500, vehicleNumber); // ON, OFF, PAUSE, PULSES
if (transmissionMode == 2) redLED.flash(140, 150, 500, pfChannel + 1); // ON, OFF, PAUSE, PULSES
if (transmissionMode == 3) redLED.off();
} else {
redLED.on(); // Always ON = battery low voltage (Rx or Tx)
}
}
//
// =======================================================================================================
// CHECK TX BATTERY VOLTAGE
// =======================================================================================================
//
void checkBattery() {
// Every 500 ms
static unsigned long lastTrigger;
if (millis() - lastTrigger >= 500) {
lastTrigger = millis();
#if F_CPU == 16000000 // 16MHz / 5V
txBatt = (analogRead(BATTERY_DETECT_PIN) / 68.2) + diodeDrop; // 1023steps / 15V = 68.2 + diode drop!
#else // 8MHz / 3.3V
txBatt = (analogRead(BATTERY_DETECT_PIN) / 103.33) + diodeDrop; // 1023steps / 9.9V = 103.33 + diode drop!
#endif
txVcc = readVcc() / 1000.0 ;
if (txBatt >= cutoffVoltage) {
batteryOkTx = true;
#ifdef DEBUG
Serial.print(txBatt);
Serial.println(" Tx battery OK");
#endif
} else {
batteryOkTx = false;
#ifdef DEBUG
Serial.print(txBatt);
Serial.println(" Tx battery empty!");
#endif
}
}
}
//
// =======================================================================================================
// DRAW DISPLAY
// =======================================================================================================
//
void drawDisplay() {
u8g.firstPage(); // clear screen
do {
switch (activeScreen) {
case 0: // Screen # 0 splash screen-----------------------------------
if (operationMode == 0) u8g.drawStr(3, 10, "Micro RC Transmitter");
if (operationMode == 1) u8g.drawStr(3, 10, "Micro RC Tester");
if (operationMode == 2) u8g.drawStr(3, 10, "Micro PONG");
// Dividing Line
u8g.drawLine(0, 13, 128, 13);
// Software version
u8g.setPrintPos(3, 30);
u8g.print("SW: ");
u8g.print(codeVersion);
// Hardware version
u8g.print(" HW: ");
u8g.print(boardVersion);
u8g.setPrintPos(3, 43);
u8g.print("created by:");
u8g.setPrintPos(3, 55);
u8g.print("TheDIYGuy999");
break;
case 100: // Screen # 100 diagnosis screen-----------------------------------
u8g.drawStr(3, 10, "Joystick readings:");
// Joysticks:
u8g.setPrintPos(3, 30);
u8g.print("Axis 1: ");
u8g.print(data.axis1);
u8g.setPrintPos(3, 40);
u8g.print("Axis 2: ");
u8g.print(data.axis2);
u8g.setPrintPos(3, 50);
u8g.print("Axis 3: ");
u8g.print(data.axis3);
u8g.setPrintPos(3, 60);
u8g.print("Axis 4: ");
u8g.print(data.axis4);
break;
case 1: // Screen # 1 main screen-------------------------------------
// Tester mode ==================
if (operationMode == 1) {
// screen dividing lines ----
u8g.drawLine(0, 12, 128, 12);