-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathControladorLocomotoraRF.ino
1806 lines (1460 loc) · 48.2 KB
/
ControladorLocomotoraRF.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
#include <Arduino.h>
#include "SWLogic.h"
//
// DEF
//
//Set both remote and locomotive to 0 to disable radio
#define REMOTE 1
#define LOCOMOTIVE 0
#define DEBUGA 0 //Debug flag
#define STANDALONE (!REMOTE && !LOCOMOTIVE) //Controller runs on local mode (no radio)
#define RADIO (REMOTE || LOCOMOTIVE) //Radio is connected to the board
#define SABERTOOTH (STANDALONE || LOCOMOTIVE) //Board is directly connected to a Sabertooth controller
//
// SABERTOOTH
//
#if SABERTOOTH
#include <USBSabertooth_NB.h>
USBSabertoothSerial C; // create a SabertoothSerial
USBSabertooth ST(C, 128); // create a Sabertooth
#endif
//
// RADIO
//
#if RADIO
#include <RF24.h>
#define CE_PIN 9
#define CS_PIN 10
RF24 radio(CE_PIN, CS_PIN); // create a Radio
uint8_t remote_address[] = {"remot"}; // define remote identifier
uint8_t locomotive_address1[] = {"loco1"}; // define locomotive identifier
uint8_t locomotive_address2[] = {"moco1"}; // define locomotive identifier (Only the first character must be different between locos)
// NOTE: On the addresses above, the first character (LSB) must be different for each channel,
// the remaining 4 characters must be all equal and they represent an unique communication address
#endif
//
// DISPLAY
//
#define OLED13
//#define OLED24
#ifdef OLED13
#define I2C_ADDRESS 0x3C // 0X3C+SA0 - 0x3C or 0x3D
#endif
#ifdef OLED24
#define I2C_ADDRESS 0x3D // 0X3C+SA0 - 0x3C or 0x3D
#endif
//#include "SSD1306AsciiAvrI2c.h"
//#ifdef SSD1306AsciiAvrI2c_h
//SSD1306AsciiAvrI2c oled; // create a display
//#endif
#include "SSD1306AsciiWire.h"
#ifdef SSD1306AsciiWire_h
SSD1306AsciiWire oled; // create a display
#endif
#include "Verdana_digits_16x24.h"
#include "Symbol_8x8.h"
#include "Symbol_24x24.h"
//
// EEPROM
//
#include <EEPROM.h>
//
// LED
//
#define LEDPIN 18
//
// IO
//
#define IPIN0 4
#define IPIN1 5
#define OPIN0 7
#define OPIN1 8
//
// CHARGER
//
#define BATTCHARGEPIN A7
#define CHARGERPLUGPIN A8
#define BATTCHECKPIN 7
//#define BATTCHARGERPIN 8 // not used
//
// ENCODER
//
#include <Encoder.h>
#define PINA 21
#define PINB 20
#define PINP 19
Encoder encoder( PINA, PINB, PINP ); // create an encoder
//
// SWITCH
//
#define SWPIN 6
bool remoteSwitch = false;
//
// COMMAND
//
//#include "SWCommand.h"
#ifdef SWCommand_H
SWCommand command;
int a=0;
int b=0;
#endif
////////////////////////////////////////////////////////////////////////////////
// GLOBAL DEFS
enum MainMode
{
MainModeNone=0,
MainModeDefault,
MainModeConfig,
};
enum MotorMode
{
MotorModeNone=0,
MotorModeStop,
MotorModeForward,
MotorModeReverse,
MotorModeWait,
};
enum RadioMode
{
RadioModeNone=0,
RadioModeLocal,
RadioModeRemote,
RadioModeRemoteError,
};
enum ConfigMode
{
ConfigModeNone=0,
ConfigModeSelect,
ConfigModeEdit,
};
enum ScreenMode
{
ScreenModeNone=0,
ScreenModeSleep,
ScreenModeDefault,
ScreenModeConfig
};
struct RemoteData
{
int motorSetPoint;
MotorMode motorMode;
byte button0;
byte button1;
RemoteData(byte b, MotorMode m) { memset( this, b, sizeof(*this) ); motorMode=m; }
};
RemoteData md(0,MotorModeStop);
RemoteData dsp_md(0xff,MotorModeNone);
struct LocomotiveData
{
int battery;
int motor1;
int motor2;
int current1;
int current2;
int temperature1;
int temperature2;
LocomotiveData(byte b) { memset( this, b, sizeof(*this) ); }
};
LocomotiveData sd(0);
LocomotiveData dsp_sd(0xff);
struct SelfData
{
MainMode mainMode;
RadioMode radioMode;
ConfigMode configMode;
ScreenMode screenMode;
int battCharge; // only used for remote
bool battIsCharging; // only used for remote
SelfData( MainMode mm, RadioMode sm, ConfigMode cm, ScreenMode scm, int batt, bool isCharging ) :
mainMode(mm), radioMode(sm), configMode(cm), screenMode(scm), battCharge(batt), battIsCharging(isCharging) {};
};
SelfData d( MainModeDefault, RadioModeLocal, ConfigModeSelect, ScreenModeDefault, 100, false );
SelfData dsp_d( MainModeNone, RadioModeNone, ConfigModeNone, ScreenModeNone, 100, false );
//SETTINGS MENU
//TODO: Save configuration into non-volatile memory
//Type of the configuration variables
enum OptionType
{
OptionTypeNone=0,
OptionTypeRotate, // value rotates through the specified range
OptionTypeShift, // value bottoms or tops on the range
};
struct ConfigOption //Data struct for each option
{
OptionType valueType; //Type of the value
int value; //The value of the option itself, stored in an integer (Use 0 and 1 for boolean)
const int minv;
const int maxv;
const char *description; //Option description that will show up in the screen, keep it short to prevent display glitches
const char format; //Size for the printf format string
ConfigOption(OptionType vType, int val, const int mi, const int ma, const char* desc, const char fmt) :
valueType(vType), value(val), minv(mi), maxv(ma), description(desc), format(fmt) {}; //Constructor with parameters for the struct
};
//Declare options
ConfigOption radioChannel (OptionTypeRotate, 80, 0, 125, "Canal Radio", '3');
ConfigOption channelAddress (OptionTypeRotate, '1', 0, 250, "Addreca", '3');
ConfigOption radioPALevel (OptionTypeShift, 1, 0, 3, "Potenc Radio",'1');
ConfigOption activeBraking (OptionTypeShift, 0, 0, 1, "Fre Motor", '1'); // TO DO: Make it work !
ConfigOption maxBarCurrent (OptionTypeShift, 20, 0, 32, "Max Ampers", '2');
ConfigOption maxSpeedForward (OptionTypeShift, 100, 0, 100, "Max Endavant",'3');
ConfigOption maxSpeedReverse (OptionTypeShift, 100, 0, 100, "Max Enrera", '3');
#if !REMOTE
ConfigOption speedLimit (OptionTypeShift, 100, 0, 100, "Limit Veloc", '3');
#endif
ConfigOption naturalControl (OptionTypeShift, 0, 0, 1, "Ctrl Natural",'1');
// ConfigOption dummyDisplay3 (OptionTypeShift, 20, 0, 32, "Dummy3", '3');
// ConfigOption dummyDisplay4 (OptionTypeShift, 20, 0, 32, "Dummy4", '3');
// ConfigOption dummyDisplay5 (OptionTypeShift, 20, 0, 32, "Dummy5", '3');
// ConfigOption dummyDisplay6 (OptionTypeShift, 20, 0, 32, "Dummy6", '3');
// ConfigOption dummyDisplay7 (OptionTypeShift, 20, 0, 32, "Dummy7", '3');
// ConfigOption dummyDisplay8 (OptionTypeShift, 20, 0, 32, "Dummy8", '3');
// ConfigOption smoothThrottle(OptionTypeBool,0,"Accel. suau");
//#define NUMVARS (10 + (RADIO!=0)) //Define the amount of settings in the menu
//Put all options in a table
ConfigOption *varRefs[] =
{
&radioChannel, &channelAddress, &radioPALevel,
&activeBraking, &maxBarCurrent,
&maxSpeedForward, &maxSpeedReverse,
#if !REMOTE
&speedLimit,
#endif
&naturalControl,
// &dummyDisplay3,
// &dummyDisplay4,
// &dummyDisplay5, &dummyDisplay6, &dummyDisplay7, &dummyDisplay8
};
#define NUMVARS (sizeof(varRefs)/sizeof(ConfigOption*))
int configVarIndex = 0; //Highlighted option in the menu
int configOffset = 0; //Config menu offset
bool userAction = false;
////////////////////////////////////////////////////////////////////////////////
int freeRAM()
{
extern int __heap_start, *__brkval;
int v;
return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval );
}
////////////////////////////////////////////////////////////////////////////////
// Setup function
void setup()
{
delay(500); // Wait for some time to initialize hardware
#if DEBUGA
Serial.begin(9600);
#endif
//
// EEPROM
//
loadSettings();
//
// LED
//
pinMode( LEDPIN, OUTPUT );
//
// IO
//
pinMode( IPIN0, INPUT_PULLUP );
pinMode( IPIN1, INPUT_PULLUP );
#if !REMOTE
pinMode( OPIN0, OUTPUT );
pinMode( OPIN1, OUTPUT );
#endif
//
// CHARGER
//
#if REMOTE
pinMode( BATTCHARGEPIN, INPUT );
pinMode( CHARGERPLUGPIN, INPUT );
pinMode( BATTCHECKPIN, OUTPUT );
// pinMode( BATTCHARGERPIN, INPUT ); // not used
#endif
//
// SWITCH
//
pinMode( SWPIN, INPUT_PULLUP );
//
// ENCODER
//
EncoderInterrupt.begin( &encoder );
//
// SABERTOOTH
//
#if SABERTOOTH
SabertoothTXPinSerial.begin(9600);
C.setPollInterval(20);
ST.async_getBattery( 1, 0 );
#endif
//
// RADIO
//
#if RADIO
radio.begin();
radio.enableAckPayload(); // We will be using the Ack Payload feature, so please enable it
radio.enableDynamicPayloads(); // Ack payloads are dynamic payloads
radio.setRetries( 6, 15 ); // Delay in 250us multiples and retries when connection fails
//radio.setPALevel( RF24_PA_LOW ); // Using low power amplifier level
radio.setPALevel( radioPALevel.value ); // Using low power amplifier level by default
radio.setDataRate( RF24_1MBPS ); // Using 1MB/s of data rate
radio.setChannel( radioChannel.value ); // Using channel 80 by default
remote_address[4] = channelAddress.value;
locomotive_address1[4] = channelAddress.value;
locomotive_address2[4] = channelAddress.value;
#if REMOTE
radio.openWritingPipe(remote_address); // communicate back and forth. Remote listens, Locomotive talks.
radio.openReadingPipe(1, locomotive_address1); // see starping example for multiple reading pipes (1 through 5 )
//radio.openReadingPipe(2, locomotive_address2); // TO DO : uncomment and find a way to set it for double traction
radio.startListening();
#elif LOCOMOTIVE
radio.openWritingPipe(locomotive_address1); // TO DO: find a way to set the right locomotive in case of double traction
radio.openReadingPipe(1, remote_address); // use pipe 1 so all 5 byte address bytes are set for reading from the remote
radio.stopListening();
#endif
#endif
//
// DISPLAY
//
#ifdef SSD1306AsciiWire_h
Wire.setClock( 100000L ); // other possibilities are 400000L and 2500000L, but don't work
#endif
#ifdef SSD1306AsciiAvrI2c_h
oled.setI2cClock( 100000L); // other possibilities are 400000L and 2500000L, but don't work
#endif
#ifdef OLED13
oled.begin(&SH1106_128x64, I2C_ADDRESS);
#endif
//#ifdef OLED24
// pinMode( 8, OUTPUT); // RES Pin Display
// digitalWrite( 8, LOW);
// delay (500);
// digitalWrite( 8, HIGH);
// oled.begin(&Adafruit128x64, I2C_ADDRESS);
//#endif
}
////////////////////////////////////////////////////////////////////////////////
// Main loop
void loop()
{
#ifdef SWCommand_H
docommand();
#endif
flashLed();
readSwitch();
#if REMOTE
readBatteryCharge();
readChargeStatus();
#endif
// #if REMOTE
// inputIO();
// #elif LOCOMOTIVE
// outputIO();
// #endif
#if SABERTOOTH
readSabertooth();
#elif REMOTE
readFromLocomotive();
#endif
selectMode();
#if LOCOMOTIVE
readFromRemote();
#endif
selectInputButtons();
selectMotorSpeed();
selectConfigValue();
#if !REMOTE
outputRelay();
#endif
#if SABERTOOTH
sendMotorSpeed();
#elif REMOTE
writeToLocomotive();
#endif
#if LOCOMOTIVE
writeToRemote();
#endif
updateScreenMode();
updateDisplay();
//Serial.print("RAM: ");
//Serial.println( freeRAM() ) ;
//Serial.print( "MILLIS: " );
//Serial.println( millis() );
}
////////////////////////////////////////////////////////////////////////////////
#ifdef SWCommand_H
void docommand()
{
#ifdef SWCOMMAND_USESTRING
if ( command.available() )
{
String var = command.var();
SWCommandType type = command.type();
if ( var == "var1" )
{
if ( type == SWCommandTypeGet ) command.print( var1 );
else if ( type == SWCommandTypeSet ) onTime = command.value();
}
else if ( var == "var2" )
{
if ( type == SWCommandTypeGet ) command.print( var2 );
else if ( type == SWCommandTypeSet ) offTime = command.value() ;
}
}
#else
if ( command.available() )
{
char var = command.var();
SWCommandType type = command.type();
if ( var == 'a' )
{
if ( type == SWCommandTypeGet ) command.print( a );
else if ( type == SWCommandTypeSet ) a = command.value();
}
else if ( var == 'b' )
{
if ( type == SWCommandTypeGet ) command.print( b );
else if ( type == SWCommandTypeSet ) b = command.value() ;
}
}
#endif
}
#endif
////////////////////////////////////////////////////////////////////////////////
#define StoreInitAddr 2
#define StoreSentinelAddr 0
const int StoreSentinelValue = 0x1966;
// Store settings to permanent memory
void storeSettings()
{
EEPROM.put( StoreSentinelAddr, StoreSentinelValue );
for ( int i=0, addr=StoreInitAddr ; i< NUMVARS ; i++ )
{
EEPROM.put( addr, varRefs[i]->value );
addr += sizeof(varRefs[i]->value);
}
// radio.setChannel( radioChannel.value ); // FIX ME: Should we uncoment this?
// radio.setPALevel( radioPALevel.value ); // FIX ME: Should we uncoment this?
}
// Load settings from permanent memory
void loadSettings()
{
// only load if at least one previous store was performed
int sentinel = 0;
EEPROM.get( StoreSentinelAddr, sentinel );
if ( sentinel != StoreSentinelValue )
return;
for ( int i=0, addr=StoreInitAddr ; i< NUMVARS ; i++ )
{
EEPROM.get( addr, varRefs[i]->value );
addr += sizeof(varRefs[i]->value);
}
}
////////////////////////////////////////////////////////////////////////////////
// Turns the LED on and off
void flashLed()
{
// const long shortTime = 50;
// const long longTime = 950;
const long shortTime = 150;
const long longTime = 2000-shortTime;
/*
const long mildTime = 200;
unsigned long now = millis();
static unsigned long start = now;
bool b0 = now - start > (unsigned long) longTime;
bool b1 = now - start > (unsigned long) (longTime+shortTime);
bool b2 = now - start > (unsigned long) (longTime+shortTime+mildTime);
bool b3 = now - start > (unsigned long) (longTime+2*shortTime+mildTime);
bool ledOn = (b0 && !b1) || (b2 && !b3);
if ( b3 ) start = now;
digitalWrite( LEDPIN, ledOn) ;
*/
unsigned long now = millis();
static unsigned long start = now;
bool b0 = now - start > (unsigned long)longTime;
bool b1 = now - start > (unsigned long)(longTime+shortTime);
if ( b1 ) start = now;
digitalWrite( LEDPIN, b0);
}
////////////////////////////////////////////////////////////////////////////////
void readSwitch()
{
#if LOCOMOTIVE
static Debouncer swDebouncer;
bool b = digitalRead( SWPIN ); // will read 1 if nothing is connected
if (swDebouncer.isDebounced( b, 3 )) remoteSwitch = b;
#elif REMOTE
remoteSwitch = true;
#else // neither remote or locomotive
remoteSwitch = false;
#endif
}
////////////////////////////////////////////////////////////////////////////////
#if REMOTE
void readBatteryCharge()
{
const long shortTime = 50;
const long longTime = 5000-shortTime;
unsigned long now = millis();
static unsigned long start = now;
bool b0 = now - start > (unsigned long)longTime;
bool b1 = now - start > (unsigned long)(longTime+shortTime);
// send out signal to read battery for a short limited time
digitalWrite( BATTCHECKPIN, b0 );
// read battery voltage and update timer
if ( b1 )
{
int rawCharge = analogRead( BATTCHARGEPIN );
const int maxRawCharge = 332; // this is about an input of 1.1v -> 1.1/3.3 * 1024 = 341 ->
const int minRawCharge = 280; // this is about an input of 0.9v -> 0.9/3.3 * 1024 = 279
if (rawCharge > maxRawCharge) rawCharge = maxRawCharge;
if (rawCharge < minRawCharge) rawCharge = minRawCharge;
int percentCharge = (rawCharge-minRawCharge)*100L/(maxRawCharge-minRawCharge);
if (percentCharge < d.battCharge) d.battCharge = (d.battCharge*80L + percentCharge*20L)/100;
else d.battCharge = percentCharge;
// debug
//d.battCharge=rawCharge;
start = now;
}
}
#endif
#if REMOTE
void readChargeStatus()
{
static SWTimer chargeTimer;
int b = (analogRead( CHARGERPLUGPIN ) > 300);
chargeTimer.timer( b, 1000 );
d.battIsCharging = chargeTimer.value();
}
#endif
////////////////////////////////////////////////////////////////////////////////
//#if REMOTE
//void inputIO()
//{
// static Debouncer swDebouncer0, swDebouncer1;
//
// bool b0 = !digitalRead( IPIN0 );
// if ( swDebouncer0.isDebounced( b0, 3 ) ) md.io0 = b0;
//
// bool b1 = !digitalRead( IPIN1 );
// if ( swDebouncer1.isDebounced( b1, 3 ) )
// {
// if ( b1 && dsp_md.io1 == md.io1 ) md.io1 = !md.io1;
// if ( !b1 ) dsp_md.io1 = md.io1;
// }
//}
//#endif
//#if LOCOMOTIVE || STANDALONE
//void outputRelay()
//{
// digitalWrite( OPIN0, md.io0 );
// digitalWrite( OPIN1, md.io1 );
//}
//#endif
////////////////////////////////////////////////////////////////////////////////
#if SABERTOOTH
// Asynchronously reads data from the motor controller
void readSabertooth()
{
int result = 0;
int context = 0;
if ( C.reply_available( &result, &context ) )
{
switch ( context )
{
case SABERTOOTH_GET_ERROR:
case SABERTOOTH_GET_TIMED_OUT:
#if DEBUGA
Serial.print( "ERROR " );
Serial.print( millis() );
Serial.print( " *** ");
Serial.println( result );
#endif
ST.async_getBattery( 1, 0 ); // try again from the beginning
break;
case 0: // get Battery
sd.battery = result;
ST.async_get( 'M', 1, 1 ); // request motor 1 value voltage with context 1
break;
case 1: // get value
sd.motor1 = result;
ST.async_get( 'M', 2, 2 ); // request motor 2 value voltage with context 2
break;
case 2: // get value
sd.motor2 = result;
ST.async_getCurrent( 1, 3 ); // request motor 1 current with context 3
break;
case 3: // get current
sd.current1 = (sd.current1*9 + result*1)/10;
ST.async_getCurrent( 2, 4 ); // request motor 2 current with context 4
break;
case 4: // get current
sd.current2 = (sd.current2*9 + result*1)/10;
ST.async_getTemperature( 1, 5 ); // request temperature 1 with context 5
break;
case 5: // get temperature
sd.temperature1 = result;
ST.async_getTemperature( 2, 6 ); // request temperature 2 voltage with context 6
break;
case 6: // get temperature
sd.temperature2 = result;
ST.async_getBattery( 1, 0 ); // request battery voltage with context 0
break;
}
}
}
#endif
////////////////////////////////////////////////////////////////////////////////
#if REMOTE
//Receive data from the locomotive (Locomotive)
void readFromLocomotive()
{
static SWTimer radioTimer;
static SWKeep radioOk;
if ( d.radioMode == RadioModeRemote || d.radioMode == RadioModeRemoteError )
{
uint8_t pipeNum;
bool b = radio.available( &pipeNum );
if ( b )
{
radio.read(&sd, sizeof(sd)); // TO DO : use pipeNum to account for locomotive display data
#if DEBUGA
Serial.print("Got payload from locomotive from pipe:");
Serial.println( pipeNum );
#endif
}
radioTimer.timer( !b, 3000 );
// bool error = radioTimer.value();
// if ( !error ) d.radioMode = RadioModeRemote;
// else if ( d.radioMode == RadioModeRemote ) d.radioMode = RadioModeRemoteError, md.motorMode = MotorModeStop;
if ( radioOk.keep( b, radioTimer.value() ) ) d.radioMode = RadioModeRemote;
else if ( d.radioMode == RadioModeRemote ) d.radioMode = RadioModeRemoteError, md.motorMode = MotorModeStop;
}
}
#endif
////////////////////////////////////////////////////////////////////////////////
//Determines the mode of each component: motor, menu, radio, config and screen.
//See the list of states for each mode in GLOBAL DEFS section.
void selectMode()
{
userAction = false;
// Button states
bool pb = encoder.button();
//Button timers: time between first and second push and length of the push
static SWTimer tempsRepeticio, tempsPuls;
//Timer that keeps track of how long the loco has been idle and with no user input
static SWTimer tempsZeroMarxa;
//Button works using a state machine
static byte finite = 0; //Current input
static byte preFinite = 0; //Previous input
static bool prePb = false;
bool pbOne, pbOneStrong, pbTime, pbTwo;
if ( finite == 3 )
{
if ( prePb && !pb ) finite = 0 ;
}
if ( finite == 2 )
{
if ( !prePb && pb ) finite = 3;
if ( tempsRepeticio.value() ) finite = 0;
}
if ( finite == 1 )
{
if ( prePb && !pb ) finite = 2;
if ( tempsPuls.value() ) finite = 0;
}
if ( finite == 0 )
{
if ( !prePb && pb ) finite = 1;
}
pbOne = pbOneStrong = pbTime = pbTwo = false;
if ( preFinite == 1 && finite == 2 ) pbOne = true; // Button has been pushed once and might be pushed again
if ( preFinite == 2 && finite == 0 ) pbOneStrong = true; // Button has been pushed only once
if ( preFinite == 1 && finite == 0 ) pbTime = true; // Button has been held for some time
if ( preFinite == 2 && finite == 3 ) pbTwo = true; // Button has been pushed twice in succession
// Start the timers if conditions are met
tempsRepeticio.timer( finite == 2, 300 ); // 300ms timer that only starts if there was a previous button input
tempsPuls.timer( finite == 1, 1000 ); // 1000ms timer counting the length of the push
// Save previous state for next iteration
preFinite = finite;
prePb = pb;
// #if DEBUGA
// static bool oldpbOne = pbOne;
// if ( oldpbOne != pbOne )
// {
// Serial.print( " One ");
// Serial.println( pbOne );
// oldpbOne = pbOne;
// }
//
// static bool oldpbTime = pbTime;
// if ( oldpbTime != pbTime )
// {
// Serial.print( " Time ");
// Serial.println( pbTime );
// oldpbTime = pbTime;
// }
//
// static bool oldpbTwo = pbTwo;
// if ( oldpbTwo != pbTwo )
// {
// Serial.print( " Two ");
// Serial.println( pbTwo );
// oldpbTwo = pbTwo;
// }
//
// static bool oldpbOneStrong = pbOneStrong;
// if ( oldpbOneStrong != pbOneStrong )
// {
// Serial.print( " OneStrong ");
// Serial.println( pbOneStrong );
// oldpbOneStrong = pbOneStrong;
// }
// #endif
// Determine the mode according to user actions
if ( !remoteSwitch || d.battIsCharging ) d.radioMode = RadioModeLocal, md.motorMode = MotorModeStop; // Turn off RC if remoteSwitch flag is off or battery is charging
else if ( d.radioMode == RadioModeLocal ) d.radioMode = RadioModeRemoteError; // Preserving RadioRemote if it existed, otherwise start with error
if ( d.mainMode == MainModeConfig ) // Display mode is on config menu
{
if ( d.configMode == ConfigModeSelect ) // When navigating through the settings menu
{
// Edit the selected option
if ( pbOne && configVarIndex < NUMVARS ) d.configMode = ConfigModeEdit;
// Exit to default mode if the selected option is the last one
if ( pbOneStrong && configVarIndex == NUMVARS /*Sortir*/ )
{
md.motorMode = MotorModeStop, d.mainMode = MainModeDefault;
storeSettings();
}
}
else if ( d.configMode == ConfigModeEdit ) // When adjusting a setting
{
if ( pbOne ) d.configMode = ConfigModeSelect; // Confirm setting and go back to settings menu
}
}
else if ( d.mainMode == MainModeDefault ) // Normal operation display
{
bool autorize = // Button will be responsible only for remote or standalone locomotive
( REMOTE && d.radioMode == RadioModeRemote ) ||
( LOCOMOTIVE && (d.radioMode == RadioModeRemoteError || d.radioMode == RadioModeLocal) );
if ( md.motorMode == MotorModeStop ) // If motor mode is neutral:
{
if ( naturalControl.value == 0 )
{
if ( pbOneStrong && autorize ) md.motorMode = MotorModeWait; // Set motor mode to wait if button is pushed once
}
else
{
if ( pbOneStrong && autorize ) md.motorMode = MotorModeForward; // Set motor mode to forward if button is pushed once
if ( pbTwo && autorize ) md.motorMode = MotorModeReverse; // Set motor mode to reverse if button is pushed twice
}
if ( pbTime ) d.mainMode = MainModeConfig; // Open up config display if button is pushed and held
}
else if ( (md.motorMode == MotorModeForward || md.motorMode == MotorModeReverse || md.motorMode == MotorModeWait) ) // If motor mode is not neutral:
{
if ( pbOneStrong || pbTwo ) md.motorMode = MotorModeStop; // Turn off motor and set the mode to neutral
}
}
// Inactivity timer, set motor to neutral after a while with zero setpoint
tempsZeroMarxa.timer( ( (md.motorMode == MotorModeForward || md.motorMode == MotorModeReverse) && md.motorSetPoint == 0 ) || md.motorMode == MotorModeWait, 10000 ); // Start 10 second timer for inactivity
if ( tempsZeroMarxa.value() ) md.motorMode = MotorModeStop; // Set motor mode to neutral
if ( finite != 0 ) userAction = true; // Action has been performed by the user
}
////////////////////////////////////////////////////////////////////////////////
#if LOCOMOTIVE
// Receive orders from the remote (RC) unit through ack payload
void readFromRemote()
{
static SWTimer radioTimer;
static SWKeep radioOk;
if ( d.radioMode == RadioModeRemote || d.radioMode == RadioModeRemoteError )
{
bool b = radio.available();
if ( b )
{
radio.read(&md, sizeof(md));
#if DEBUGA
Serial.println("Got Ack payload from remote");
#endif
}
radioTimer.timer( !b, 3000 );
if ( radioOk.keep( b, radioTimer.value() ) ) d.radioMode = RadioModeRemote;
else if ( d.radioMode == RadioModeRemote ) d.radioMode = RadioModeRemoteError, md.motorMode = MotorModeStop;
}
}
#endif
////////////////////////////////////////////////////////////////////////////////
// Updates input button states.
void selectInputButtons()
{
static Debouncer swDebouncer0, swDebouncer1;