-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathExlploration Robot Arduino Software.ino
1584 lines (1466 loc) · 68.2 KB
/
Exlploration Robot Arduino Software.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
/* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * *
* PLEASE READ THE FOLLOWING! *
* This open source software was written by Liam Price 2020 and is FREE to use... *
* The purpose of this software is to compile and run on an Arduino based IoT device, like an ESP32 *
* *
* This is used to control an 'Exploration Robot' that I designed to be controlled from a computer *
* steering wheel joystick, however you can use the code for any robot project, if you want to see *
* the Exploration Robot I designed this for software, visit my GitHub Repo for it: *
* https://github.com/LeehamElectronics/Exploration-Robot-Arduino *
* *
* And here is the open source Python Control Panel I made for it: *
* https://github.com/LeehamElectronics/Exploration-Robot-Control-Panel *
* *
* If you'd like to support my open source work, buy me a coffee: *
* https://www.paypal.com/paypalme/liamproice/ *
* *
* Check out my website and portfolio at https://ldprice.com *
* *
* *
* And if you need help, feel free to email me at [email protected] *
* Thanks! *
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
/*
██╗░░░░░███████╗███████╗██╗░░██╗░█████╗░███╗░░░███╗██╗░██████╗ ░██████╗░█████╗░███████╗████████╗░██╗░░░░░░░██╗░█████╗░██████╗░███████╗
██║░░░░░██╔════╝██╔════╝██║░░██║██╔══██╗████╗░████║╚█║██╔════╝ ██╔════╝██╔══██╗██╔════╝╚══██╔══╝░██║░░██╗░░██║██╔══██╗██╔══██╗██╔════╝
██║░░░░░█████╗░░█████╗░░███████║███████║██╔████╔██║░╚╝╚█████╗░ ╚█████╗░██║░░██║█████╗░░░░░██║░░░░╚██╗████╗██╔╝███████║██████╔╝█████╗░░
██║░░░░░██╔══╝░░██╔══╝░░██╔══██║██╔══██║██║╚██╔╝██║░░░░╚═══██╗ ░╚═══██╗██║░░██║██╔══╝░░░░░██║░░░░░████╔═████║░██╔══██║██╔══██╗██╔══╝░░
███████╗███████╗███████╗██║░░██║██║░░██║██║░╚═╝░██║░░░██████╔╝ ██████╔╝╚█████╔╝██║░░░░░░░░██║░░░░░╚██╔╝░╚██╔╝░██║░░██║██║░░██║███████╗
╚══════╝╚══════╝╚══════╝╚═╝░░╚═╝╚═╝░░╚═╝╚═╝░░░░░╚═╝░░░╚═════╝░ ╚═════╝░░╚════╝░╚═╝░░░░░░░░╚═╝░░░░░░╚═╝░░░╚═╝░░╚═╝░░╚═╝╚═╝░░╚═╝╚══════╝
*/
/* include library */
#include "include/configuration.h"
#include "include/mqttConfiguration.h"
#include "include/gpioConfiguration.h"
#include <WiFiManager.h> // Use this fork because the original library has issues with HTTP headers on the ESP32: https://github.com/Brunez3BD/WIFIMANAGER-ESP32
#include <WiFi.h>
// UPDATE: WiFiManager Development builds seem to work better and is more stable: https://github.com/tzapu/WiFiManager/tree/development
/*
* This 'PubSubClient' is actually the MQTT Arduino Library that we are using to make the Arduino
* board communicate with the Control Panel I made, you might be wondering, why is it called
* 'PubSubClient' and not ArduinoMQTT? Well there is a more 'official' Arduino MQTT library available,
* however it is very new at the time of writing and I prefer using these more 'established' libraries
* for stability.
*/
#include <PubSubClient.h>
/* #include <ESP32_Servo.h> having issues? Use the following ESP32 Library instead: */
#include <ESP32Servo.h> /* Get it from https://github.com/madhephaestus/ESP32Servo */
//#include <Arduino.h> /* Surprising? */
#include <analogWrite.h> /* this was required for ESP32 chips to use analogWrite for some reason, look it up https://github.com/ERROPiX/ESP32_AnalogWrite */
/*
* Used to store information even when the robot is turned off, dont abuse it, only has a set
* amount of read / write cycles. If you need to use EEPROM A LOT try using a SD Card instead!
*/
#include <EEPROM.h>
#include <ArduinoJson.h> /* This is a very important library and takes a lot to learn properly, definitely worth it though */
/* OLED Display 64x128 setup code, find more examples at https://github.com/olikraus/U8glib_Arduino/blob/master/examples/Bitmap/Bitmap.ino for different OLED's*/
/* If you want to make your own images to display to the OLED LCD, use this: http://en.radzio.dxp.pl/bitmap_converter/ */
#include "U8glib.h" // not using atm because im out of IO on the ESP32 ):
/*
* The following libraries are needed for the MPU6050 to function:
*
* https://github.com/ElectronicCats/mpu6050
* Connect MPU VCC to Arduino 5V (or if it's a 3.3V board use that voltage instead)
* Connect GND to GND
* Connect SCL to Arduino SCL
* Connect SDA to Arduino SDA
*
*/
#include "I2Cdev.h"
#include "MPU6050_6Axis_MotionApps20.h"
#include "Wire.h"
#include <math.h>
MPU6050 mpu;
#define OUTPUT_READABLE_YAWPITCHROLL
#define INTERRUPT_PIN 39 // use pin 39 which is 5VN on an ESP32 chip (next to pin 34 GPIO) CHAJNGED TO PIN 36 OOOOOF
// MPU control/status vars
bool dmpReady = false; // set true if DMP init was successful
uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU
uint8_t devStatus; // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize; // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount; // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer
// orientation/motion vars
Quaternion q; // [w, x, y, z] quaternion container
VectorInt16 aa; // [x, y, z] accel sensor measurements
VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements
VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements
VectorFloat gravity; // [x, y, z] gravity vector
float euler[3]; // [psi, theta, phi] Euler angle container
float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector
// packet structure for InvenSense teapot demo
uint8_t teapotPacket[14] = { '$', 0x02, 0,0, 0,0, 0,0, 0,0, 0x00, 0x00, '\r', '\n' };
// ================================================================
// === INTERRUPT DETECTION ROUTINE ===
// ================================================================
boolean update_gyro_pos = true;
float gyro_val_0;
float gyro_val_1;
float gyro_val_2;
volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
mpuInterrupt = true;
}
/* EEPROM Flash Memory setup: */
#define EEPROM_SIZE 22 /* don't touch unless your adding more EEPROM functionality... */
/* MQTT Variables Below, make sure to fill them in with your MQTT credentials, or it won't work! */
#define mqtt_user "IoTER"
#define mqtt_password "*!xlVZ3jVOGw"
/* This is the IP address or hostname of your MQTT server... */
const char* mqtt_server = "skynet.ciscofreak.com";
WiFiClient espClient;
PubSubClient client(espClient);
WiFiManager wifiManager;
/* Servo Setup */
Servo craneYawServo;
Servo cranePitchServo1;
Servo cranePitchServo2;
Servo craneElbowServo;
Servo craneGripperServo;
/* Global tank control variables */
int steeringFowardMomentumVal = 0;
int steeringLeftMomentumVal = 0;
int steeringRightMomentumVal = 0;
boolean isMomentumLeft = false;
boolean isMomentumRight = false;
boolean isMomentumBackwards = false;
/* crane rotation check: */
boolean isYawRotatingLeft = false;
boolean isYawRotatingRight = false;
/* crane center_axis movement check: */
boolean isPitchMovingUp = false;
boolean isPitchMovingDown = false;
/* crane forarm movement check: */
boolean isElbowMovingUp = false;
boolean isElbowMovingDown = false;
/* crane gripper_axis movement check: */
boolean isGrippperOpening = false;
boolean isGrippperClosing = false;
/* Relay variable logic */
boolean isHeadlightOn = false;
/*
* Initial crane position variables that are written
* to servos on startup. These values are replaced by
* the values stored in EEPROM but I have left values
* assigned to them anyways in case EEPROM fails...
*/
int craneYawPos = 90;
int cranePitchPos1 = 90;
int cranePitchPos2 = 90;
int craneElbowPos = 90;
int craneGripperPos = 90;
/*
* Crane movement constraint variables, these are
* also stored and read from EEPROM and can be
* virtually adjusted via the Python Control Panel
*/
/*** Rotation axis ***/
int craneYawConstraintX;
int craneYawConstraintY;
/*** Center axis ***/
int cranePitchConstraintX;
int cranePitchConstraintY;
/*** Forearm axis ***/
int craneElbowConstraintX;
int craneElbowConstraintY;
/*** Gripper axis ***/
int craneGripperConstraintX;
int craneGripperConstraintY;
/*
* Crane movement speed variables are also
* stored in EEPROM and are adjustable for
* conveinence
*/
/*** Rotation axis ***/
int craneYawMovementSpeed;
/*** Center axis_1 ***/
int cranePitchMovementSpeed;
/*** Forearm axis ***/
int craneElbowMovementSpeed;
/*** Gripper axis ***/
int craneGripperMovementSpeed;
/* Time management */
unsigned long craneMovementUpdaterPreviousMillis = 0; // will store last time 'Crane Rotation' was updated
unsigned long sysPwrUsageUpdaterPreviousMillis = 0; // will store last time 'Crane current_value' was updated
unsigned long gyroValUpdaterPreviousMillis = 0; // stores last time gyro pos is updated and sent
long craneMovementUpdaterInterval = 100; // interval at which to update crane's rotation (milliseconds)
long sysPwrUpdaterInterval = 2000; // interval at which to update crane's current usage (milliseconds)
long gyroValUpdaterInterval = 1500; // amount of time between gyro value checks occur and are sent to mqtt broker
/* unproccessed axis values from steering wheel */
float controllerAxis0Raw; // ranges between turning full lock left and full lock right
float controllerAxis1Raw; // foward acceleration
float controllerAxis2Raw; // backwards acceleration
/* OLED Display 64 x 128 (height x width) pixels setup code: */
// U8GLIB_SH1106_128X64 u8g(10, 11, 9, 6, 5); /* CLK=10, MOS=11, CS=9, DC=6, Reset=5 */
int enable_wifi_portal_button_state = 0; // stores the current state of the button (HIGH or LOW)
/**************************************** RECEIVE DATA FROM MQTT ******************************************/
void callback(char* topic, byte* payload, unsigned int length) {
Serial.print("Topic is:");
Serial.println(topic);
if (strcmp(topic, "/ExpR/in/SW_axs_0/Rs") == 0) {
// axis 0 is for left and right turning
String axs_0_temp = String((char*)payload);
controllerAxis0Raw = axs_0_temp.toFloat();
// Serial.print("SOFT RIGHT");
if (isMomentumBackwards == true) {
Serial.println("SOFT TURN RIGHT MOTOR BACK");
motor_back();
}
else {
Serial.println("SOFT TURN RIGHT MOTOR FOWARD");
motor_foward();
}
if (controllerAxis0Raw == 1.00) {
Serial.println("STEERING WHEEL CENTER");
isMomentumLeft = false;
isMomentumRight = false;
}
else {
isMomentumRight = true;
}
/* accelerate tank with slightly smaler PWM on the right hand side */
steeringRightMomentumVal = steeringFowardMomentumVal * controllerAxis0Raw;
accelerate_angle(steeringFowardMomentumVal, steeringLeftMomentumVal, steeringRightMomentumVal);
}
else if (strcmp(topic, "/ExpR/in/SW_axs_0/Rh") == 0) {
// axis 0 is for left and right turning
String axs_0_temp = String((char*)payload);
controllerAxis0Raw = axs_0_temp.toFloat();
// Serial.print("HARD RIGHT");
digitalWrite(leftMotorPosPin, HIGH);
digitalWrite(leftMotorNegPin, LOW);
digitalWrite(rightMotorPosPin, LOW);
digitalWrite(rightMotorNegPin, HIGH);
/* accelerate tank with slightly larger PWM on the right hand side with inversed polarity (full lock "tank steering" standard) */
steeringRightMomentumVal = steeringFowardMomentumVal * controllerAxis0Raw;
// Serial.print(global_steering_right);
isMomentumRight = true;
accelerate_angle(steeringFowardMomentumVal, steeringLeftMomentumVal, steeringRightMomentumVal);
}
else if (strcmp(topic, "/ExpR/in/SW_axs_0/Ls") == 0) {
// axis 0 is for left and right turning
String axs_0_temp = String((char*)payload);
controllerAxis0Raw = axs_0_temp.toFloat();
// Serial.print("SOFT LEFT");
if (isMomentumBackwards == true) {
Serial.println("SOFT TURN LEFT MOTOR BACK");
motor_back();
}
else {
Serial.println("SOFT TURN LEFT MOTOR FOWARD");
motor_foward();
}
if (controllerAxis0Raw == 1.00) {
Serial.println("STEERING WHEEL CENTER!");
isMomentumLeft = false;
isMomentumRight = false;
}
else {
isMomentumLeft = true;
}
/* accelerate tank with slightly smaler PWM on the left hand side */
steeringLeftMomentumVal = steeringFowardMomentumVal * controllerAxis0Raw;
// Serial.print(global_steering_left);
accelerate_angle(steeringFowardMomentumVal, steeringLeftMomentumVal, steeringRightMomentumVal);
}
else if (strcmp(topic, "/ExpR/in/SW_axs_0/Lh") == 0) {
// axis 0 is for left and right turning
String axs_0_temp = String((char*)payload);
controllerAxis0Raw = axs_0_temp.toFloat();
// Serial.print("HARD LEFT");
digitalWrite(leftMotorPosPin, LOW);
digitalWrite(leftMotorNegPin, HIGH);
digitalWrite(rightMotorPosPin, HIGH);
digitalWrite(rightMotorNegPin, LOW);
/* accelerate tank with slightly larger PWM on the left hand side with inversed polarity (full lock "tank steering" standard) */
steeringLeftMomentumVal = steeringFowardMomentumVal * controllerAxis0Raw;
// Serial.print(global_steering_left);
isMomentumLeft = true;
accelerate_angle(steeringFowardMomentumVal, steeringLeftMomentumVal, steeringRightMomentumVal);
}
else if (strcmp(topic, "/ExpR/in/SW_axs_1") == 0) {
// axis 1 is for accelerating fowards
String axs_1_temp = String((char*)payload);
controllerAxis1Raw = axs_1_temp.toInt();
steeringFowardMomentumVal = map(controllerAxis1Raw, -100, 100, 1000, 0);
Serial.println(steeringFowardMomentumVal);
isMomentumBackwards = false;
accelerate(steeringFowardMomentumVal);
}
else if (strcmp(topic, "/ExpR/in/SW_axs_2") == 0) {
// axis 0 for going backwards
String axs_2_temp = String((char*)payload);
controllerAxis2Raw = axs_2_temp.toInt();
steeringFowardMomentumVal = map(controllerAxis2Raw, -100, 100, 1000, 0);
Serial.println(steeringFowardMomentumVal);
isMomentumBackwards = true;
accelerate_back(steeringFowardMomentumVal);
}
else if (strcmp(topic, "/ExpR/in") == 0) {
Serial.print("Topic match 'in'");
if (payload[0] == '1') {
Serial.println("Going foward!");
manual_foward();
}
else if (payload[0] == '2') {
Serial.println("Going Back!");
manual_back();
}
else if (payload[0] == '3') {
Serial.println("Going Left!");
manual_left();
}
else if (payload[0] == '4') {
Serial.println("Going Right!");
manual_right();
}
else if (payload[0] == '5') {
Serial.println("STOP!");
manual_stop();
}
else if (payload[0] == 'g') {
Serial.println("sending current crane pos values to control panel");
send_crane_pos();
}
else if (payload[0] == 's') {
Serial.println("saving current crane pos values as default");
save_crane_pos();
}
else if (payload[0] == 'k') {
Serial.println("sending current crane constraints to control panel");
send_crane_constraints();
}
else if (payload[0] == 'o') {
Serial.println("saving current crane constraints into EEPROM");
save_crane_constraints();
}
else if (payload[0] == 'u') {
Serial.println("saving current crane movement speed into EEPROM");
save_crane_movement_speed();
}
else if (payload[0] == 'y') {
Serial.println("sending current crane speed values to control panel");
send_crane_movement_speed_values();
}
}
else if (strcmp(topic, "/ExpR/in/newC") == 0) {
Serial.print("recieving new crane pos'");
String json_temp = String((char*)payload);
Serial.print("Raw JSON Data: ");
Serial.println(json_temp);
DynamicJsonBuffer jsonBuffer(200);
JsonObject& json_obj = jsonBuffer.parseObject(json_temp);
if (!json_obj.success()) {
Serial.println("parseObject() failed");
return;
}
/*** Rotation axis ***/
craneYawPos = json_obj["rot"];
/*** Center axis_1 ***/
cranePitchPos1 = json_obj["ca_1"];
/*** Center axis_2 ***/
cranePitchPos2 = json_obj["ca_2"];
/*** Forearm axis ***/
craneElbowPos = json_obj["fa"];
/*** Gripper axis ***/
craneGripperPos = json_obj["grip"];
apply_current_crane_pos_values();
}
else if (strcmp(topic, "/ExpR/in/ncc") == 0) {
Serial.print("recieving new crane constraint values'");
String json_temp = String((char*)payload);
Serial.print("Raw JSON Data: ");
Serial.println(json_temp);
DynamicJsonBuffer jsonBuffer(200);
JsonObject& json_obj = jsonBuffer.parseObject(json_temp);
if (!json_obj.success()) {
Serial.println("parseObject() failed for crane_constraints");
return;
}
/*** Rotation axis ***/
craneYawConstraintX = json_obj["rcx"];
craneYawConstraintY = json_obj["rcy"];
/*** Center axis ***/
cranePitchConstraintX = json_obj["ccx"];
cranePitchConstraintY = json_obj["ccy"];
/*** Forearm axis ***/
craneElbowConstraintX = json_obj["fcx"];
craneElbowConstraintY = json_obj["fcy"];
/*** Gripper axis ***/
craneGripperConstraintX = json_obj["gcx"];
craneGripperConstraintY = json_obj["gcy"];
}
else if (strcmp(topic, "/ExpR/in/ncs") == 0) {
Serial.print("recieving new crane movement speed values'");
String json_temp = String((char*)payload);
Serial.print("Raw JSON Data: ");
Serial.println(json_temp);
DynamicJsonBuffer jsonBuffer(200);
JsonObject& json_obj = jsonBuffer.parseObject(json_temp);
if (!json_obj.success()) {
Serial.println("parseObject() failed for crane_constraints");
return;
}
/*** Rotation axis ***/
craneYawMovementSpeed = int(json_obj["rs"]);
/*** Center axis_1 ***/
cranePitchMovementSpeed = int(json_obj["cs"]);
/*** Forearm axis ***/
craneElbowMovementSpeed = int(json_obj["fs"]);
/*** Gripper axis ***/
craneGripperMovementSpeed = int(json_obj["gs"]);
}
else if (strcmp(topic, "/ExpR/in/nt") == 0) {
Serial.print("recieving new timings values'");
String json_temp = String((char*)payload);
Serial.print("Raw JSON Data: ");
Serial.println(json_temp);
DynamicJsonBuffer jsonBuffer(200);
JsonObject& json_obj = jsonBuffer.parseObject(json_temp);
if (!json_obj.success()) {
Serial.println("parseObject() failed for timings_values");
return;
}
/*** current reading / sending speed: ***/
sysPwrUpdaterInterval = long(json_obj["c"]);
/*** gyro reading / sending speed: ***/
gyroValUpdaterInterval = long(json_obj["g"]);
}
else if (strcmp(topic, "/ExpR/in/SW_btn_d") == 0) {
char button_temp = payload[0];
Serial.println("butn DOWN topic");
Serial.println(button_temp);
if (button_temp == '4') {
isYawRotatingLeft = true;
Serial.println("crane rot left...");
}
else if (button_temp == '5') {
isYawRotatingRight = true;
Serial.println("crane rot right...");
}
else if (button_temp == '6') {
light_toggle();
}
else if (button_temp == '7') {
Serial.println("crane open gripper...");
isGrippperOpening = true;
isGrippperClosing = false;
}
else if (button_temp == 's') {
Serial.println("crane close gripper...");
isGrippperOpening = false;
isGrippperClosing = true;
}
}
else if (strcmp(topic, "/ExpR/in/SW_btn_u") == 0) {
char button_temp = payload[0];
Serial.println("butn UP topic");
Serial.println(button_temp);
if (button_temp == '4') {
isYawRotatingLeft = false;
Serial.println("crane NOT rot left...");
}
else if (button_temp == '5') {
isYawRotatingRight = false;
Serial.println("crane NOT rot right...");
}
else if (button_temp == '6') {
light_toggle();
}
else if (button_temp == '7') {
Serial.println("crane NOT open gripper...");
isGrippperOpening = false;
isGrippperClosing = false;
}
else if (button_temp == 's') {
Serial.println("crane NOT close gripper...");
isGrippperOpening = false;
isGrippperClosing = false;
}
}
else if (strcmp(topic, "/ExpR/in/hat") == 0) {
String temp_local = String(char(payload[0]));
String hat_temp = temp_local;
Serial.print("steering wheel HAT: ");
Serial.println(hat_temp);
if (hat_temp == "x") {
Serial.println("crane forearm UP");
isElbowMovingUp = true;
isElbowMovingDown = false;
}
else if (hat_temp == "y") {
Serial.println("crane forearm DOWN");
isElbowMovingDown = true;
isElbowMovingUp = false;
}
else if (hat_temp == "v") {
Serial.println("crane center_axis UP");
isPitchMovingDown = false;
isPitchMovingUp = true;
}
else if (hat_temp == "c") {
Serial.println("crane center_axis DOWN");
isPitchMovingDown = true;
isPitchMovingUp = false;
}
else if (hat_temp == "b") {
Serial.println("crane HALT");
isElbowMovingUp = false;
isElbowMovingDown = false;
isPitchMovingDown = false;
isPitchMovingUp = false;
isYawRotatingLeft = false;
isYawRotatingRight = false;
}
}
else {
Serial.print("Topic not relevant!");
}
}
void setup() {
Serial.begin(115200);
Serial.println("Exploration Robot Systems Starting, Built and Designed By Liam Price 2020");
Serial.println("Starting LCD Panel...");
// initialize EEPROM with predefined size
EEPROM.begin(EEPROM_SIZE);
delay(10);
/* initialise all motor outputs */
pinMode(leftMotorPosPin, OUTPUT);
pinMode(leftMotorNegPin, OUTPUT);
pinMode(rightMotorPosPin, OUTPUT);
pinMode(rightMotorNegPin, OUTPUT);
pinMode(leftMotorPwmPin, OUTPUT);
pinMode(rightMotorPwmPin, OUTPUT);
pinMode(enableWifiPortalPin, INPUT);
/* Relay outputs */
pinMode(headLightRelayPin, OUTPUT);
light_toggle();
Serial.println("READING EEPROM VALUES");
/* The following code reads the default crane positions from EEPROM and writes it to the servos */
craneYawPos = EEPROM.read(0);
craneElbowPos = EEPROM.read(1);
cranePitchPos1 = EEPROM.read(2);
cranePitchPos2 = EEPROM.read(3);
craneGripperPos = EEPROM.read(4);
/*** Rotation axis ***/
craneYawConstraintX = EEPROM.read(5);
craneYawConstraintY = EEPROM.read(6);
/*** Center axis_1 ***/
cranePitchConstraintX = EEPROM.read(7);
cranePitchConstraintY = EEPROM.read(8);
/*** Forearm axis ***/
craneElbowConstraintX = EEPROM.read(9);
craneElbowConstraintY = EEPROM.read(10);
/*** Gripper axis ***/
craneGripperConstraintX = EEPROM.read(11);
craneGripperConstraintY = EEPROM.read(12);
/*** Rotation axis ***/
craneYawMovementSpeed = EEPROM.read(13);
/*** Center axis_1 ***/
cranePitchMovementSpeed = EEPROM.read(14);
/*** Forearm axis ***/
craneElbowMovementSpeed = EEPROM.read(15);
/*** Gripper axis ***/
craneGripperMovementSpeed = EEPROM.read(16);
/* Now we will initialize the servo outputs */
craneYawServo.attach(25);
cranePitchServo1.attach(27);
cranePitchServo2.attach(32);
craneElbowServo.attach(26);
craneGripperServo.attach(33);
/* NETWORKING SETUP BELOW */
//set callback that gets called when connecting to previous WiFi fails, and enters Access Point mode
wifiManager.setAPCallback(configModeCallback);
Serial.println("Connecting to WiFi...");
//if it does not connect it starts an access point with the specified name
//here "AutoConnectAP"
//and goes into a blocking loop awaiting configuration
if (!wifiManager.autoConnect(PORTAL_SSID, PORTAL_PWD)) {
Serial.println("failed to connect and hit timeout");
//reset and try again, or maybe put it to deep sleep
ESP.restart();
delay(1000);
}
//if you get here you have connected to the WiFi
Serial.println("connected...yeey :)");
/* Attempt to connect to MQTT server */
client.setServer(MQTT_SERVER, MQTT_PORT);
client.setCallback(callback);
/* This will cause the crane to move into initial position, we will make this happen AFTER it connects to network. */
apply_current_crane_pos_values();
Serial.println("Networking Setup done, displaying LCD update, will no init the gyro");
delay(100);
/* This following code will setup our MPU6050 Gyroscope by joining a I2C bus */
// join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
Wire.begin();
Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
Fastwire::setup(400, true);
#endif
// initialize MPU6050 Gyro
Serial.println(F("Initializing I2C devices..."));
mpu.initialize();
pinMode(INTERRUPT_PIN, INPUT);
// verify connection
Serial.println(F("Testing device connections..."));
Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
// load and configure the DMP
Serial.println(F("Initializing DMP..."));
devStatus = mpu.dmpInitialize();
// supply your own gyro offsets here, scaled for min sensitivity
mpu.setXGyroOffset(220);
mpu.setYGyroOffset(76);
mpu.setZGyroOffset(-85);
mpu.setZAccelOffset(1788); // 1688 factory default for my test chip
// make sure it worked (returns 0 if so)
if (devStatus == 0) {
// Calibration Time: generate offsets and calibrate our MPU6050
mpu.CalibrateAccel(6);
mpu.CalibrateGyro(6);
mpu.PrintActiveOffsets();
// turn on the DMP, now that it's ready
Serial.println(F("Enabling DMP..."));
mpu.setDMPEnabled(true);
// enable Arduino interrupt detection
Serial.print(F("Enabling interrupt detection (Arduino external interrupt "));
Serial.print(digitalPinToInterrupt(INTERRUPT_PIN));
Serial.println(F(")..."));
attachInterrupt(digitalPinToInterrupt(INTERRUPT_PIN), dmpDataReady, RISING);
mpuIntStatus = mpu.getIntStatus();
// set our DMP Ready flag so the main loop() function knows it's okay to use it
Serial.println(F("DMP ready! Waiting for first interrupt..."));
dmpReady = true;
// get expected DMP packet size for later comparison
packetSize = mpu.dmpGetFIFOPacketSize();
}
else {
// ERROR!
// 1 = initial memory load failed
// 2 = DMP configuration updates failed
// (if it's going to break, usually the code will be 1)
Serial.print(F("DMP Initialization failed (code "));
Serial.print(devStatus);
Serial.println(F(")"));
}
}
void loop() {
if (!client.connected()) {
/* If we loose connection to MQTT server try to reconnect */
Serial.println("Not connected to MQTT, trying to connect to broker...");
reconnect();
}
unsigned long currentMillis = millis();
if (currentMillis - craneMovementUpdaterPreviousMillis >= craneMovementUpdaterInterval) {
// save the last time we checked the cranes rotation status
craneMovementUpdaterPreviousMillis = currentMillis;
if (isYawRotatingLeft == true) {
if (craneYawPos >= craneYawConstraintY) {
isYawRotatingLeft = false;
Serial.println("Crane Rotation Left MAX");
}
else {
craneYawPos = craneYawPos + craneYawMovementSpeed;
craneYawServo.write(craneYawPos);
Serial.println(craneYawPos);
}
}
if (isYawRotatingRight == true) {
if (craneYawPos <= craneYawConstraintX) {
isYawRotatingRight = false;
Serial.println("Crane Rotation Right MAX");
craneYawPos = craneYawConstraintX;
craneYawServo.write(craneYawPos);
}
else {
craneYawPos = craneYawPos - craneYawMovementSpeed;
if (craneYawPos <= craneYawConstraintX) {
isYawRotatingRight = false;
Serial.println("Crane Rotation Right MAX");
craneYawPos = craneYawConstraintX;
}
else {
craneYawServo.write(craneYawPos);
Serial.println(craneYawPos);
}
}
}
if (isElbowMovingUp == true) {
if (craneElbowPos >= craneElbowConstraintY) { // contraint for forearm movement upwards...
isElbowMovingUp = false;
Serial.println("crane forearm_upward MAX");
}
else {
craneElbowPos = craneElbowPos + craneElbowMovementSpeed;
craneElbowServo.write(craneElbowPos);
Serial.println(craneElbowPos);
}
}
else if (isElbowMovingDown == true) {
if (craneElbowPos <= craneElbowConstraintX) { // contraint for forearm movement down...
isElbowMovingDown = false;
Serial.println("crane forearm_down MAX");
}
else {
craneElbowPos = craneElbowPos - craneElbowMovementSpeed;
craneElbowServo.write(craneElbowPos);
Serial.println(craneElbowPos);
}
}
if (isPitchMovingUp == true) {
if (cranePitchPos1 >= cranePitchConstraintY) { // contraint for center_axis movement upwards...
isPitchMovingUp = false;
Serial.println("crane center_axis_upward MAX");
}
else {
cranePitchPos1 = cranePitchPos1 + cranePitchMovementSpeed;
cranePitchServo1.write(cranePitchPos1);
Serial.println(cranePitchPos1);
// support servo:
cranePitchPos2 = cranePitchPos2 - cranePitchMovementSpeed;
cranePitchServo2.write(cranePitchPos2);
}
}
else if (isPitchMovingDown == true) {
if (cranePitchPos2 >= cranePitchConstraintX) { // contraint for center_axis movement down...
isPitchMovingDown = false;
Serial.println("crane center_axis_down MAX");
}
else {
cranePitchPos1 = cranePitchPos1 - cranePitchMovementSpeed;
cranePitchServo1.write(cranePitchPos1);
Serial.println(cranePitchPos1);
// support servo:
cranePitchPos2 = cranePitchPos2 + cranePitchMovementSpeed;
cranePitchServo2.write(cranePitchPos2);
}
}
if (isGrippperClosing == true) {
if (craneGripperPos >= craneGripperConstraintY) { // contraint for center_axis movement upwards...
isGrippperClosing = false;
Serial.println("crane gripper closing MAX");
}
else {
craneGripperPos = craneGripperPos + craneGripperMovementSpeed;
craneGripperServo.write(craneGripperPos);
Serial.println(craneGripperPos);
}
}
else if (isGrippperOpening == true) {
if (craneGripperPos <= craneGripperConstraintX) { // contraint for center_axis movement down...
isGrippperOpening = false;
Serial.println("crane gripper opening MAX");
}
else {
craneGripperPos = craneGripperPos - craneGripperMovementSpeed;
craneGripperServo.write(craneGripperPos);
Serial.println(craneGripperPos);
}
}
}
if (currentMillis - sysPwrUsageUpdaterPreviousMillis >= sysPwrUpdaterInterval) {
sysPwrUsageUpdaterPreviousMillis = currentMillis;
/*
* This code is executed every time 'sysPwrUsageUpdaterPreviousMillis' is reached, which then
* reads the current being used by the robot and sends it to the control panel as a float.
*/
Serial.print("Uploading current usage value... ");
float average = 0;
for (int i = 0; i < 100; i++) {
average = average + (.044 * analogRead(sysPwrReaderPin) - 3.78) / 100;
//5A mode, if 20A or 30A mode, need to modify this formula to
//(.19 * analogRead(A0) -25) for 20A mode and
//(.044 * analogRead(A0) -3.78) for 30A mode
}
Serial.println(average);
String temp = String(average);
Serial.print("formatted current value: ");
Serial.println(temp);
client.publish("/ExpR/out/current_main", (char*)temp.c_str());
}
if (currentMillis - gyroValUpdaterPreviousMillis >= gyroValUpdaterInterval) {
gyroValUpdaterPreviousMillis = currentMillis;
/*
* This code is executed every time 'gyro_value_previousMillis' is reached, which then
* reads the gyro values of the robot and sends it to the control panel as a float.
*/
Serial.print("Uploading gyro usage value... ");
send_crane_gyro_values();
}
/* This code checks to see if the wifi portal button was pressed */
enable_wifi_portal_button_state = digitalRead(enableWifiPortalPin);
if (enable_wifi_portal_button_state == HIGH) {
Serial.println("WiFi Portal button has been hit!!!");
WiFi.disconnect(true);
//reset settings - for testing
//wifiManager.resetSettings();
//sets timeout until configuration portal gets turned off
//useful to make it all retry or go to sleep
//in seconds
//wifiManager.setTimeout(120);
//WITHOUT THIS THE AP DOES NOT SEEM TO WORK PROPERLY WITH SDK 1.5 , update to at least 1.5.11883
//WiFi.mode(WIFI_STA);
if (!wifiManager.startConfigPortal("ExpR WiFi Connect Manual", "CiscoExpR123")) {
Serial.println("failed to connect and hit timeout");
delay(3000);
//reset and try again, or maybe put it to deep sleep
ESP.restart();
delay(5000);
}
//if you get here you have connected to the WiFi
Serial.println("connected...yeey :)");
}
/* The following code will update the gyro values locally */
// wait for MPU interrupt or extra packet(s) available
while (!mpuInterrupt && fifoCount < packetSize) {
if (mpuInterrupt && fifoCount < packetSize) {
// try to get out of the infinite loop
fifoCount = mpu.getFIFOCount();
}
// other program behavior stuff here
// .
// .
// .
// if you are really paranoid you can frequently test in between other
// stuff to see if mpuInterrupt is true, and if so, "break;" from the
// while() loop to immediately process the MPU data
}
// reset interrupt flag and get INT_STATUS byte
mpuInterrupt = false;
mpuIntStatus = mpu.getIntStatus();
// get current FIFO count
fifoCount = mpu.getFIFOCount();
if (fifoCount < packetSize) {
//Lets go back and wait for another interrupt. We shouldn't be here, we got an interrupt from another event
// This is blocking so don't do it while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount();
}
// check for overflow (this should never happen unless our code is too inefficient)
else if ((mpuIntStatus & (0x01 << MPU6050_INTERRUPT_FIFO_OFLOW_BIT)) || fifoCount >= 1024) {
// reset so we can continue cleanly
mpu.resetFIFO();
// fifoCount = mpu.getFIFOCount(); // will be zero after reset no need to ask
Serial.println(F("FIFO overflow!"));
// otherwise, check for DMP data ready interrupt (this should happen frequently)
}
else if (mpuIntStatus & (0x01 << MPU6050_INTERRUPT_DMP_INT_BIT)) {
// read a packet from FIFO
while (fifoCount >= packetSize) { // Lets catch up to NOW, someone is using the dreaded delay()!
mpu.getFIFOBytes(fifoBuffer, packetSize);
// track FIFO count here in case there is > 1 packet available
// (this lets us immediately read more without waiting for an interrupt)
fifoCount -= packetSize;
}
// display Euler angles in degrees
mpu.dmpGetQuaternion(&q, fifoBuffer);
mpu.dmpGetGravity(&gravity, &q);
mpu.dmpGetYawPitchRoll(ypr, &q, &gravity);
gyro_val_0 = round(ypr[0] * 180 / M_PI);
gyro_val_1 = round(ypr[1] * 180 / M_PI);
gyro_val_2 = round(ypr[2] * 180 / M_PI);
}
client.loop();
}
//gets called when WiFiManager enters configuration mode
void configModeCallback(WiFiManager* myWiFiManager) {
Serial.println("Entered config mode");
//WiFi.disconnect(true);
Serial.println(WiFi.softAPIP());
//if you used auto generated SSID, print it
Serial.println(myWiFiManager->getConfigPortalSSID());
// Make LED turn on representing we are in WiFi config mode!
// red_led_ticker.attach(.2, red_led_tick_func);
}
/********************************************* ACCELERATE *****************************************************/
void accelerate(int f)
{
// PWM code:
if (isMomentumLeft == true) {
Serial.println("ACCELERARTING WITH LEFT PRE VALUES");
steeringLeftMomentumVal = f * controllerAxis0Raw;
steeringRightMomentumVal = f;
if (f == 1000) {
Serial.println("max RM speed");
digitalWrite(rightMotorPwmPin, HIGH);
analogWrite(leftMotorPwmPin, steeringLeftMomentumVal);
}
else {
analogWrite(rightMotorPwmPin, steeringRightMomentumVal);
analogWrite(leftMotorPwmPin, steeringLeftMomentumVal);
}
}
else if (isMomentumRight == true) {
Serial.println("ACCELERARTING WITH RIGHT PRE VALUES");
steeringRightMomentumVal = f * controllerAxis0Raw;
steeringLeftMomentumVal = f;
if (f == 1000) {
Serial.println("max LM speed");
digitalWrite(leftMotorPwmPin, HIGH);
analogWrite(rightMotorPwmPin, steeringRightMomentumVal);
}
else {
analogWrite(rightMotorPwmPin, steeringRightMomentumVal);
analogWrite(leftMotorPwmPin, steeringLeftMomentumVal);
}
}
else {