-
Notifications
You must be signed in to change notification settings - Fork 583
Expand file tree
/
Copy pathWiFiInterface.cpp
More file actions
2557 lines (2220 loc) · 73.6 KB
/
WiFiInterface.cpp
File metadata and controls
2557 lines (2220 loc) · 73.6 KB
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
/*
* WiFiInterface.cpp
*
* Created on: 27 Nov 2017
* Authors: Christian and David
*/
#include "WiFiInterface.h"
#if HAS_WIFI_NETWORKING
#include <Platform/Platform.h>
#include <Platform/RepRap.h>
#include <GCodes/GCodeBuffer/GCodeBuffer.h>
#include <Networking/HttpResponder.h>
#include <Networking/FtpResponder.h>
#include <Networking/TelnetResponder.h>
#if SUPPORT_MQTT
#include <Networking/MQTT/MqttClient.h>
#endif
#include "WifiFirmwareUploader.h"
#include <General/IP4String.h>
#include "WiFiSocket.h"
#include <Cache.h>
#include <AppNotifyIndices.h>
#if HAS_LWIP_NETWORKING && defined(DUET3MINI_V04)
# include "LwipEthernet/AllocateFromPbufPool.h"
#endif
static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and MessageFormats.h don't match");
// Define exactly one of the following as 1, the other as zero
#if SAM4E
# include <pmc/pmc.h>
# include <spi/spi.h>
// The PDC seems to be too slow to work reliably without getting transmit underruns, so we use the DMAC now.
# define USE_PDC 0 // use SAM4 peripheral DMA controller
# define USE_DMAC 1 // use SAM4 general DMA controller
# define USE_DMAC_MANAGER 0 // use SAMD/SAME DMA controller via DmacManager module
# define USE_XDMAC 0 // use SAME7 XDMA controller
#elif SAME70
# include <pmc/pmc.h>
# include <spi/spi.h>
# include <DmacManager.h>
# define USE_PDC 0 // use SAM4 peripheral DMA controller
# define USE_DMAC 0 // use SAM4 general DMA controller
# define USE_DMAC_MANAGER 0 // use SAMD/SAME DMA controller via DmacManager module
# define USE_XDMAC 1 // use SAME7 XDMA controller
static __nocache MessageBufferOut messageBufferOut;
static __nocache MessageBufferIn messageBufferIn;
#elif SAME5x
# include <DmacManager.h>
# include <Interrupts.h>
# include <Serial.h>
# include <AsyncSerial.h>
# define USE_PDC 0 // use SAM4 peripheral DMA controller
# define USE_DMAC 0 // use SAM4 general DMA controller
# define USE_DMAC_MANAGER 1 // use SAMD/SAME DMA controller via DmacManager module
# define USE_XDMAC 0 // use SAME7 XDMA controller
// Compatibility with existing RRF Code
constexpr Pin APIN_ESP_SPI_MISO = EspMisoPin;
constexpr Pin APIN_ESP_SPI_SCK = EspSclkPin;
constexpr IRQn ESP_SPI_IRQn = WiFiSpiSercomIRQn;
#else
# error Unknown board
#endif
#if USE_PDC
# include "pdc/pdc.h"
#endif
#if USE_DMAC
# include "dmac/dmac.h"
#endif
#if USE_XDMAC
# include "xdmac/xdmac.h"
#endif
#if !SAME5x
# include "matrix/matrix.h"
#endif
const uint32_t WiFiSlowResponseTimeoutMillis = 500; // SPI timeout when when the ESP has to access the SPIFFS filesytem; highest measured is 234ms.
const uint32_t WiFiFastResponseTimeoutMillis = 100; // SPI timeout when when the ESP does not have to access SPIFFS filesystem. 20ms is too short on Duet 2 with both FTP and Telnet enabled.
const uint32_t WiFiWaitReadyMillis = 100;
const uint32_t WiFiStartupMillis = 15000; // Formatting the SPIFFS partition can take up to 10s.
#if WIFI_USES_ESP32
const uint32_t WiFiStableMillis = 500; // Spin() fails in state starting2 when starting wifi in config.g if we use 300 or lower here. When testing, 400 was OK.
#else
const uint32_t WiFiStableMillis = 100;
#endif
const unsigned int MaxHttpConnections = 4;
#if SAME5x
void SerialWiFiPortInit(AsyncSerial*) noexcept
{
for (Pin p : WiFiUartSercomPins)
{
SetPinFunction(p, WiFiUartSercomPinsMode);
}
}
void SerialWiFiPortDeinit(AsyncSerial*) noexcept
{
for (Pin p : WiFiUartSercomPins)
{
pinMode(p, INPUT_PULLUP); // just enable pullups on TxD and RxD pins
}
}
#endif
// Static functions
static inline void DisableSpi() noexcept
{
#if SAME5x
WiFiSpiSercom->SPI.CTRLA.reg &= ~SERCOM_SPI_CTRLA_ENABLE;
while (WiFiSpiSercom->SPI.SYNCBUSY.reg & (SERCOM_SPI_SYNCBUSY_SWRST | SERCOM_SPI_SYNCBUSY_ENABLE)) { };
#else
spi_disable(ESP_SPI);
#endif
}
static inline void EnableSpi() noexcept
{
#if SAME5x
WiFiSpiSercom->SPI.CTRLA.reg |= SERCOM_SPI_CTRLA_ENABLE;
while (WiFiSpiSercom->SPI.SYNCBUSY.reg & (SERCOM_SPI_SYNCBUSY_SWRST | SERCOM_SPI_SYNCBUSY_ENABLE)) { };
#else
spi_enable(ESP_SPI);
#endif
}
// Clear the transmit and receive registers and put the SPI into slave mode, SPI mode 1
static inline void ResetSpi() noexcept
{
#if SAME5x
WiFiSpiSercom->SPI.CTRLA.reg |= SERCOM_SPI_CTRLA_SWRST;
while (WiFiSpiSercom->SPI.SYNCBUSY.reg & SERCOM_SPI_SYNCBUSY_SWRST) { };
WiFiSpiSercom->SPI.CTRLA.reg = SERCOM_SPI_CTRLA_CPHA | SERCOM_SPI_CTRLA_DIPO(3) | SERCOM_SPI_CTRLA_DOPO(0) | SERCOM_SPI_CTRLA_MODE(2);
WiFiSpiSercom->SPI.CTRLB.reg = SERCOM_SPI_CTRLB_RXEN | SERCOM_SPI_CTRLB_SSDE | SERCOM_SPI_CTRLB_PLOADEN;
while (WiFiSpiSercom->SPI.SYNCBUSY.reg & SERCOM_SPI_SYNCBUSY_MASK) { };
WiFiSpiSercom->SPI.CTRLC.reg = SERCOM_SPI_CTRLC_DATA32B;
#else
spi_reset(ESP_SPI); // this clears the transmit and receive registers and puts the SPI into slave mode
#endif
}
static void spi_dma_disable() noexcept;
#if !SAME5x
static bool spi_dma_check_rx_complete() noexcept;
#endif
#ifdef DUET3MINI
AsyncSerial *serialWiFiDevice;
# define SERIAL_WIFI_DEVICE (*serialWiFiDevice)
# if !defined(SERIAL_WIFI_ISR0) || !defined(SERIAL_WIFI_ISR2) || !defined(SERIAL_WIFI_ISR3)
# error SERIAL_WIFI_ISRn not defined
# endif
void SERIAL_WIFI_ISR0() noexcept
{
serialWiFiDevice->Interrupt0();
}
void SERIAL_WIFI_ISR2() noexcept
{
serialWiFiDevice->Interrupt2();
}
void SERIAL_WIFI_ISR3() noexcept
{
serialWiFiDevice->Interrupt3();
}
#else
#define SERIAL_WIFI_DEVICE (serialWiFi)
#endif
static volatile bool transferPending = false;
static WiFiInterface *wifiInterface;
#if 0
static void debugPrintBuffer(const char *msg, void *buf, size_t dataLength) noexcept
{
const size_t MaxDataToPrint = 20;
const uint8_t * const data = reinterpret_cast<const uint8_t *>(buf);
debugPrintf("%s %02x %02x %02x %02x %04x %04x %08x",
msg,
data[0], data[1], data[2], data[3],
*reinterpret_cast<const uint16_t*>(data + 4), *reinterpret_cast<const uint16_t*>(data + 6),
*reinterpret_cast<const uint32_t*>(data + 8));
if (dataLength != 0)
{
debugPrintf(" ");
for (size_t i = 0; i < min<size_t>(dataLength, MaxDataToPrint); ++i)
{
debugPrintf("%02x", data[i + 12]);
}
if (dataLength > MaxDataToPrint)
{
debugPrintf("...");
}
}
debugPrintf("\n");
}
#endif
static void EspTransferRequestIsr(CallbackParameter) noexcept
{
wifiInterface->EspRequestsTransfer();
}
static inline void EnableEspInterrupt() noexcept
{
attachInterrupt(EspDataReadyPin, EspTransferRequestIsr, InterruptMode::rising, CallbackParameter(nullptr));
}
static inline void DisableEspInterrupt() noexcept
{
detachInterrupt(EspDataReadyPin);
}
static const char* GetWiFiAuthFriendlyStr(WiFiAuth auth) noexcept
{
const char* res = "Unknown";
switch (auth)
{
case WiFiAuth::OPEN:
res = "Open";
break;
case WiFiAuth::WEP:
res = "WEP";
break;
case WiFiAuth::WPA_PSK:
res = "WPA-Personal";
break;
case WiFiAuth::WPA2_PSK:
res = "WPA2-Personal";
break;
case WiFiAuth::WPA_WPA2_PSK:
res = "WPA/WPA2-Personal";
break;
case WiFiAuth::WPA2_ENTERPRISE:
res = "WPA2-Enterprise";
break;
case WiFiAuth::WPA3_PSK:
res = "WPA3-Personal";
break;
case WiFiAuth::WPA2_WPA3_PSK:
res = "WPA2/WPA3-Personal";
break;
case WiFiAuth::WAPI_PSK:
res = "WAPI-Personal";
break;
default:
break;
}
return res;
}
/*-----------------------------------------------------------------------------------*/
// WiFi interface class
WiFiInterface::WiFiInterface(Platform& p) noexcept
: platform(p), bufferOut(nullptr), bufferIn(nullptr), uploader(nullptr), espWaitingTask(nullptr),
ftpDataPort(0), closeDataPort(false),
requestedMode(WiFiState::disabled), currentMode(WiFiState::disabled), activated(false),
espStatusChanged(false), spiTxUnderruns(0), spiRxOverruns(0), serialRunning(false), debugMessageChars(0)
{
wifiInterface = this;
// Create the sockets
for (WiFiSocket*& skt : sockets)
{
skt = new WiFiSocket(this);
}
actualSsid.copy("(unknown)");
wiFiServerVersion.copy("(unknown)");
#ifdef DUET3MINI
serialWiFiDevice = new AsyncSerial(WiFiUartSercomNumber, WiFiUartRxPad, 512, 512, SerialWiFiPortInit, SerialWiFiPortDeinit);
serialWiFiDevice->setInterruptPriority(NvicPriorityWiFiUartRx, NvicPriorityWiFiUartTx);
#else
SERIAL_WIFI_DEVICE.setInterruptPriority(NvicPriorityWiFiUart);
#endif
}
#if SUPPORT_OBJECT_MODEL
// Object model table and functions
// Note: if using GCC version 7.3.1 20180622 and lambda functions are used in this table, you must compile this file with option -std=gnu++17.
// Otherwise the table will be allocated in RAM instead of flash, which wastes too much RAM.
// Macro to build a standard lambda function that includes the necessary type conversions
#define OBJECT_MODEL_FUNC(...) OBJECT_MODEL_FUNC_BODY(WiFiInterface, __VA_ARGS__)
#define OBJECT_MODEL_FUNC_IF(_condition,...) OBJECT_MODEL_FUNC_IF_BODY(WiFiInterface, _condition, __VA_ARGS__)
constexpr ObjectModelTableEntry WiFiInterface::objectModelTable[] =
{
// These entries must be in alphabetical order
{ "actualIP", OBJECT_MODEL_FUNC(self->ipAddress), ObjectModelEntryFlags::none },
{ "firmwareVersion", OBJECT_MODEL_FUNC(self->wiFiServerVersion.c_str()), ObjectModelEntryFlags::none },
{ "gateway", OBJECT_MODEL_FUNC(self->gateway), ObjectModelEntryFlags::none },
{ "mac", OBJECT_MODEL_FUNC_IF(self->GetState() == NetworkState::active, self->macAddress), ObjectModelEntryFlags::none },
{ "ssid", OBJECT_MODEL_FUNC_IF(self->GetState() == NetworkState::active, self->actualSsid.c_str()), ObjectModelEntryFlags::none },
{ "state", OBJECT_MODEL_FUNC(self->GetStateName()), ObjectModelEntryFlags::none },
{ "subnet", OBJECT_MODEL_FUNC(self->netmask), ObjectModelEntryFlags::none },
{ "type", OBJECT_MODEL_FUNC_NOSELF("wifi"), ObjectModelEntryFlags::none },
};
constexpr uint8_t WiFiInterface::objectModelTableDescriptor[] = { 1, 8 };
DEFINE_GET_OBJECT_MODEL_TABLE(WiFiInterface)
#endif
void WiFiInterface::Init() noexcept
{
interfaceMutex.Create("WiFi");
// Make sure the ESP8266 is held in the reset state
ResetWiFi();
lastTickMillis = millis();
SetIPAddress(DefaultIpAddress, DefaultNetMask, DefaultGateway);
for (size_t i = 0; i < NumWiFiTcpSockets; ++i)
{
sockets[i]->Init(i);
}
currentSocket = 0;
}
void WiFiInterface::IfaceStartProtocol(NetworkProtocol protocol) noexcept
{
switch(protocol)
{
case HttpProtocol:
SendListenCommand(portNumbers[protocol], protocol, MaxHttpConnections);
break;
case FtpProtocol:
SendListenCommand(portNumbers[protocol], protocol, 1);
break;
case TelnetProtocol:
SendListenCommand(portNumbers[protocol], protocol, 1);
break;
default:
break;
}
// mDNS announcement is done by the WiFi Server firmware
}
void WiFiInterface::IfaceShutdownProtocol(NetworkProtocol protocol, bool permanent) noexcept
{
switch(protocol)
{
case HttpProtocol:
StopListening(portNumbers[protocol]);
TerminateSockets(portNumbers[protocol]);
break;
case FtpProtocol:
StopListening(portNumbers[protocol]);
TerminateSockets(portNumbers[protocol]);
if (ftpDataPort != 0)
{
StopListening(ftpDataPort);
TerminateSockets(ftpDataPort);
}
break;
case TelnetProtocol:
StopListening(portNumbers[protocol]);
TerminateSockets(portNumbers[protocol]);
break;
#if SUPPORT_MQTT
case MqttProtocol:
TerminateSockets(portNumbers[protocol], false);
break;
#endif
default:
break;
}
}
#if HAS_CLIENTS
void WiFiInterface::ConnectProtocol(NetworkProtocol protocol) noexcept
{
MutexLocker lock(interfaceMutex);
switch(protocol)
{
#if SUPPORT_MQTT
case MqttProtocol:
SendConnectCommand(portNumbers[protocol], protocol, ipAddresses[protocol]);
break;
#endif
default:
break;
}
}
#endif
NetworkProtocol WiFiInterface::GetProtocolByLocalPort(TcpPort port) const noexcept
{
if (port == ftpDataPort)
{
return FtpDataProtocol;
}
for (NetworkProtocol p : ARRAY_INDICES(portNumbers))
{
if (portNumbers[p] == port)
{
return p;
}
}
return AnyProtocol;
}
// This is called at the end of config.g processing.
// Start the network if it was enabled
void WiFiInterface::Activate() noexcept
{
if (!activated)
{
activated = true;
#if SAME70
bufferOut = &messageBufferOut;
bufferIn = &messageBufferIn;
#elif HAS_LWIP_NETWORKING && defined(DUET3MINI_V04)
{
void *const mem = AllocateFromPbufPool(sizeof(MessageBufferOut));
bufferOut = (mem != nullptr) ? new (mem) MessageBufferOut : new MessageBufferOut;
}
{
void *const mem = AllocateFromPbufPool(sizeof(MessageBufferIn));
bufferIn = (mem != nullptr) ? new (mem) MessageBufferIn : new MessageBufferIn;
}
#else
bufferOut = new MessageBufferOut;
bufferIn = new MessageBufferIn;
#endif
#if HAS_MASS_STORAGE || HAS_EMBEDDED_FILES
uploader = new WifiFirmwareUploader(SERIAL_WIFI_DEVICE, *this);
#endif
if (requestedMode != WiFiState::disabled)
{
Start();
}
else
{
platform.Message(UsbMessage, "WiFi is disabled.\n");
}
}
}
void WiFiInterface::Exit() noexcept
{
Stop();
}
// Get the network state into the reply buffer, returning true if there is some sort of error
GCodeResult WiFiInterface::GetNetworkState(const StringRef& reply) noexcept
{
switch (GetState())
{
case NetworkState::disabled:
reply.copy("WiFi module is disabled");
break;
case NetworkState::starting1:
case NetworkState::starting2:
reply.copy("WiFi module is being started");
break;
case NetworkState::changingMode:
reply.copy("WiFi module is changing mode");
break;
case NetworkState::active:
reply.copy("WiFi module is ");
reply.cat(TranslateWiFiState(currentMode));
if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
{
reply.catf("%s, IP address %s", actualSsid.c_str(), IP4String(ipAddress).c_str());
}
break;
case NetworkState::idle:
reply.copy("WiFi module is idle");
break;
default:
reply.copy("Unknown network state");
return GCodeResult::error;
break;
}
return GCodeResult::ok;
}
// Start up the ESP. We assume it is not already started.
// ESP8266 boot modes:
// GPIO0 GPIO2 GPIO15
// 0 1 0 Firmware download from UART
// 1 1 0 Normal boot from flash memory
// 0 0 1 SD card boot (not used on Duet)
void WiFiInterface::Start() noexcept
{
// The ESP8266 is held in a reset state by a pulldown resistor until we enable it.
// Make sure the ESP8266 is in the reset state
#if !WIFI_USES_ESP32
pinMode(EspResetPin, OUTPUT_LOW);
#endif
pinMode(EspEnablePin, OUTPUT_LOW);
// Set up our transfer request pin (GPIO4) as an output and set it low
pinMode(SamTfrReadyPin, OUTPUT_LOW);
// Set up our data ready pin (ESP8266 and ESP32 GPIO0) as an output and set it high ready to boot the ESP from flash
pinMode(EspDataReadyPin, OUTPUT_HIGH);
#if WIFI_USES_ESP32
pinMode(SamCsPin, INPUT_PULLUP); // ensure that SS is pulled high
#else
// Set our CS input (ESP8266 GPIO15) low ready for booting the ESP. This also clears the transfer ready latch on older Duet 2 boards.
pinMode(SamCsPin, OUTPUT_LOW);
// ESP8266 GPIO2 also needs to be high to boot. It's connected to MISO on the SAM, so set the pullup resistor on that pin
pinMode(APIN_ESP_SPI_MISO, INPUT_PULLUP);
#endif
// Make sure it has time to reset - no idea how long it needs, but 20ms should be plenty
delay(50);
// Release the reset on the ESP8266
StartWiFi();
// Give it time to sample GPIO0 and GPIO15
// GPIO0 has to be held high for sufficient time:
// - 10ms is not enough
// - 18ms after reset is released, an oscillating signal appears on GPIO0 for 55ms
// - so 18ms is probably long enough. Use 50ms for safety.
delay(50);
#if !WIFI_USES_ESP32
// Relinquish control of our CS pin so that the ESP can take it over
pinMode(SamCsPin, INPUT);
#endif
// Set the data request pin to be an input
pinMode(EspDataReadyPin, INPUT_PULLUP);
// The ESP takes about 300ms before it starts talking to us, so don't wait for it here, do that in Spin()
spiTxUnderruns = spiRxOverruns = 0;
reconnectCount = 0;
transferAlreadyPendingCount = readyTimeoutCount = responseTimeoutCount = 0;
lastTickMillis = millis();
lastDataReadyPinState = 0;
risingEdges = 0;
SetState(NetworkState::starting1);
}
// Stop the ESP
void WiFiInterface::Stop() noexcept
{
if (GetState() != NetworkState::disabled)
{
MutexLocker lock(interfaceMutex);
digitalWrite(SamTfrReadyPin, false); // tell the ESP we can't receive
#if !WIFI_USES_ESP32
digitalWrite(EspResetPin, false); // put the ESP back into reset
#endif
digitalWrite(EspEnablePin, false);
DisableEspInterrupt(); // ignore IRQs from the transfer request pin
NVIC_DisableIRQ(ESP_SPI_IRQn);
DisableSpi();
#if !SAME5x
spi_dma_check_rx_complete();
#endif
spi_dma_disable();
SetState(NetworkState::disabled);
currentMode = WiFiState::disabled;
}
}
bool WiFiInterface::GetFirmwareVersion(int &major, int &minor, int &patch)
{
// Simple parser for WiFi module firmware version string.
// Parse the format (x=major, y=minor, and z=patch):
// - x.y.z (from 2.1.0)
// - x.y (prior to 2.1.0), returns -1 for z
// Should be able to handle appended string after the version string.
major = minor = patch = -1;
auto numbers = {&major, &minor, &patch};
const char *curr = wiFiServerVersion.c_str();
const char *end = nullptr;
for (auto num : numbers)
{
int temp = StrToI32(curr, &end);
if (curr == end)
{
if (num != &patch)
{
return false;
}
break;
}
*num = temp;
curr = end + 1;
end = nullptr;
}
return true;
}
void WiFiInterface::Spin() noexcept
{
// Main state machine.
switch (GetState())
{
case NetworkState::starting1:
{
const bool currentDataReadyPinState = digitalRead(EspDataReadyPin);
if (currentDataReadyPinState != lastDataReadyPinState)
{
if (currentDataReadyPinState && risingEdges < 10)
{
risingEdges++;
}
lastDataReadyPinState = currentDataReadyPinState;
}
// The ESP toggles CS before it has finished starting up, so don't look at the CS signal too soon
const uint32_t now = millis();
if (risingEdges >= 2) // the first rising edge is the one coming out of reset
{
lastTickMillis = now;
startupRetryCount = 0;
SetState(NetworkState::starting2);
}
else
{
if (now - lastTickMillis >= WiFiStartupMillis) // time wait expired
{
platform.Message(NetworkInfoMessage, "WiFi module disabled - start timed out\n");
SetState(NetworkState::disabled);
}
}
}
break;
case NetworkState::starting2:
{
// See if the WiFi module has kept its pins at their stable values for long enough
const uint32_t now = millis();
if (digitalRead(SamCsPin) && digitalRead(EspDataReadyPin) && !digitalRead(APIN_ESP_SPI_SCK))
{
if (now - lastTickMillis >= WiFiStableMillis)
{
// Setup the SPI controller in slave mode and assign the CS pin to it
platform.Message(NetworkInfoMessage, "WiFi module started\n");
SetupSpi(); // set up the SPI subsystem
// Read the status to get the WiFi server version and MAC address
Receiver<NetworkStatusResponse> status;
int32_t rc = SendCommand(NetworkCommand::networkGetStatus, 0, 0, nullptr, 0, status);
if (rc >= (int32_t)MinimumStatusResponseLength)
{
wiFiServerVersion.copy(status.Value().versionText);
macAddress.SetFromBytes(status.Value().macAddress);
// Set the hostname before anything else is done
rc = SendCommand(NetworkCommand::networkSetHostName, 0, 0, 0, reprap.GetNetwork().GetHostname(), HostNameLength, nullptr, 0);
if (rc != ResponseEmpty)
{
reprap.GetPlatform().MessageF(NetworkErrorMessage, "failed to set WiFi hostname: %s\n", TranslateWiFiResponse(rc));
}
#if SAME5x
int majorVer = 0, dummy = -1;
// If running the RTOS-based WiFi module code, tell the module to increase SPI clock speed to 40MHz.
// This is safe on SAME5x processors but not on SAM4 processors.
if (GetFirmwareVersion(majorVer, dummy, dummy) && (majorVer >= 2))
{
rc = SendCommand(NetworkCommand::networkSetClockControl, 0, 0, 0x2001, nullptr, 0, nullptr, 0);
if (rc != ResponseEmpty)
{
reprap.GetPlatform().MessageF(NetworkErrorMessage, "failed to set WiFi SPI speed: %s\n", TranslateWiFiResponse(rc));
}
}
#endif
SetState(NetworkState::idle);
espStatusChanged = true; // make sure we fetch the current state and enable the ESP interrupt
}
else if (startupRetryCount < 3)
{
// When we use the ESP32 module, the first startup attempt often fails when we try to start up straight after running config.g
++startupRetryCount;
lastTickMillis = now;
}
else
{
// Something went wrong, maybe a bad firmware image was flashed. Disable the WiFi chip again in this case
Stop();
platform.MessageF(NetworkErrorMessage, "failed to initialise WiFi module: %s\n", TranslateWiFiResponse(rc));
}
}
}
else
{
lastTickMillis = now;
}
}
break;
case NetworkState::disabled:
#if HAS_MASS_STORAGE || HAS_EMBEDDED_FILES
if (uploader != nullptr)
{
uploader->Spin();
}
#endif
break;
case NetworkState::idle:
case NetworkState::active:
if (espStatusChanged && digitalRead(EspDataReadyPin))
{
if (reprap.Debug(Module::WiFi))
{
debugPrintf("ESP reported status change\n");
}
GetNewStatus();
}
else if ( currentMode != requestedMode
&& currentMode != WiFiState::connecting
&& currentMode != WiFiState::reconnecting
&& currentMode != WiFiState::autoReconnecting
)
{
// Tell the wifi module to change mode
int32_t rslt = ResponseUnknownError;
if (currentMode != WiFiState::idle)
{
// We must set WiFi module back to idle before changing to the new state
rslt = SendCommand(NetworkCommand::networkStop, 0, 0, 0, nullptr, 0, nullptr, 0);
}
else if (requestedMode == WiFiState::connected)
{
rslt = SendCommand(NetworkCommand::networkStartClient, 0, 0, 0, requestedSsid.Pointer(), requestedSsid.Capacity(), nullptr, 0);
}
else if (requestedMode == WiFiState::runningAsAccessPoint)
{
rslt = SendCommand(NetworkCommand::networkStartAccessPoint, 0, 0, 0, nullptr, 0, nullptr, 0);
}
if (rslt >= 0)
{
SetState(NetworkState::changingMode);
}
else
{
Stop();
platform.MessageF(NetworkErrorMessage, "failed to change WiFi mode: %s\n", TranslateWiFiResponse(rslt));
}
}
else if (currentMode == WiFiState::connected || currentMode == WiFiState::runningAsAccessPoint)
{
#if HAS_CLIENTS
// Maintain client connections
for (uint8_t p = 0; p < NumSelectableProtocols; p++)
{
if (protocolEnabled[p])
{
if (reprap.GetNetwork().StartClient(this, p))
{
ConnectProtocol(p);
}
}
else
{
reprap.GetNetwork().StopClient(this, p);
}
}
#endif
// Find the next socket to poll
const size_t startingSocket = currentSocket;
do
{
if (sockets[currentSocket]->NeedsPolling())
{
break;
}
++currentSocket;
if (currentSocket == NumWiFiTcpSockets)
{
currentSocket = 0;
}
} while (currentSocket != startingSocket);
// Either the current socket needs polling, or no sockets do but we must still poll one of them to get notified of any new connections
sockets[currentSocket]->Poll();
++currentSocket;
if (currentSocket == NumWiFiTcpSockets)
{
currentSocket = 0;
}
// Check if the data port needs to be closed
if (closeDataPort)
{
for (WiFiSocket *s : sockets)
{
if (s->GetProtocol() == FtpDataProtocol)
{
if (!s->IsClosing())
{
TerminateDataPort();
}
break;
}
}
}
}
break;
case NetworkState::changingMode:
// Here when we have asked the ESP to change mode. Don't leave this state until we have a new status report from the ESP.
if (espStatusChanged && digitalRead(EspDataReadyPin))
{
GetNewStatus();
switch (currentMode)
{
case WiFiState::connecting:
case WiFiState::reconnecting:
case WiFiState::autoReconnecting:
break; // let the connect attempt continue
case WiFiState::connected:
case WiFiState::runningAsAccessPoint:
SetState(NetworkState::active);
{
// Get our IP address, this needs to be correct for FTP to work
Receiver<NetworkStatusResponse> status;
if (SendCommand(NetworkCommand::networkGetStatus, 0, 0, nullptr, 0, status) >= (int32_t)MinimumStatusResponseLength)
{
ipAddress.SetV4LittleEndian(status.Value().ipAddress);
actualSsid.copy(status.Value().ssid);
}
InitSockets();
reconnectCount = 0;
platform.MessageF(NetworkInfoMessage, "WiFi module is %s%s, IP address %s\n",
TranslateWiFiState(currentMode),
actualSsid.c_str(),
IP4String(ipAddress).c_str());
}
break;
case WiFiState::idle:
default:
if (requestedMode != WiFiState::connected)
{
requestedMode = currentMode; // don't keep repeating the request if it failed and it wasn't a connect request
}
SetState(NetworkState::idle);
platform.MessageF(NetworkInfoMessage, "WiFi module is %s\n", TranslateWiFiState(currentMode));
break;
}
}
break;
default:
break;
}
// Check for debug info received from the WiFi module
if (serialRunning)
{
while (!debugPrintPending && SERIAL_WIFI_DEVICE.available() != 0)
{
const char c = (char)SERIAL_WIFI_DEVICE.read();
if (c == '\n')
{
debugPrintPending = true;
}
else if (c != '\r')
{
debugMessageBuffer[debugMessageChars++] = c;
if (debugMessageChars == ARRAY_SIZE(debugMessageBuffer) - 1)
{
debugPrintPending = true;
}
}
}
}
// Check for debug info received from the WiFi module
if (debugPrintPending)
{
if (reprap.Debug(Module::WiFi))
{
debugMessageBuffer[debugMessageChars] = 0;
debugPrintf("WiFi: %s\n", debugMessageBuffer);
}
debugMessageChars = 0;
debugPrintPending = false;
}
}
// Translate a ESP8266 reset reason to text. Keep this in step with the codes used in file MessageFormats.h in the WiFi server project.
const char* WiFiInterface::TranslateEspResetReason(uint32_t reason) noexcept
{
// Mapping from known ESP reset codes to reasons
static const char * const resetReasonTexts[] =
{
"Power up",
"Hardware watchdog",
"Exception",
"Software watchdog",
"Software restart",
"Deep-sleep wakeup",
"Turned on by main processor",
"Brownout",
"SDIO reset",
"Unknown"
};
return (reason < sizeof(resetReasonTexts)/sizeof(resetReasonTexts[0]))
? resetReasonTexts[reason]
: "Unrecognised";
}
void WiFiInterface::Diagnostics(MessageType mtype) noexcept
{
platform.MessageF(mtype,
"=== WiFi ===\nInterface state: %s\n"
"Module is %s\n"
"Failed messages: pending %u, notrdy %u, noresp %u\n",
GetStateName(),
TranslateWiFiState(currentMode),
transferAlreadyPendingCount, readyTimeoutCount, responseTimeoutCount
);
if (GetState() != NetworkState::disabled && GetState() != NetworkState::starting1 && GetState() != NetworkState::starting2)
{
Receiver<NetworkStatusResponse> status;
status.Value().clockReg = 0xFFFFFFFF; // older WiFi firmware doesn't return this value, so preset it