-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathRcSetupTool.ino
3446 lines (3166 loc) · 117 KB
/
RcSetupTool.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 <EEPROM.h>
#include <ESP8266WiFi.h>
#include <ESP8266WebServer.h>
// #define DEBUG_ESP_MDNS
#include <ESP8266mDNS.h>
#include <DNSServer.h>
#include <Servo.h>
// *** CONFIGURAITON ***
// Used Ports as as summary (WiFi-Kit-8)
/*
D0 : OLED Reset
D1 : I2C-SCL OLED + GY521
D2 : I2C-SDA OLED + GY521
D3 : Drehwinkelgeber CLK
D4 : free
D5 : ServoOut
D6 : Drehwinkelgeber PushButton
D7 : Drehwinkelgeber DT
D8 : Buzzer
D9 : TX
D10: RX
*/
#define WIFI_KIT_8
#define OLED
#define CURRENT_SENSOR
#define ROTARY_ENCODER
#define SERVO_PIN D5
#define PIN_BUZZER_OUT D8
#define PIN_PUSH_BUTTON D6
// **** Voltage measurement settings ****
// analog input pin
#define VOLTAGE_PIN A0
// supply voltage
static const char myName[] = "RcSetupTool";
long ourDebug1;
long ourDebug2;
String ourDebug3;
#ifdef OLED
#include <U8g2lib.h> // Universal 8bit Graphics Library (https://github.com/olikraus/u8g2/)
#ifdef WIFI_KIT_8
// Wifi Kit 8 has a fixed wired 128x32 display
// U8G2_SSD1306_128X32_UNIVISION_1_HW_I2C ourOLED(U8G2_R0, /* reset=*/ 16, /* clock=*/ 5, /* data=*/ 4);
U8G2_SSD1306_128X32_UNIVISION_1_HW_I2C ourOLED(U8G2_R0, /* reset=*/ D0, /* clock=*/ D1, /* data=*/ D2);
#else
U8G2_SH1106_128X64_NONAME_1_HW_I2C ourOLED(U8G2_R0, /* reset=*/ U8X8_PIN_NONE, /* clock=*/ D3, /* data=*/ D4);
//U8G2_SSD1306_128X64_NONAME_1_HW_I2C ourOLED(U8G2_R0, /* reset=*/ U8X8_PIN_NONE, /* clock=*/ D3, /* data=*/ D4);
#endif
#endif
#ifdef ROTARY_ENCODER
#include <Encoder.h>
Encoder ourRotaryEncoder(D7, D3);
#define RE_MULITPLIER_SLOW 1
#define RE_MULITPLIER_NORMAL 5
long ourRotaryEncoderPosition=0;
long ourRotaryMenuPosition=0;
uint8_t ourRotaryEncoderMultiplier;
static boolean ourREState = true;
static int8_t ourREInversion = 1;
static long ourREPos = 0;
static long ourREOldPos = 0;
#include <Bounce2.h>
Bounce2::Button ourPushButton = Bounce2::Button();
#endif
#define OTA
#ifdef OTA
#include <ArduinoOTA.h>
#endif
#include "htmlAdminPage.h"
#include "htmlExpertPage.h"
#include "htmlMenuPage.h"
#include "htmlServoPage.h"
#include "htmlAngleSensorPage.h"
#include "htmlMultiToolPage.h"
#include "htmlShowProtocolTablePage.h"
#include "htmlScript.h"
#include "htmlStyles.h"
#include "Config.h"
// !!!!!!!!!!!!!!!!!!
// if you enable this define, the sligthly patched lib
// Adafruit_MMA8451_Library from
// https://github.com/Pulsar07/Adafruit_MMA8451_Library
// has to be added to the arduino library folder
// #define SUPPORT_MMA8451
// !!!!!!!!!!!!!!!!!!
#ifdef SUPPORT_MMA8451
#include <Adafruit_MMA8451.h> // MMA8451 library
#endif
// I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
// for both classes must be in the include path of your project
#include "I2Cdev.h"
// #define USE_MPU6050_MPU
#ifdef USE_MPU6050_MPU
#include "MPU6050_6Axis_MotionApps20.h"
#else
#include "MPU6050.h"
#endif
// #define DO_LOG
// Version history
// V0.10 : full functional initial version
// merge of ServoController and RuderwegMesssensor
// V0.11 : protocol page to multiToolPage added and some bug fixes
// V0.12 : some small beautifications
// V0.13 : support for all ASCII special chars in SSID and passwords
// more enhanced preset and protocol behaviour
// V0.14 : provided patched Adafruit_MMA8451_Library in the repository
// V0.15 : fixed support for USE_MPU6050_MPU
// V0.16 : fixed layout problems in angle measure view and bug in audio context for reference value handling
// V0.161 : fixed CTRL-Key handling for Macs
// V0.162 : expert menu now as a separate button, and AJAX get requets will work with ESP32 web server
// V0.170 : first draft: support for working OLED GUI for servo page, angle page and settings for angle tara, rudder depth, servo steps and servo null value
// V0.171 : second draft: more menus and settings an enhance GUI vor the 128x32 OLED
// V0.172 : bug fix: current smoothing disabled, menu back handling with one click fixed
// V0.173 : bug fix: current / ACS712 handling optimized and some other small enhancements
// V0.174 : new settings for buzzer, angle and rudder inversion, display rotation and safe config
// V0.175 : new settings for max current alarm and some menu enhancements
#define APP_VERSION "V0.175"
/**
* \file RcSetupTool.ino
*
* \brief small tool to control an rc-servo and measure the rudder throw via a web browser
*
* \author Author: Rainer Stransky
*
* \copyright This project is released under the GNU Public License v3
* see https://www.gnu.org/licenses/gpl.html.
* Contact: [email protected]
*
*/
/**
* \mainpage RC-Einstell-Tool Projekt zur Ansteuerung eines Modellflug-Servos und zum Vermessen von Ruderausschlägen mittels eines Winkelsensors
*
* \section intro_sec_de Übersicht
* Das RC Einstell Tool kann eine Servo mittels PWM Pulserzeugung steuern und die Ansteuerdaten anzeigen.
* Zusatzlich kann mittels eines Winkelsensors der Ruderausschlag sehr genau vermessen werden (besser als 0.5mm).
* Die Benutzeroberfläches ist als Web-Oberfläche ausgelegt, was eine Bedienung auch mit dem Smartphone zulässt.
* Eine einfach kleine Power-Bank dient als Stromversorgung und man kann extrem einfach und schnell auf der Werkbank beim
* Bau oder bei Endeinstellarbeiten alle wichtigen Daten schnell, genau und vollkommen reproduzierbar ablesen.
* Hiermit lassen sich Einstellarbeiten auf der Werkbank oder am aufgebauten Modell sehr professionell, schnell,
* genau und reproduzierbar durchführen.
* Dieses Projekt ist die Zusammenführung von https://github.com/Pulsar07/RuderwegMessSensor und https://github.com/Pulsar07/ServoController
* ![Architektur](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_Architecture.png)
*
* \section hardware_sec_de Hardware
* \subsection hardware_subsec_de_mk Mikrokontroller
* Als Mikrokontroller wird der Wemos D1/ESP8266 benutzt, der ausreichende Rechenpower und
* Speicherresourcen bietet und eine WLAN Schnittstelle hat. Es stehen ausgereifte Bibliotheken zur Nutzung der WiFi
* Schnittstelle, zur Bereitstellung eines Web-Servers (GUI) und auch zur Ansteuerung von Servos zur Verfügung.
*
* Hier ein paar Links:
* * https://www.az-delivery.de/products/d1-mini
* * https://github.com/esp8266/Arduino
*
* \subsection hardware_subsec_de_ms Messsensor
* Als Messsensor wird der GY-521/MPU-6050 benutzt. Die Genauigkeit liegt nach Kalibrierung bei
* Winkeln bis +/- 45° kleiner als 0.5°. Der Baustein MPU-6050 wird von einer wirklich sehr gut
* gemachten Libs von J.Rowberg unterstützt (siehe Link)
* Der Aufbau sollte auch ohne den Winkelsensor funktionieren, um nur die Funktion des Servo-Controllers zu erhalten.
*
* Hier ein paar Links:
* * https://www.invensense.com/wp-content/uploads/2015/02/MPU-6000-Datasheet1.pdf
* * https://www.az-delivery.de/products/gy-521-6-achsen-gyroskop-und-beschleunigungssensor
* * https://github.com/jrowberg/i2cdevlib/tree/master/Arduino/MPU6050
*
* \subsection hardware_subsec_de_sc Servo-Controller
* Für den Servo-Controller ist außer dem Signal-Kabel vom D7-Pin des Microcontrollers keinerlei Hardware notwendig.
* Will man nur einen Winkelmesser bauen, kann dieses Kabel einfach weggelassen werden.
*
* \subsection hardware_subsec_de_sp Schaltplan
* Der Schaltplan ist denkbar einfach. Es werden nur 4 Verbindungen zwischen Sensorplatine und
* Mikrokontroller benötigt. Das Layout und die Software sind so ausgelegt, dass mit einer Stiftleiste
* 4x1 das Sensorboard mit dem Gesicht in Richtung Mikrokontroller direkt verlötet werden kann.
* ![Schaltplan](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_CircuitDiagram.png)
* <br>Der Servo wird lediglich mittels eines Signal-Kabels auf den D7 Pin des Microcontrollers verbunden.
* Die Plus- und Ground-Verbindung wird mittels eines auftrennten und wieder zusammengefügten USB-MicroUSB Kabels
* hergestellt. Die Servo Stromversorgung wird einfach mittels eines Servo-Buchsenkabels erstellt und
* sollte nicht über den Microkontroller erfolgen, da die Stromstärke zu hoch für
* diesen ist.
* \subsection hardware_subsec_de_kv Ruderklemmvorrichtung
* Hier kann der geneigte Modellbauer die Kombination aus Microprozessor und Sensor in eine geeignete Klemmvorrichtung [ein-]bauen,
* die ein rutschfestes Klemmen am Ruder gewährleistet.
* So sieht der Prototyp des Authors aus:
* ![Klemm](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_InOperation.jpg)
*
* \section hmi_sec_de Anleitung
* \subsection hmi_subsec_de_ib Inbetriebnahme
* * Stromversorgung
* * Der Sensor / das Mikroprozessorboard ist mit einem Micro-USB-Anschluss ausgestattet,
* hier kann man jedes handelsübliche USB-Netzteil anschließen oder besser jede
* normale Powerbank. Damit ist man in der Werkstatt oder auf dem Flugfeld mobil ausgestattet.
* * WiFi
* * Der Sensor muss zuerst mit Smartphone oder PC verbunden werden. Dazu stellt
* der Sensor per WiFi einen Accesspoint mit der SSID "UHU" und Kennwort "12345678"
* zur Verfügung. Ist das Gerät mit diesem WLAN verbunden, kann im Web-Browser
* über die Adresse http://192.168.4.1 die Benutzeroberfläche benutzt und der Sensor
* konfiguriert werden. Sowohl obige SSID als auch das Kennwort können danach geändert werden.
* * Auf der Einstellseite kann eine SSID und ein Kennwort für ein WLAN (WLAN-Client)
* konfiguriert werden, mit dem sich der Sensor verbinden. Dabei wird dem Sensor
* eine IP-Adresse zugewiesen, die am WLAN-Router abgefragt werden muss. Änderungen
* der WLAN Einstellungen müssen gespeichert werden und werden erst nach Neustart aktiv.
* * Ist die Verbindung zu einem WLAN konfiguriert (WLAN-Client), kann auf der
* Einstellungsseite, der Accesspoint deaktiviert werden (nach Speichern und Neustart).
* Kann beim Neustart keine Verbindung zum konfigurierten WLAN aufgebaut werden,
* wird der Accesspoint-Mode aber trotzdem aktiviert, damit ein Zugang zum Gerät möglich ist.
* * Nutzung des Sensorboard GY-521 mit MPU-6050
* * Genauigkeit: Der MEMS Chip des MPU-6050 sollte Winkelauflösungen besser als 0.5°
* bei 45° Ausschlag messen können, was bei einer 60mm Rudertiefe von 60mm einen Fehler von kleiner als 0.5mm ergibt.
* Zudem sind diverse Anzeigegenauigkeiten für die Winkel und die Ruderwegs-Messung auswählbar.
* Die Anzeige hat zwar immer 2 Dezimalstellen, intern wird aber gerundet.
* * Experten-Einstellungen:
* * Kalibrierung: Damit der MPU-6050 allerdings diese Genauigkeit erreicht, muss
* er nachträglich kalibriert werden. Die Software unterstützt diese Funktion und
* kann die Werte intern speichern. Zur Kalibrierung muss die GY-521-Sensorplatine
* mit der flachen Rückseite möglichst exakt horizontal aufgelegt werden. Dann den
* Kalibrier-Button drücken und ca. 5s warten bis die Kalibrierung beendet ist.
* Dabei sollte die Auflagefläche (Tisch) nicht bewegt werden und frei von Vibrationen sein.
* * Einbaulage: Die Sensorplatine sollte auch genau so, wie bei der Kalibrierung,
* betrieben werden. Also die flache Seite nach unten und die Seite mit den
* Elektronikbausteinen nach oben. Nur so wird die oben genannte Genauigkeit erreicht.
* * Achsen und Anzeige-Genauigkeit: Auf der Konfigurationsseite, kann die Bezugs-Achse
* der Winkelmessung, je nach Einbaulage in der Klemmeinrichtung ausgewählt werden.
* * Kalibrierungsoffset: Hier können Kalibrierungs-Messwerte für +/- 45° Referenzmessungen eingebeben werden und
* aktiviert/deaktiviert werden, um die höchst mögliche Genauigkeit zu erreichen. Damit werden
* dann die Messwerte auf die Offsetwerte interpoliert.
* Der Grund hierfür ist, wie die Erfahrung zeigt, dass die verfügbaren günstggen China-Importe, nicht
* die höchste Qualität aufweisen. Z.T. lassen sich diese Sensoren
* einfach nicht kalibrieren. Ein manuelles Kalibrieren mit diesem Kalibrierungsoffset, bringt jedoch
* meist den gewünschten Erfolg
* (siehe Experten-Einstellungen) und gewährleistet genaues Arbeiten.
*
* \subsection hmi_subsec_de_me Winkel-Messung
* * Der mit dem Mikrokontroller verbundene Messensor sollte mit einer Klemmvorrichtung fest
* verbunden sein, und kann dann einfach an eine beliebige Stelle des Ruders aufgeklemmt werden.
* Die Ruderdrehachse, sollte möglichst parallel zur ausgewählten Dreh-Achse (X- oder Y-Achse)
* sein. Wie schon beschrieben, muss der Sensor mit dem Gesicht nach oben auf dem Ruder
* befestigt sein.
* * Einschränkungen: Der Sensor kann nur Winkel in Bezug auf die Schwerkraft messen.
* Somit sind Ruderwegsmessungen für das Seitenruder nur möglich wenn der Rumpf um
* 90° gedreht liegt.
* * Der Ruderweg ist abhänig von der Rudertiefe. Diese ist an der Stelle zu Messen,
* an der man den Ruderweg messen will. In der Web-Oberfläche des Sensor kann
* diese Rudertiefe eingegeben werden.
* * Ist der Sensor so auf dem Ruder angebracht, und die Rudertiefe eingestellt,
* ist die Ruderstellung in die Null-Lage zu bringen. Jetzt können Winkel
* und Ruderweg per "Tara"-Button auf 0 gesetzt werden.
* * Bewegt man das Ruder nun nach oben oder unten werden die Ausschläge in Grad und
* Millimeter angezeigt. Sollte das Vorzeichen nicht den Erwartungen entsprechen,
* kann dies bei den Einstellungen angepasst werden.
* * Zur Flugphasenmessung kann die Min-/Max-Rudermessung benutzt werden.
* Hier sollte man das Ruder in die Neutralstellung der Flugphase bringen.
* Nun den Schalter für die Min-/Max-Ruderweg-Messung aktivieren. Damit wird der
* aktuelle Ruderausschlag als Neutralwert übernommen. Jetzt können die beiden
* Min-/Max-Werte angefahren werden. Alle drei Werte werden bis zur
* Deaktiverung der Messung angezeigt.
* ![AngleSensorPage](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_AngleSensorPage.png)
*
* \subsection hmi_subsec_de_sc Servo-Controller
* Die Bedienung am Web-GUI ist denkbar einfach. Die Servo-Position kann über zwei
* Eingabefelder prozentual oder als Impulsbreite gesteuert werden. Zusätzlich kann die Servoposition
* über ein Slider-Widget gesteuert werden.
* Zudem erlaubt eine aktivierbare Maus-Wheel Funktion, mit Beschleunigungsfaktor, das Steuern des Servowegs
* mittels der Maus.
* Es sind für diverse Aufgaben noch 5 vordefinierte und einstellbare (Save) Positions-Buttons
* verfügbar.
* Die Limit-Buttons, können zum Begrenzen des Servo-Wegs benutzt werden, um ein versehntliches Überfahren eines
* mechanischen Limits zu verhindern.
* Auf der Einstellseite, können die Limits und 100%-Settings für verschiedene Hersteller von RC-Systemen voreingestellt werden,
* damit die Anzeige exakt mit den Werte des genutzten RC-System übereinstimmt.
* ![ServoPage](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_ServoPage.png)
*
* \subsection hmi_subsec_de_ms Steuern und Messen
* In dieser Ansicht kann sowohl der Servo gesteurt als auch der Winkel-Sensor abgelesen werden.
* Dies ist vor allem bei Servo- und Gestänge-Einbauten ein große Hilfe.
* ![MultiToolPage](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_MultiToolPage.png)
* Zusätzlich können den in den Preset-Buttons gespeicherten Servo-Werte
* (und die gemessenen Winkel- und Ruderauschlagswerte) und eine Nutzer-Beschreibung
* des Datensatzes festgehalten und mittels der Funktion "Zeige Protokoll"
* in Tabellenform ausgegeben werden.
* ![ProtocolPage](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_ProtocolPage.png)
*
* Weitere Details gibt es unter <a href="http://www.so-fa.de/nh/RcSetupTool">Albatross, Seite für Modellflug und Technik</a>
*
* \subsection hmi_subsec_de_flash Bin-Datei direkt zum Flashen
* ist im bin-Verzeichnis verfügbar.
* Download NodeMCU-Flasher (z. Bspl. Von hier: https://github.com/marcelstoer/nodemcu-pyflasher/releases/tag/v4.0 )<br>
* ![UploadBin](https://raw.githubusercontent.com/Pulsar07/RcSetupTool/master/doc/img/RCST_UploadBin.jpg)
* <br>Flasher-Programm starten und Port wählen, Bin-Datei öffnen und 115200 Baud einstellen.<br>
* Flash-Button drücken.<br>
* Das war es ;-)<br>
*/
// #define MYSEP €
// #define MYSEP ";"
#define MYSEP_STR "~~~"
const byte DNS_PORT = 53;
DNSServer ourDNSServer;
IPAddress ourApIp(192,168,4,1);
IPAddress ourNetmask(255,255,255,0);
static configData_t ourConfig;
#ifdef SUPPORT_MMA8451
static Adafruit_MMA8451 mma;
#endif
static MPU6050 mpu;
static const uint8_t MPU6050ADDR1 = 0x68; // I2C address of the MPU-6050. If AD0 pin is set to HIGH, the I2C address will be 0x69.
static const uint8_t MPU6050ADDR2 = 0x69; // I2C address of the MPU-6050. If AD0 pin is set to HIGH, the I2C address will be 0x69.
#ifdef SUPPORT_MMA8451
static const uint8_t MMA8451ADDR1 = 0x1C; // I2C address of the MMA-8451. If AD0 pin is set to LOW, the I2C address will be 0x1C.
static const uint8_t MMA8451ADDR2 = 0x1D; // I2C address of the MMA-8451. If AD0 pin is set to LOW, the I2C address will be 0x1C.
#endif
static uint8_t ourSCL_Pin;
static uint8_t ourSDA_Pin;
static uint8_t ourI2CAddr;
static String ourSensorTypeName;
static boolean ourTriggerCalibrateMPU6050 = false;
static unsigned long ourTriggerRestart = 0;
int16_t ourAccelerometer_x, ourAccelerometer_y, ourAccelerometer_z; // variables for ourAccelerometer raw data
int16_t gyro_x, gyro_y, gyro_z; // variables for gyro raw data
int16_t temperature; // variables for temperature data
static double ourTara = 0;
static double ourSmoothedAngle_x = 0;
static double ourSmoothedAngle_y = 0;
static double ourSmoothedAngle_z = 0;
static double ourTaraAngle_x = 0;
static double ourTaraAngle_y = 0;
static double ourTaraAngle_z = 0;
static double ourSmoothedGyro_x = 0;
static double ourSmoothedGyro_y = 0;
static double ourSmoothedGyro_z = 0;
static double ourTaraGyro_x = 0;
static double ourTaraGyro_y = 0;
static double ourTaraGyro_z = 0;
static double ourTargetAmplitude = 5;
static float ourNullAmpl;
static float ourMinAmpl;
static float ourMaxAmpl;
static boolean ourIsMeasureActive=false;
float mySmoothedCurrent = 0.0f;
float ourServoCurrent;
float ourServoAlarmCurrent = 0.6f;
static unsigned long ourBuzzTimeTill = 0;
static boolean ourBuzzOn = false;
static boolean ourBuzzerEnabled = true;
enum ToolContext {
BASE_MENU_PAGE,
SERVO_MENU_PAGE,
MULTI_MENU_PAGE,
ANGLE_MENU_PAGE,
SETTINGS_MENU_PAGE,
SERVO_PAGE,
ANGLE_SENSOR_PAGE,
MULTI_TOOL_PAGE,
ADMIN_PAGE,
SET_SERVO_STEPS,
SET_RUDDER_DEPTH,
SET_RUDDER_INVERS,
SET_ANGLE_INVERS,
EXPERT_ADMIN_PAGE,
SET_ALARM_CURRENT,
INFO_PAGE,
DEBUG_PAGE,
};
ToolContext ourContext=BASE_MENU_PAGE;
// BASE_MENU_PAGE
const char* ourBaseMenu0 = "0:Multi-Tool";
const char* ourBaseMenu1 = "1:Servocontroller";
const char* ourBaseMenu2 = "2:Winkelmesser";
const char* ourBaseMenu3 = "3:Einstellungen";
const char* ourBaseMenu4 = "4:Infos";
const char* ourBaseMenu5 = "5:Debug-Anzeige";
const char* ourBaseMenuItems[] = {ourBaseMenu0, ourBaseMenu1, ourBaseMenu2, ourBaseMenu3, ourBaseMenu4, ourBaseMenu5};
const uint8_t ourBaseMenuSize = sizeof(ourBaseMenuItems) / sizeof(char*);;
// SERVO_MENU_PAGE
const char* ourServoMenu0 = "0:Servo-Pos=0%";
const char* ourServoMenu1 = "1:Setze Servoschritte"; // SET_SERVO_STEPS
const char* ourServoMenu2 = "2:Setze Stromalarm"; // SET_ALARM_CURRENT
const char* ourServoMenu3 = "3:zurueck";
const char* ourServoMenu4 = "4:Hauptmenu";
const char* ourServoMenuItems[] = {ourServoMenu0, ourServoMenu1, ourServoMenu2, ourServoMenu3, ourServoMenu4};
const uint8_t ourServoMenuSize = sizeof(ourServoMenuItems) / sizeof(char*);;
// MULTI_MENU_PAGE
const char* ourMultiMenu0 = "0:Servo-Pos=0%";
const char* ourMultiMenu1 = "1:Tara-Winkel";
const char* ourMultiMenu2 = "2:Inv.Winkelanzeige"; // SET_ANGLE_INVERS
const char* ourMultiMenu3 = "3:Setze Rudertiefe"; // SET_RUDDER_DEPTH
const char* ourMultiMenu4 = "4:Inv. Ruderanzeige"; // SET_RUDDER_INVERS
const char* ourMultiMenu5 = "5:Setze Servoschritte"; // SET_SERVO_STEPS
const char* ourMultiMenu6 = "6:Setze Stromalarm"; // SET_ALARM_CURRENT
const char* ourMultiMenu7 = "7:zurueck";
const char* ourMultiMenu8 = "8:Hauptmenu";
const char* ourMultiMenuItems[] = {ourMultiMenu0, ourMultiMenu1, ourMultiMenu2, ourMultiMenu3, ourMultiMenu4, ourMultiMenu5, ourMultiMenu6, ourMultiMenu7, ourMultiMenu8};
const uint8_t ourMultiMenuSize = sizeof(ourMultiMenuItems) / sizeof(char*);;
// ANGLE_MENU_PAGE
const char* ourAngleMenu0 = "0:Tara-Winkel";
const char* ourAngleMenu1 = "1:Inv.Winkelanzeige"; // SET_ANGLE_INVERS
const char* ourAngleMenu2 = "2:Setze Rudertiefe"; // SET_RUDDER_DEPTH
const char* ourAngleMenu3 = "3:Inv. Ruderanzeige"; // SET_RUDDER_INVERS
const char* ourAngleMenu4 = "4:Hauptmenu";
const char* ourAngleMenuItems[] = {ourAngleMenu0, ourAngleMenu1, ourAngleMenu2, ourAngleMenu3, ourAngleMenu4};
const uint8_t ourAngleMenuSize = sizeof(ourAngleMenuItems) / sizeof(char*);;
// SETTINGS_MENU_PAGE
const char* ourSettingsMenu0 = "0:Buzzer an/aus";
const char* ourSettingsMenu1 = "1:Anzeige drehen";
const char* ourSettingsMenu2 = "2:Drehknopf invert.";
const char* ourSettingsMenu3 = "3:Sichere Einstell.";
const char* ourSettingsMenu4 = "4:Hauptmenu";
const char* ourSettingsMenuItems[] = {ourSettingsMenu0, ourSettingsMenu1, ourSettingsMenu2, ourSettingsMenu3, ourSettingsMenu4};
const uint8_t ourSettingsMenuSize = sizeof(ourSettingsMenuItems) / sizeof(char*);;
#define MIN_PULSE_WITDH 700 // us
#define MAX_PULSE_WITDH 2300 // us
// LOGGING LOGGING
enum LogSeverity {
LS_START=0,
DEBUG,
INFO,
WARNING,
ERROR,
LS_END
};
#define LOG_MOD_HTTP 0x01
#define LOG_MOD_PERF 0x02
#define LOG_MOD_RTEST 0x04
#define LOG_MOD_RADIO 0x08
#define LOG_MOD_5 0x10
#define LOG_MOD_6 0x20
#define LOG_MOD_7 0x40
#define LOG_MOD_8 0x80
LogSeverity ourLogSeverity=DEBUG;
byte ourLogModules = 0;
void setLogModule(byte aModule) {
ourLogModules = ourLogModules | aModule;
}
// some forward declarations
void setupLog() {
setLogModule(LOG_MOD_HTTP);
setLogModule(LOG_MOD_PERF);
setLogModule(LOG_MOD_RTEST);
setLogModule(LOG_MOD_RADIO);
}
#define LOGGY3(a, b, c) logMsg(a, b, c)
#define LOGGY2(a, b) logMsg(a, b)
// #define LOGGY2(a, b)
void logMsg(LogSeverity aSeverity, String aMessage);
void log_printSecond();
void logMsg(byte aModule, LogSeverity aSeverity, String aMessage) {
if (aModule & ourLogModules) {
logMsg(aSeverity, aMessage);
}
}
void logMsg(LogSeverity aSeverity, String aMessage) {
if (aSeverity >= ourLogSeverity) {
log_printSecond();
Serial.print(myName);
Serial.print(':');
Serial.print(aMessage);
Serial.println();
}
}
void log_printSecond() {
char buf[25];
snprintf (buf, 25, "%08d: ", millis());
Serial.print(buf);
}
enum {
RD_QR1_L,
RD_QR1_R,
RD_QR2_L,
RD_QR2_R,
RD_WK1_L,
RD_WK1_R,
RD_WK2_L,
RD_WK2_R,
RD_VL_L,
RD_VL_R,
RD_SR_1,
RD_SR_2,
RD_HR_1,
RD_HR_2,
RD_SF_1,
RD_SF_2,
RD_SF_3,
RD_SF_4,
RD_LAST
};
const char *ourFunctionDefMap[] = {
[RD_QR1_L] = "option_fd_QR-1-L",
[RD_QR1_R] = "option_fd_QR-1-R",
[RD_QR2_L] = "option_fd_QR-2-L",
[RD_QR2_R] = "option_fd_QR-2-R",
[RD_WK1_L] = "option_fd_WK-1-L",
[RD_WK1_R] = "option_fd_WK-1-R",
[RD_WK2_L] = "option_fd_WK-2-L",
[RD_WK2_R] = "option_fd_WK-2-R",
[RD_VL_L] = "option_fd_VL-L",
[RD_VL_R] = "option_fd_VL-R",
[RD_SR_1] = "option_fd_SR-1",
[RD_SR_2] = "option_fd_SR-2",
[RD_HR_1] = "option_fd_HR-1",
[RD_HR_2] = "option_fd_HR-2",
[RD_SF_1] = "option_fd_SF-1",
[RD_SF_2] = "option_fd_SF-2",
[RD_SF_3] = "option_fd_SF-3",
[RD_SF_4] = "option_fd_SF-4",
};
typedef struct {
int rudderIdx;
String descr;
int8_t functionIdx;
int servoPresets[CONFIG_SERVO_PRESET_MAX];
int limitLow;
int limitHigh;
int8_t servoDirection;
float angle;
int servoPos;
float rudderSize;
float presetAngles[CONFIG_SERVO_PRESET_MAX];
} servoDataSet_t;
#define DATA_SET_IDX_MAX RD_LAST
#define ANGLE_UNSET_VAL 999.0f
typedef struct {
String datasetDescription;
int8_t currentFunctionIdx=0;
int8_t dataSetIdxUnused=0;
servoDataSet_t rudderData[DATA_SET_IDX_MAX];
float currentPresetAngles[CONFIG_SERVO_PRESET_L];
} protocolData_t;
protocolData_t ourProtocolData;
Servo ourServo;
int16_t ourServoPos;
int8_t ourServoDirection = 1;
boolean ourWheelActivation = false;
uint8_t ourWheelFactor = 1;
int ourServoLimit[2];
#ifdef USE_MPU6050_MPU
#define INTERRUPT_PIN 15 // use pin 15 on ESP8266
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
#endif
ESP8266WebServer server(80); // Server Port hier einstellen
void setDefaultConfig();
void setup()
{
delay(1000);
setupLog();
Serial.begin(115200);
delay(1000);
Serial.println();
Serial.println();
Serial.print("Starting ServoController :");
Serial.println(APP_VERSION);
delay(1000);
// check HW Pin 4 for HW Reset
// checkHWReset(D6);
loadConfig();
initConfig();
printConfig("stored configuration:");
detectSensor();
if (isI2C_MPU6050Addr()) {
Wire.begin(ourSDA_Pin, ourSCL_Pin); //SDA, SCL
initMPU6050();
#ifdef SUPPORT_MMA8451
} else if (isI2C_MMA8451Addr()) {
initMMA8451();
#endif
}
#ifdef OLED
setupDisplay();
#endif
setupWiFi();
setupWebServer();
initServo();
initProtocolData();
#ifdef ROTARY_ENCODER
setupRotaryEncoder();
setupPushButton();
#endif
setupBuzzer();
if (WiFi.status() == WL_CONNECTED) {
#ifdef OTA
setup_ota();
#endif
}
}
#ifdef OLED
const uint8_t *oledFontLarge;
const uint8_t *oledFontBig;
const uint8_t *oledFontNormal;
const uint8_t *oledFontSmall;
void setupDisplay() {
// Wifi Kit 8 has a fixed wired 128x32 display
ourOLED.begin();
// ourOLED.enableUTF8Print();
int oledDisplayHeight = ourOLED.getDisplayHeight();
int oledDisplayWidth = ourOLED.getDisplayWidth();
logMsg(INFO, F("init OLED display: ") + String(oledDisplayWidth) + String(F("x")) + String(oledDisplayHeight));
oledFontLarge = u8g2_font_helvB18_tf;
oledFontBig = u8g2_font_helvB14_tf;
oledFontNormal = u8g2_font_7x13B_tf; // u8g2_font_helvB08_tf;
oledFontSmall = u8g2_font_5x7_tr;
ourOLED.setFlipMode(ourConfig.oledFlipped);
ourOLED.firstPage();
do {
showHello();
} while ( ourOLED.nextPage() );
}
void showHello() {
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 15);
ourOLED.print("Hello I am ");
ourOLED.setCursor(0, 32);
ourOLED.print(myName);
ourOLED.print(" ");
ourOLED.print(APP_VERSION);
}
void showOLEDAngleSensorPage() {
ourOLED.setDrawColor(1);
ourOLED.setFontMode(0);
ourOLED.setFont(oledFontLarge);
String str = "";
str += String(getRoundedAngle(), 1);
str += String((char) 176);
ourOLED.setCursor(64-ourOLED.getStrWidth(str.c_str()), 18);
ourOLED.print(str.c_str());
str = String(getRoundedAmplitude(), 1);
ourOLED.setCursor(118-ourOLED.getStrWidth(str.c_str()), 18);
ourOLED.print(str.c_str());
ourOLED.setFont(oledFontSmall);
str = F("mm");
ourOLED.setCursor(118, 18);
ourOLED.print(str.c_str());
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 32);
ourOLED.print(F("RT="));
ourOLED.print(ourConfig.rudderSize, 1);
ourOLED.print(F("mm"));
}
/**
return the math result of a modulo operation instead of the symmetric (as implemented in the %-operator
*/
int8_t getModulo(long aDivident, uint8_t aDivisor) {
// Umrechnung der Modulo Resultate von der in C++ implementierten symmetrischen Modulo-Variante in die mathematische Variante
return ((aDivident % aDivisor) + aDivisor) % aDivisor;
}
void showOLEDMenu(const char* aItems[], uint8_t aNumItems) {
ourOLED.drawBox(0, 11, 128, 11);
ourOLED.setDrawColor(2);
ourOLED.setFontMode(1);
ourOLED.setFont(oledFontNormal);
for (int8_t i=-1; i<2; i++) {
ourOLED.drawStr(0,21+i*11, aItems[getModulo(ourRotaryMenuPosition+i, aNumItems)]);
}
}
void showOLEDInfoPage() {
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 12);
ourOLED.print(myName);
ourOLED.print(" ");
ourOLED.print(APP_VERSION);
ourOLED.setCursor(0, 24);
ourOLED.print(F("IP:"));
if (WiFi.status() == WL_CONNECTED) {
ourOLED.print(WiFi.localIP().toString());
}
}
void showOLEDDebugInfo() {
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 10);
ourOLED.print(F("D1:"));
ourOLED.print(ourDebug1);
ourOLED.setCursor(0, 21);
ourOLED.print(F("D2:"));
ourOLED.print(ourDebug2);
ourOLED.setCursor(0, 32);
ourOLED.print(F("D3:"));
ourOLED.print(ourDebug3);
}
void showOLEDSetServoSteps() {
// SET_SERVO_STEPS:
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 15);
ourOLED.print("Servo-Steps=");
ourOLED.print(String(ourRotaryEncoderMultiplier));
ourOLED.print("%");
}
void showOLEDSetRudderDepth() {
// SET_RUDDER_DEPTH:
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 15);
ourOLED.print("Rudertiefe=");
ourOLED.print(String(ourConfig.rudderSize));
ourOLED.print("mm");
}
void showOLEDSetAlarmCurrent() {
// SET_ALARM_CURRENT:
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(0, 15);
ourOLED.print("Alarm bei I=");
ourOLED.print(String(ourServoAlarmCurrent, 1));
ourOLED.print("A");
}
void showOLEDServoPositionPage(int16_t aPosition) {
ourOLED.setDrawColor(1);
ourOLED.setFontMode(0);
ourOLED.setFont(oledFontBig);
String position = String(aPosition) + F("%");
ourOLED.setCursor(127-ourOLED.getStrWidth(position.c_str()), 24);
ourOLED.print(position.c_str());
ourOLED.setFont(oledFontNormal);
ourOLED.setCursor(20, 32);
switch(ourRotaryEncoderMultiplier) {
case RE_MULITPLIER_SLOW:
ourOLED.print(F("."));
break;
case RE_MULITPLIER_NORMAL:
ourOLED.print(F("o"));
break;
}
ourOLED.print(F(":"));
ourOLED.print(F("I="));
ourOLED.print(ourServoCurrent, 1);
ourOLED.print(F("A"));
// ourOLED.print(F(":Raw I="));
// ourOLED.print(mySmoothedCurrent);
// showServoPosition(0, 13, 64, 5, (150.0f+aPosition)/300);
showServoPositionVertical(0, 0, 18, 32, (150.0f-aPosition)/300);
}
void showOLEDServoPositionAndAnglePage() {
// showServoPositionHorizontal(0, 0, 64, 13, (150.0f+getServoPosInPercent())/300);
// ourOLED.setDrawColor(1);
// ourOLED.setFontMode(0);
ourOLED.setDrawColor(2);
ourOLED.setFontMode(1);
ourOLED.setFont(oledFontBig); // 12
uint8_t upper = 13;
String str;
str = String(getServoPosInPercent()) + F("%");
ourOLED.setCursor(64-ourOLED.getStrWidth(str.c_str()), upper);
ourOLED.print(str.c_str());
ourOLED.setFont(oledFontNormal); // 12
str = F("mm");
ourOLED.setCursor(110, 32);
ourOLED.print(str.c_str());
ourOLED.setFont(oledFontBig); // 12
str = String(getRoundedAmplitude(), 1);
ourOLED.setCursor(108-ourOLED.getStrWidth(str.c_str()), 32);
ourOLED.print(str.c_str());
str = String(getRoundedAngle(), 1) + String((char) 176);
ourOLED.setCursor(128-ourOLED.getStrWidth(str.c_str()), upper);
ourOLED.print(str.c_str());
ourOLED.setFont(oledFontSmall);
ourOLED.setCursor(0, upper);
switch(ourRotaryEncoderMultiplier) {
case RE_MULITPLIER_SLOW:
ourOLED.print(F("."));
break;
case RE_MULITPLIER_NORMAL:
ourOLED.print(F("o"));
break;
}
ourOLED.setCursor(0, 24);
ourOLED.print(F("I="));
ourOLED.print(ourServoCurrent, 1);
ourOLED.print(F("A"));
ourOLED.setCursor(0, 32);
ourOLED.print(F("RT="));
ourOLED.print(ourConfig.rudderSize);
ourOLED.print(F("mm"));
}
void showServoPositionVertical(int x, int y, int w, int h, float value) {
ourOLED.drawFrame(x, y, w, h);
ourOLED.drawBox(x + 2, y + 2, (w - 4), (h - 3) * value);
}
void showServoPositionHorizontal(int x, int y, int w, int h, float value) {
// ourOLED.drawFrame(x, y, w, h);
ourOLED.drawBox(x, y, (w) * value, h);
}
void updateOLED(unsigned long aNow) {
static unsigned long last=0;
#define OLED_REFRESH_CYCLE 200
if (aNow < last) {
return;
}
last = aNow + OLED_REFRESH_CYCLE;
ourOLED.firstPage();
do {
switch (ourContext) {
case MULTI_TOOL_PAGE:
showOLEDServoPositionAndAnglePage();
break;
case SERVO_PAGE:
showOLEDServoPositionPage(getServoPosInPercent());
break;
case ANGLE_SENSOR_PAGE:
showOLEDAngleSensorPage();
break;
case INFO_PAGE:
showOLEDInfoPage();
break;
case DEBUG_PAGE:
showOLEDDebugInfo();
break;
case SET_SERVO_STEPS:
showOLEDSetServoSteps();
break;
case SET_RUDDER_DEPTH:
showOLEDSetRudderDepth();
break;
case SET_ALARM_CURRENT:
showOLEDSetAlarmCurrent();
break;
case MULTI_MENU_PAGE:
showOLEDMenu(ourMultiMenuItems, ourMultiMenuSize);
break;
case SERVO_MENU_PAGE:
showOLEDMenu(ourServoMenuItems, ourServoMenuSize);
break;
case SETTINGS_MENU_PAGE:
showOLEDMenu(ourSettingsMenuItems, ourSettingsMenuSize);
break;
case ANGLE_MENU_PAGE:
showOLEDMenu(ourAngleMenuItems, ourAngleMenuSize);
break;
case BASE_MENU_PAGE:
default: // MENU
showOLEDMenu(ourBaseMenuItems, ourBaseMenuSize);
break;
}
} while ( ourOLED.nextPage() );
}
#endif
#ifdef ROTARY_ENCODER
void setupRotaryEncoder() {
ourRotaryEncoderMultiplier = RE_MULITPLIER_NORMAL;
ourREInversion = ourConfig.rotaryEncoderFlipped ? -1 : 1;
resetRotaryEncoder();
}
void setupPushButton() {
// BUTTON SETUP
// INPUT_PULLUP for bare ourSignalButton connected from GND to input pin
ourPushButton.attach(PIN_PUSH_BUTTON, INPUT); // USE EXTERNAL PULL-UP
// DEBOUNCE INTERVAL IN MILLISECONDS
ourPushButton.interval(50);
// INDICATE THAT THE LOW STATE CORRESPONDS TO PHYSICALLY PRESSING THE BUTTON
ourPushButton.setPressedState(LOW);
}
void updatePushButton(unsigned long aNow) {
ourPushButton.update();
static unsigned long history[5] = {0UL};;
static unsigned long reactOnMultiplePressed = 0;
static uint8_t buttonCnt=0;
#define CLEAR_HISTORY history[0] = 0L
#define MULTI_PRESS_TIMERANGE 1500
#define MULTI_PRESS_REACTION_TIME 700
// save the button press history
if (ourPushButton.pressed()) {
for (int i=4; i>0; i--) {
history[i] = history[i-1];
}
history[0] = aNow;
buttonCnt=0;
for (int i=0; i<5; i++) {
if ((aNow - history[i]) < MULTI_PRESS_TIMERANGE) {
buttonCnt++;
} else {
break;
}
}
logMsg(INFO, F("Button pressed: ") + String(buttonCnt));
reactOnMultiplePressed = history[buttonCnt-1] + MULTI_PRESS_REACTION_TIME;
} else if (ourPushButton.isPressed()) {
}
if (reactOnMultiplePressed) {
controlRotaryEncoder(false);
}
if (reactOnMultiplePressed && aNow > reactOnMultiplePressed) {
controlRotaryEncoder(true);
reactOnMultiplePressed=0;
static ToolContext backContext=BASE_MENU_PAGE;
CLEAR_HISTORY;
switch (buttonCnt) {
case 1:
switch (ourContext) {
case ANGLE_SENSOR_PAGE:
// save the context for back jump
backContext=ourContext;
ourContext=ANGLE_MENU_PAGE;
resetRotaryEncoder();