-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathShadowC2.ino
2599 lines (2345 loc) · 88.5 KB
/
ShadowC2.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
// =======================================================================================
// SHADOW : Small Handheld Arduino Droid Operating Wand
// =======================================================================================
// Last Revised Date: 03/22/2023
// Written By: KnightShade
// Inspired by the PADAWAN by danf
// Bug Fixes from BlackSnake and vint43
// Contributions for PWM Motor Controllers by JoyMonkey/Paul Murphy
// With credit to Brad/BHD
// Modified by Jon Haag
// =======================================================================================
//
// Jon's Changelog:
// 03/22/2023
// - Added support for embedded Human Cyborg Relations (HCR) vocalizer board
//
// 03/29/2022
// - Reverted base code back to latest original code (as of 04/2019)
// - Updated values for drive speed, dome auto speed, and startup volume
// - Added random sounds to dome automation
// - Reordered sound commands & updated to match C2's custom sounds
// - Added initialization for Pololu Maestro on Serial2
//
// =======================================================================================
//
// This program is free software: you can redistribute it and/or modify it .
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
//
// =======================================================================================
// Note: You will need a Arduino Mega 1280/2560 to run this sketch,
// as a normal Arduino (Uno, Duemilanove etc.) doesn't have enough SRAM and FLASH
//
// This is written to be a UNIVERSAL Sketch - supporting multiple controller options
// - Single PS3 Move Navigation
// - Pair of PS3 Move Navigation
// - Android Phone (Limited Controls)
// Future Planned Enhancements:
// - XBox 360 Controller (Why not, these also uses the USB Host Shield)
// - PS3 Dual Shock Controller
// - PS4 Dual Shock Controller
//
// PS3 Bluetooth library - developed by Kristian Lauszus ([email protected])
// For more information visit my blog: http://blog.tkjelectronics.dk/ or
//
// Holoprojector Support:
// Legacy Holoprojector Support: was based on Padawan, using a second Arduino (Teeces)
// This used a Padawan Dome sketch that was loaded to the Teeces Logics.
// It leveraged the EasyTransfer libraries by Bill Porter
// Legacy support will likely be deprecated and removed in time
// Long Term Holoprojector Support:
// SHADOW control will be isolated from particular logic hardware.
// We will migrate to I2C dome commands with PWM support:
// Holoprojector Servos and LEDs will be driven by:
// http://www.adafruit.com/product/815
// This can drive 6 servos, and 3 LEDs. PWM will allow for LED brightness "flicker"
//
// Sabertooth (Foot Drive):
// Set Sabertooth 2x32 or 2x25 Dip Switches: 1 and 2 Down, All Others Up
//
// SyRen 10 Dome Drive:
// For SyRen packetized Serial Set Switches: 1, 2 and 4 Down, All Others Up
// NOTE: Support for SyRen Simple Serial has been removed, due to problems.
// Please contact DimensionEngineering to get an RMA to flash your firmware
// Some place a 10K ohm resistor between S1 & GND on the SyRen 10 itself
//
// =======================================================================================
//
// ---------------------------------------------------------------------------------------
// User Settings
// ---------------------------------------------------------------------------------------
//Primary Controller bound to Gmyle Class 1 Adapter
//String PS3MoveNavigatonPrimaryMAC = "04:76:6E:87:B0:F5"; //If using multiple controlers, designate a primary
//Primary Controller bound to Parani UD-100
String PS3MoveNavigatonPrimaryMAC = "00:07:04:05:EA:DF"; //If using multiple controlers, designate a primary
#define FOOT_CONTROLLER 0 //0 for Sabertooth Serial or 1 for individual R/C output (for Q85/NEO motors with 1 controller for each foot, or Sabertooth Mode 2 Independant Mixing)
byte drivespeed1 = 70; //set these 3 to whatever speeds work for you. 0-stop, 127-full speed.
byte drivespeed2 = 127; //Recommend beginner: 50 to 75, experienced: 100 to 127, I like 100.
byte turnspeed = 75; //50; // the higher this number the faster it will spin in place, lower - easier to control.
// Recommend beginner: 40 to 50, experienced: 50 $ up, I like 75
byte domespeed = 127; // If using a speed controller for the dome, sets the top speed
// Use a number up to 127 for serial
byte ramping = 4; //3; // Ramping- the lower this number the longer R2 will take to speedup or slow down,
// change this by increments of 1
int footDriveSpeed = 0; //This was moved to be global to support better ramping of NPC Motors
byte joystickFootDeadZoneRange = 15; // For controllers that centering problems, use the lowest number with no drift
byte joystickDomeDeadZoneRange = 10; // For controllers that centering problems, use the lowest number with no drift
byte driveDeadBandRange = 10; // Used to set the Sabertooth DeadZone for foot motors
int invertTurnDirection = 1; //This may need to be set to 1 for some configurations
byte domeAutoSpeed = 100; // Speed used when dome automation is active (1- 127)
int time360DomeTurnLeft = 700; // milliseconds for dome to complete 360 turn at domeAutoSpeed
int time360DomeTurnRight = 700; // milliseconds for dome to complete 360 turn at domeAutoSpeed
///Cut in half to reduce spin. Offset for different rotation startups due to gearing.
//#define TEST_CONROLLER //Support coming soon
//#define SHADOW_DEBUG //uncomment this for console DEBUG output
//#define SHADOW_VERBOSE //uncomment this for console VERBOSE output
//#define BLUETOOTH_SERIAL //uncomment this for console output via bluetooth.
// NOTE: BLUETOOTH_SERIAL is suspected of adding CPU load in high traffic areas
// ---------------------------------------------------------------------------------------
// Drive Controller Settings
// ---------------------------------------------------------------------------------------
int motorControllerBaudRate = 9600; // Set the baud rate for the Syren motor controller
// for packetized options are: 2400, 9600, 19200 and 38400
#define SYREN_ADDR 129 // Serial Address for Dome Syren
#define SABERTOOTH_ADDR 128 // Serial Address for Foot Sabertooth
// R/C Mode settings...
#define leftFootPin 44 //connect this pin to motor controller for left foot (R/C mode)
#define rightFootPin 45 //connect this pin to motor controller for right foot (R/C mode)
#define leftDirection 1 //change this if your motor is spinning the wrong way
#define rightDirection 0 //change this if your motor is spinning the wrong way
// ---------------------------------------------------------------------------------------
// Sound Settings
// ---------------------------------------------------------------------------------------
//Uncomment one line based on your sound system
//#define SOUND_CFSOUNDIII //Original system tested with SHADOW
//#define SOUND_MP3TRIGGER //Code Tested by Dave C. and Marty M.
//#define SOUND_ROGUE_RMP3 //Support coming soon
//#define SOUND_RASBERRYPI //Support coming soon
#define SOUND_HCR // Human Cyborg Relations Vocalizer board
//#define EXTRA_SOUNDS
// ---------------------------------------------------------------------------------------
// Dome Control System
// ---------------------------------------------------------------------------------------
//Uncomment one line based on your Dome Control
#define DOME_I2C_ADAFRUIT //Current SHADOW configuration used with R-Series Logics
//#define DOME_SERIAL_TEECES //Original system tested with SHADOW
//#define DOME_I2C_TEECES //Untested Nov 2014
// ---------------------------------------------------------------------------------------
// Utility Arm Settings
// ---------------------------------------------------------------------------------------
//Utility Arm Contribution by Dave C.
//TODO: Move PINS to upper part of Mega for Shield purposes
const int UTILITY_ARM_TOP_PIN = 49;
const int UTILITY_ARM_BOTTOM_PIN = 50;
int utilArmClosedPos = 0; // variable to store the servo closed position
int utilArmOpenPos = 140; // variable to store the servo Opened position
// Check value, open = true, closed = false
boolean isUtilArmTopOpen = false;
boolean isUtilArmBottomOpen = false;
int UtilArmBottomPos = 0;
int UtilArmTopPos = 0;
const int UTIL_ARM_TOP = 1;
const int UTIL_ARM_BOTTOM = 2;
// ---------------------------------------------------------------------------------------
// LED Settings
// ---------------------------------------------------------------------------------------
//Coin Slot LED Contribution by Dave C.
//TODO: Move PINS to upper part of Mega for Shield purposes
#define numberOfCoinSlotLEDs 3
int COIN_SLOT_LED_PINS[] = { 47, 48, 49 }; // LED pins to use.
long nextCoinSlotLedFlash[numberOfCoinSlotLEDs]; // Array indicating which LED to flash next.
int coinSlotLedState[numberOfCoinSlotLEDs]; // Array indicating the state of the LED's.
// ---------------------------------------------------------------------------------------
// Libraries
// ---------------------------------------------------------------------------------------
#include <PS3BT.h>
#include <SPP.h>
#include <usbhub.h>
// Satisfy IDE, which only needs to see the include statment in the ino.
#ifdef dobogusinclude
#include <spi4teensy3.h>
#endif
#include <Sabertooth.h>
#include <Servo.h>
#include <LedControl.h>
#ifdef DOME_SERIAL_TEECES
#include <EasyTransfer.h>
#endif
#ifdef DOME_I2C_TEECES
#include <EasyTransferI2C.h>
#endif
#ifdef DOME_I2C_ADAFRUIT
#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
//#include <Servos.h> //Attempted to use the "SlowServo library from BHD.... had issues
#endif
//This is the traditional sound controler that has been used with PADAWAN
#ifdef SOUND_MP3TRIGGER
#include <MP3Trigger.h>
MP3Trigger trigger;
#endif
#ifdef SOUND_HCR
#include <hcr.h>
HCRVocalizer HCR(&Serial1, 9600); // Use Serial1 for HCR
#endif
//Included for Pololu Maestro
#include <PololuMaestro.h>
//#include <SoftwareSerial.h>
//Custom written Libraryy for the old CFSoundIII to emulate 12 button remote
//CFSoundIII needs a supporting CFSOUND.BAS version running on the CFSoundIII
#ifdef SOUND_CFSOUNDIII
#include <CFSoundIII.h>
CFSoundIII cfSound;
#endif
//#ifdef SOUND_ROGUE_RMP3
//TODO:add rMP3 support
//#endif
//#ifdef SOUND_RASBERRYPI
//TODO:add Raspberry Pi Sound support
//#endif
// ---------------------------------------------------------------------------------------
// Variables
// ---------------------------------------------------------------------------------------
//SoftwareSerial MaestroSerial_1 (10,11);
MiniMaestro MaestroBody (Serial3); //create the Maestro
boolean topUtilArmOpen = false;
boolean bottomUtilArmOpen = false;
boolean doorsOpen = false;
long previousDomeMillis = millis();
long previousFootMillis = millis();
long currentMillis = millis();
int serialLatency = 25; //This is a delay factor in ms to prevent queueing of the Serial data.
//25ms seems appropriate for HardwareSerial, values of 50ms or larger are needed for Softare Emulation
#if FOOT_CONTROLLER == 0
Sabertooth *ST=new Sabertooth(SABERTOOTH_ADDR, Serial2);
#endif
Sabertooth *SyR=new Sabertooth(SYREN_ADDR, Serial2);
#ifdef DOME_SERIAL_TEECES
EasyTransfer ET;
#endif
#ifdef DOME_I2C_TEECES
EasyTransferI2C ET;
#endif
#if defined(DOME_SERIAL_TEECES) || defined(DOME_I2C_TEECES)
struct SEND_DATA_STRUCTURE
{
//put your variable definitions here for the data you want to send
//THIS MUST BE EXACTLY THE SAME ON THE OTHER ARDUINO
int hpx; // hp movement
int hpy; // hp movement
int hpl; // hp light
int hpa; // hp automation
int dsp; // 100=no change, 0=random, 1=alarm, 4=whistle, 5=leia, 6=short circut, 10=EQ, 11=alarm2,
}; // 21=speed1, 22=speed2, 23=speed3, 24=logics+, 25=logics-
SEND_DATA_STRUCTURE domeData;//give a name to the group of data
#endif
#ifdef DOME_I2C_ADAFRUIT
const int HOLO_FRONT = 1;
const int HOLO_BACK = 2;
const int HOLO_TOP = 3;
const int HOLO_DELAY = 20000; //up to 20 second delay
const int PWM_OFF = 4095; //setting from Adafruit
const int HOLO_FRONT_RED_PWM_PIN = 0;
const int HOLO_FRONT_GREEN_PWM_PIN = 1;
const int HOLO_FRONT_BLUE_PWM_PIN = 2;
const int HOLO_FRONT_X_PWM_PIN = 3;
const int HOLO_FRONT_Y_PWM_PIN = 4;
const int HOLO_BACK_RED_PWM_PIN = 5;
const int HOLO_BACK_GREEN_PWM_PIN = 6;
const int HOLO_BACK_BLUE_PWM_PIN = 7;
const int HOLO_BACK_X_PWM_PIN = 8;
const int HOLO_BACK_Y_PWM_PIN = 9;
const int HOLO_TOP_X_PWM_PIN = 10;
const int HOLO_TOP_Y_PWM_PIN = 11;
const int HOLO_TOP_RED_PWM_PIN = 12;
const int HOLO_TOP_GREEN_PWM_PIN = 13;
const int HOLO_TOP_BLUE_PWM_PIN = 14;
const int HOLO_SERVO_CTR = 300;
const int HOLO_FRONT_X_SERVO_MIN = 265; //250; //150; // Issues with resin holo...
const int HOLO_FRONT_X_SERVO_MAX = 315; //350; //600; // Issues with resin holo...
const int HOLO_FRONT_Y_SERVO_MIN = 250; //200; //150; // Issues with resin holo...
const int HOLO_FRONT_Y_SERVO_MAX = 330; //400; //600; // Issues with resin holo...
const int HOLO_BACK_X_SERVO_MIN = 275; //250; //150;
const int HOLO_BACK_X_SERVO_MAX = 325; //350; //600;
const int HOLO_BACK_Y_SERVO_MIN = 250; //200; //150;
const int HOLO_BACK_Y_SERVO_MAX = 350; //400; //600;
const int HOLO_TOP_X_SERVO_MIN = 275; //250; //150;
const int HOLO_TOP_X_SERVO_MAX = 325; //350; //600;
const int HOLO_TOP_Y_SERVO_MIN = 250; //200; //150;
const int HOLO_TOP_Y_SERVO_MAX = 350; //400; //600;
const int HOLO_LED_OFF = 0;
const int HOLO_LED_ON = 1;
const int HOLO_LED_FLICKER = 2;
int holoLightFrontStatus = 0;
int holoLightBackStatus = 0;
int holoLightTopStatus = 0;
uint32_t holoFrontRandomTime = 0;
uint32_t holoBackRandomTime = 0;
uint32_t holoTopRandomTime = 0;
Adafruit_PWMServoDriver domePWM = Adafruit_PWMServoDriver();
#endif
///////Setup for USB and Bluetooth Devices////////////////////////////
USB Usb;
//USBHub Hub1(&Usb); // Some dongles have a hub inside
BTD Btd(&Usb); // You have to create the Bluetooth Dongle instance like so
PS3BT *PS3Nav=new PS3BT(&Btd);
PS3BT *PS3Nav2=new PS3BT(&Btd);
//Used for PS3 Fault Detection
uint32_t msgLagTime = 0;
uint32_t lastMsgTime = 0;
uint32_t currentTime = 0;
uint32_t lastLoopTime = 0;
int badPS3Data = 0;
#ifdef BLUETOOTH_SERIAL
SPP SerialBT(&Btd,"Astromech:R2","1977"); // Create a BT Serial device(defaults: "Arduino" and the pin to "0000" if not set)
boolean firstMessage = true;
#endif
String output = "";
boolean isFootMotorStopped = true;
boolean isDomeMotorStopped = true;
boolean isPS3NavigatonInitialized = false;
boolean isSecondaryPS3NavigatonInitialized = false;
#ifdef SOUND_MP3TRIGGER
byte vol = 40; // 0 = full volume, 255 off
#endif
#ifdef SOUND_HCR
byte vol = 80; // 0 = off, 100 = full volume
#endif
boolean isStickEnabled = true;
byte isAutomateDomeOn = false;
unsigned long automateMillis = 0;
// Dome Automation Variables
boolean domeAutomation = false;
int domeTurnDirection = 1; // 1 = positive turn, -1 negative turn
float domeTargetPosition = 0; // (0 - 359) - degrees in a circle, 0 = home
unsigned long domeStopTurnTime = 0; // millis() when next turn should stop
unsigned long domeStartTurnTime = 0; // millis() when next turn should start
int domeStatus = 0; // 0 = stopped, 1 = prepare to turn, 2 = turning
byte automateDelay = random(5, 20);
byte action = 0;
unsigned long DriveMillis = 0;
Servo UtilArmTopServo; // create servo object to control a servo
Servo UtilArmBottomServo; // create servo object to control a servo
#if FOOT_CONTROLLER ==1
Servo leftFootSignal;
Servo rightFootSignal;
#endif
// =======================================================================================
// Main Program
// =======================================================================================
void setup()
{
//Debug Serial for use with USB Debugging
Serial.begin(115200);
while (!Serial); // Wait for serial port to connect - used on Leonardo, Teensy and other boards with built-in USB CDC serial connection
if (Usb.Init() == -1)
{
Serial.print(F("\r\nOSC did not start"));
while (1); //halt
}
Serial.print(F("\r\nBluetooth Library Started"));
output.reserve(200); // Reserve 200 bytes for the output string
//Setup for PS3
PS3Nav->attachOnInit(onInitPS3); // onInit() is called upon a new connection - you can call the function whatever you like
PS3Nav2->attachOnInit(onInitPS3Nav2);
//The Arduino Mega has three additional serial ports:
// - Serial1 on pins 19 (RX) and 18 (TX),
// - Serial2 on pins 17 (RX) and 16 (TX),
// - Serial3 on pins 15 (RX) and 14 (TX).
//Setup for Serial1:: Sound
#ifdef SOUND_CFSOUNDIII
cfSound.setup(&Serial1,2400);
#endif
#ifdef SOUND_MP3TRIGGER
trigger.setup(&Serial1);
trigger.setVolume(vol);
#endif
#ifdef SOUND_HCR
HCR.begin(); // start the HCR
HCR.SetVolume(CH_V,vol);
HCR.SetVolume(CH_A,vol);
HCR.SetVolume(CH_B,vol);
#endif
//Setup for Serial2:: Motor Controllers - Syren (Dome) and Sabertooth (Feet)
Serial2.begin(motorControllerBaudRate);
SyR->autobaud();
SyR->setTimeout(300); //DMB: How low can we go for safety reasons? multiples of 100ms
#if FOOT_CONTROLLER == 0
//Setup for Sabertooth / Foot Motors
ST->autobaud(); // Send the autobaud command to the Sabertooth controller(s).
ST->setTimeout(300); //DMB: How low can we go for safety reasons? multiples of 100ms
ST->setDeadband(driveDeadBandRange);
#elif FOOT_CONTROLLER == 1
leftFootSignal.attach(leftFootPin);
rightFootSignal.attach(rightFootPin);
#endif
stopFeet();
// NOTE: *Not all* Sabertooth controllers need the autobaud command.
// It doesn't hurt anything, but V2 controllers use an
// EEPROM setting (changeable with the function setBaudRate) to set
// the baud rate instead of detecting with autobaud.
//
// If you have a 2x12, 2x25 V2, 2x60 or SyRen 50, you can remove
// the autobaud line and save yourself two seconds of startup delay.
#ifdef DOME_I2C_ADAFRUIT
domePWM.begin();
domePWM.setPWMFreq(50); // Analog servos run at ~50 Hz updates
#endif
#ifdef DOME_SERIAL_TEECES
//Setup for Serial3:: Dome Communication Link
Serial3.begin(57600);//start the library, pass in the data details and the name of the serial port.
ET.begin(details(domeData), &Serial3);
#endif
#ifdef DOME_I2C_TEECES
Wire.begin();
ET.begin(details(domeData), &Wire);
#endif
//Setup for Utility Arm Servo's
UtilArmTopServo.attach(UTILITY_ARM_TOP_PIN);
UtilArmBottomServo.attach(UTILITY_ARM_BOTTOM_PIN);
closeUtilArm(UTIL_ARM_TOP);
closeUtilArm(UTIL_ARM_BOTTOM);
//Setup for Coin Slot LEDs
for(int i = 0; i<numberOfCoinSlotLEDs; i++)
{
pinMode(COIN_SLOT_LED_PINS[i],OUTPUT);
coinSlotLedState[i] = LOW;
digitalWrite(COIN_SLOT_LED_PINS[i], LOW); // all LEDs off
nextCoinSlotLedFlash[i] = millis() +random(100, 1000);
}
Serial3.begin(9600);
//Close doors and arms
MaestroBody.restartScript(1); //close Top Utility Arm
MaestroBody.restartScript(3); //close Bottom Utility Arm
MaestroBody.restartScript(5); //close both Doors
}
boolean readUSB()
{
//The more devices we have connected to the USB or BlueTooth, the more often Usb.Task need to be called to eliminate latency.
Usb.Task();
if (PS3Nav->PS3NavigationConnected ) Usb.Task();
if (PS3Nav2->PS3NavigationConnected ) Usb.Task();
if ( criticalFaultDetect() )
{
//We have a fault condition that we want to ensure that we do NOT process any controller data!!!
flushAndroidTerminal();
return false;
}
//Fix backported from Shadow_MD to fix "Dome Twitch"
if (criticalFaultDetectNav2())
{
//We have a fault condition that we want to ensure that we do NOT process any controller data!!!
return false;
}
return true;
}
void loop()
{
initAndroidTerminal();
//Useful to enable with serial console when having controller issues.
#ifdef TEST_CONROLLER
testPS3Controller();
#endif
//LOOP through functions from highest to lowest priority.
if ( !readUSB() )
{
//We have a fault condition that we want to ensure that we do NOT process any controller data!!!
return;
}
footMotorDrive();
if ( !readUSB() )
{
//We have a fault condition that we want to ensure that we do NOT process any controller data!!!
return;
}
automateDome();
domeDrive();
utilityArms();
holoprojector();
toggleSettings();
soundControl();
flashCoinSlotLEDs();
flushAndroidTerminal();
}
void onInitPS3()
{
String btAddress = getLastConnectedBtMAC();
PS3Nav->setLedOn(LED1);
isPS3NavigatonInitialized = true;
badPS3Data = 0;
#ifdef SHADOW_DEBUG
output += "\r\nBT Address of Last connected Device when Primary PS3 Connected: ";
output += btAddress;
if (btAddress == PS3MoveNavigatonPrimaryMAC)
{
output += "\r\nWe have our primary controller connected.\r\n";
}
else
{
output += "\r\nWe have a controller connected, but it is not designated as \"primary\".\r\n";
}
#endif
}
void onInitPS3Nav2()
{
String btAddress = getLastConnectedBtMAC();
PS3Nav2->setLedOn(LED1);
isSecondaryPS3NavigatonInitialized = true;
badPS3Data = 0;
if (btAddress == PS3MoveNavigatonPrimaryMAC) swapPS3NavControllers();
#ifdef SHADOW_DEBUG
output += "\r\nBT Address of Last connected Device when Secondary PS3 Connected: ";
output += btAddress;
if (btAddress == PS3MoveNavigatonPrimaryMAC)
{
output += "\r\nWe have our primary controller connecting out of order. Swapping locations\r\n";
}
else
{
output += "\r\nWe have a secondary controller connected.\r\n";
}
#endif
}
String getLastConnectedBtMAC()
{
String btAddress = "";
for(int8_t i = 5; i >= 0; i--)
{
if (btAddress.length() > 0)
{
btAddress +=(":");
}
if (Btd.disc_bdaddr[i]<0x10)
{
btAddress +="0";
}
btAddress += String(Btd.disc_bdaddr[i], HEX);
}
btAddress.toUpperCase();
return btAddress;
}
void swapPS3NavControllers()
{
PS3BT* temp = PS3Nav;
PS3Nav = PS3Nav2;
PS3Nav2 = temp;
//Correct the status for Initialization
boolean tempStatus = isPS3NavigatonInitialized;
isPS3NavigatonInitialized = isSecondaryPS3NavigatonInitialized;
isSecondaryPS3NavigatonInitialized = tempStatus;
//Must relink the correct onInit calls
PS3Nav->attachOnInit(onInitPS3);
PS3Nav2->attachOnInit(onInitPS3Nav2);
}
void initAndroidTerminal()
{
#ifdef BLUETOOTH_SERIAL
//Setup for Bluetooth Serial Monitoring
if (SerialBT.connected)
{
if (firstMessage)
{
firstMessage = false;
SerialBT.println(F("Hello from S.H.A.D.O.W.")); // Send welcome message
}
//TODO: Process input from the SerialBT
//if (SerialBT.available())
// Serial.write(SerialBT.read());
}
else
{
firstMessage = true;
}
#endif
}
void flushAndroidTerminal()
{
if (output != "")
{
if (Serial) Serial.println(output);
#ifdef BLUETOOTH_SERIAL
if (SerialBT.connected)
SerialBT.println(output);
SerialBT.send();
#endif
output = ""; // Reset output string
}
}
void automateDome()
{
//automate dome movement
if (isAutomateDomeOn)
{
long rndNum;
int domeSpeed;
if (domeStatus == 0) // Dome is currently stopped - prepare for a future turn
{
if (domeTargetPosition == 0) // Dome is currently in the home position - prepare to turn away
{
domeStartTurnTime = millis() + (random(5, 20) * 1000);
rndNum = random(5,354);
domeTargetPosition = rndNum; // set the target position to a random degree of a 360 circle - shaving off the first and last 5 degrees
if (domeTargetPosition < 180) // Turn the dome in the positive direction
{
domeTurnDirection = 1;
domeStopTurnTime = domeStartTurnTime + ((domeTargetPosition / 360) * time360DomeTurnRight);
}
else // Turn the dome in the negative direction
{
domeTurnDirection = -1;
domeStopTurnTime = domeStartTurnTime + (((360 - domeTargetPosition) / 360) * time360DomeTurnLeft);
}
}
else // Dome is not in the home position - send it back to home
{
domeStartTurnTime = millis() + (random(5, 20) * 1000);
if (domeTargetPosition < 180)
{
domeTurnDirection = -1;
domeStopTurnTime = domeStartTurnTime + ((domeTargetPosition / 360) * time360DomeTurnLeft);
}
else
{
domeTurnDirection = 1;
domeStopTurnTime = domeStartTurnTime + (((360 - domeTargetPosition) / 360) * time360DomeTurnRight);
}
domeTargetPosition = 0;
if (currentMillis - automateMillis > (automateDelay * 1000)) {
automateMillis = millis();
// Added random sounds back into latest version of code
action = random(1, 5);
if (action > 1) {
#ifdef SOUND_MP3TRIGGER
trigger.play(random(17, 51));
#endif
#ifdef SOUND_HCR
HCR.Muse();
#endif
automateDelay = random(3,10);
}
}
}
domeStatus = 1; // Set dome status to preparing for a future turn
#ifdef SHADOW_DEBUG
output += "Dome Automation: Initial Turn Set\r\n";
output += "Current Time: ";
output += millis();
output += "\r\n Next Start Time: ";
output += domeStartTurnTime;
output += "\r\n";
output += "Next Stop Time: ";
output += domeStopTurnTime;
output += "\r\n";
output += "Dome Target Position: ";
output += domeTargetPosition;
output += "\r\n";
#endif
}
if (domeStatus == 1) // Dome is prepared for a future move - start the turn when ready
{
if (domeStartTurnTime < millis())
{
domeStatus = 2;
#ifdef SHADOW_DEBUG
output += "Dome Automation: Ready To Start Turn\r\n";
#endif
}
}
if (domeStatus == 2) // Dome is now actively turning until it reaches its stop time
{
if (domeStopTurnTime > millis())
{
domeSpeed = domeAutoSpeed * domeTurnDirection;
SyR->motor(domeSpeed);
#ifdef SHADOW_DEBUG
output += "Turning Now!!\r\n";
#endif
}
else // turn completed - stop the motor
{
domeStatus = 0;
SyR->stop();
#ifdef SHADOW_DEBUG
output += "STOP TURN!!\r\n";
#endif
}
}
}
}
// =======================================================================================
// //////////////////////////Process PS3 Controller Fault Detection///////////////////////
// =======================================================================================
//TODO: boolean criticalFaultDetect(PS3BT* myPS3 = PS3Nav, int controllerNumber = 1)
boolean criticalFaultDetect()
{
if (PS3Nav->PS3NavigationConnected || PS3Nav->PS3Connected)
{
lastMsgTime = PS3Nav->getLastMessageTime();
currentTime = millis();
if ( currentTime >= lastMsgTime)
{
msgLagTime = currentTime - lastMsgTime;
} else
{
#ifdef SHADOW_DEBUG
output += "Waiting for PS3Nav Controller Data\r\n";
#endif
badPS3Data++;
msgLagTime = 0;
}
if (msgLagTime > 100 && !isFootMotorStopped)
{
#ifdef SHADOW_DEBUG
output += "It has been 100ms since we heard from the PS3 Controller\r\n";
output += "Shut downing motors, and watching for a new PS3 message\r\n";
#endif
stopFeet();
SyR->stop();
isFootMotorStopped = true;
return true;
}
if ( msgLagTime > 30000 )
{
#ifdef SHADOW_DEBUG
output += "It has been 30s since we heard from the PS3 Controller\r\n";
output += "msgLagTime:";
output += msgLagTime;
output += " lastMsgTime:";
output += lastMsgTime;
output += " millis:";
output += millis();
output += "\r\nDisconnecting the controller.\r\n";
#endif
PS3Nav->disconnect();
}
//Check PS3 Signal Data
if(!PS3Nav->getStatus(Plugged) && !PS3Nav->getStatus(Unplugged))
{
// We don't have good data from the controller.
//Wait 10ms, Update USB, and try again
delay(10);
Usb.Task();
if(!PS3Nav->getStatus(Plugged) && !PS3Nav->getStatus(Unplugged))
{
badPS3Data++;
#ifdef SHADOW_DEBUG
output += "\r\nInvalid data from PS3 Controller.";
#endif
return true;
}
}
else if (badPS3Data > 0)
{
//output += "\r\nPS3 Controller - Recovered from noisy connection after: ";
//output += badPS3Data;
badPS3Data = 0;
}
if ( badPS3Data > 10 )
{
#ifdef SHADOW_DEBUG
output += "Too much bad data coming from the PS3 Controller\r\n";
output += "Disconnecting the controller.\r\n";
#endif
PS3Nav->disconnect();
}
}
else if (!isFootMotorStopped)
{
#ifdef SHADOW_DEBUG
output += "No Connected Controllers were found\r\n";
output += "Shuting downing motors, and watching for a new PS3 message\r\n";
#endif
stopFeet();
SyR->stop();
isFootMotorStopped = true;
return true;
}
return false;
}
// =======================================================================================
// //////////////////////////END of PS3 Controller Fault Detection///////////////////////
// =======================================================================================
// =======================================================================================
// //////////////////////////Process of PS3 Secondary Controller Fault Detection//////////
// =======================================================================================
//TODO: This is moved as is, but should merge with above function.
boolean criticalFaultDetectNav2()
{
if (PS3Nav2->PS3NavigationConnected || PS3Nav2->PS3Connected)
{
lastMsgTime = PS3Nav2->getLastMessageTime();
currentTime = millis();
if ( currentTime >= lastMsgTime)
{
msgLagTime = currentTime - lastMsgTime;
}
else
{
#ifdef SHADOW_DEBUG
output += "Waiting for PS3Nav Secondary Controller Data\r\n";
#endif
badPS3Data++;
msgLagTime = 0;
}
if ( msgLagTime > 10000 )
{
#ifdef SHADOW_DEBUG
output += "It has been 10s since we heard from the PS3 secondary Controller\r\n";
output += "msgLagTime:";
output += msgLagTime;
output += " lastMsgTime:";
output += lastMsgTime;
output += " millis:";
output += millis();
output += "\r\nDisconnecting the secondary controller.\r\n";
#endif
SyR->stop();
PS3Nav2->disconnect();
return true;
}
//Check PS3 Signal Data
if(!PS3Nav2->getStatus(Plugged) && !PS3Nav2->getStatus(Unplugged))
{
// We don't have good data from the controller.
//Wait 15ms, Update USB, and try again
delay(15);
Usb.Task();
if(!PS3Nav2->getStatus(Plugged) && !PS3Nav2->getStatus(Unplugged))
{
badPS3Data++;
#ifdef SHADOW_DEBUG
output += "\r\nInvalid data from PS3 Secondary Controller.";
#endif
return true;
}
}
else if (badPS3Data > 0)
{
badPS3Data = 0;
}
if ( badPS3Data > 10 )
{
#ifdef SHADOW_DEBUG
output += "Too much bad data coming from the PS3 Secondary Controller\r\n";
output += "Disconnecting the controller.\r\n";
#endif
SyR->stop();
PS3Nav2->disconnect();
return true;
}
}
return false;
}
// =======================================================================================
// //////////////////////////END of PS3 Secondary Controller Fault Detection//////////////
// =======================================================================================
// =======================================================================================
// //////////////////////////Mixing Function for R/C Mode////////////////////////////////
// =======================================================================================
#if FOOT_CONTROLLER == 1
int leftFoot,rightFoot; //will hold foot speed values (-100 to 100)
void mixBHD(byte stickX, byte stickY, byte maxDriveSpeed){
// This is BigHappyDude's mixing function, for differential (tank) style drive using two motor controllers.
// Takes a joysticks X and Y values, mixes using the diamind mix, and output a value 0-180 for left and right motors.
// 180,180 = both feet full speed forward.
// 000,000 = both feet full speed reverse.
// 180,000 = left foot full forward, right foot full reverse (spin droid clockwise)
// 000,180 = left foot full reverse, right foot full forward (spin droid counter-clockwise)
// 090,090 = no movement
// for simplicity, we think of this diamond matrix as a range from -100 to +100 , then map the final values to servo range (0-180) at the end
// Ramping and Speed mode applied on the droid.
if(((stickX <= 113) || (stickX >= 141)) || ((stickY <= 113) || (stickY >= 141))){ // if movement outside deadzone
// Map to easy grid -100 to 100 in both axis, including deadzones.
int YDist = 0; // set to 0 as a default value if no if used.
int XDist = 0;
if(stickY <= 113){
YDist = (map(stickY, 0, 113, 100, 1)); // Map the up direction stick value to Drive speed
} else if(stickY >= 141){