From 9161ccc15ce93405ef658a4096acbf63db68b32c Mon Sep 17 00:00:00 2001 From: David Crocker Date: Fri, 23 Sep 2022 08:54:18 +0100 Subject: Fixed issue on MB6XD with endstops/Z probes stopping external drivers --- src/Movement/DDA.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/Movement/DDA.cpp b/src/Movement/DDA.cpp index 5ea10f5b..751841c0 100644 --- a/src/Movement/DDA.cpp +++ b/src/Movement/DDA.cpp @@ -1498,7 +1498,7 @@ void DDA::Prepare(SimulationMode simMode) noexcept if ( platform.GetDriversBitmap(drive) != 0 // if any of the drives is local #if SUPPORT_CAN_EXPANSION - || flags.checkEndstops // if checking endstops, create a DM even if there are no local drives involved + || flags.checkEndstops // if checking endstops or a Z probe, create a DM even if there are no local drives involved #endif ) { @@ -2061,12 +2061,12 @@ void DDA::StepDrivers(Platform& p, uint32_t now) noexcept // Trigger the TC so that it generates a step pulse STEP_GATE_TC->TC_CHANNEL[STEP_GATE_TC_CHAN].TC_CCR = TC_CCR_SWTRG; lastStepHighTime = StepTimer::GetTimerTicks(); + } - // Calculate the next step times - for (DriveMovement *dm2 = activeDMs; dm2 != dm; dm2 = dm2->nextDM) - { - (void)dm2->CalcNextStepTime(*this); // calculate next step times - } + // Calculate the next step times. We must do this even if no local drivers are stepping in case endstops or Z probes are active. + for (DriveMovement *dm2 = activeDMs; dm2 != dm; dm2 = dm2->nextDM) + { + (void)dm2->CalcNextStepTime(*this); // calculate next step times } #else # if SUPPORT_SLOW_DRIVERS // if supporting slow drivers -- cgit v1.2.3 From 7435c50300e113b276c508456286381429c26af7 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Mon, 19 Sep 2022 12:59:22 +0100 Subject: Support optional WiFi extension to MB6HC --- .cproject | 2 +- src/Config/Pins_Duet3_MB6HC.h | 30 +++++++++++-- src/Config/Pins_DuetNG.h | 7 ++- src/Hardware/SAM4E/Devices.cpp | 12 ++--- src/Hardware/SAM4E/Devices.h | 2 +- src/Hardware/SAME70/Devices.cpp | 22 ++++++++++ src/Hardware/SAME70/Devices.h | 4 ++ src/Networking/ESP8266WiFi/WiFiInterface.cpp | 25 +++++++---- src/Networking/Network.cpp | 66 ++++++++++++++++------------ src/Networking/Network.h | 27 ++++++++++-- src/Platform/RepRap.cpp | 3 ++ 11 files changed, 144 insertions(+), 56 deletions(-) diff --git a/.cproject b/.cproject index 1280d93a..ec0fce31 100644 --- a/.cproject +++ b/.cproject @@ -612,7 +612,7 @@ - + diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index 2dab95d8..5705b09d 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -14,10 +14,12 @@ #define IAP_CAN_LOADER_FILE "Duet3_CANiap32_" BOARD_SHORT_NAME ".bin" constexpr uint32_t IAP_IMAGE_START = 0x20458000; // last 32kb of RAM +#define WIFI_FIRMWARE_FILE "DuetWiFiServer_32S3.bin" + // Features definition // Networking support #define HAS_LWIP_NETWORKING 1 -#define HAS_WIFI_NETWORKING 0 +#define HAS_WIFI_NETWORKING 1 // Storage support #define HAS_SBC_INTERFACE 1 @@ -386,6 +388,28 @@ constexpr Pin APIN_SBC_SPI_SCK = PortCPin(24); constexpr Pin APIN_SBC_SPI_SS0 = PortCPin(25); constexpr GpioPinFunction SBCPinPeriphMode = GpioPinFunction::C; +// WiFi pins, mostly shared with the SBC interface +#define ESP_SPI SPI1 +#define ESP_SPI_INTERFACE_ID ID_SPI1 +#define ESP_SPI_IRQn SPI1_IRQn +#define ESP_SPI_HANDLER SPI1_Handler + +constexpr Pin APIN_ESP_SPI_MOSI = PortCPin(27); +constexpr Pin APIN_ESP_SPI_MISO = PortCPin(26); +constexpr Pin APIN_ESP_SPI_SCK = PortCPin(24); +constexpr Pin APIN_ESP_SPI_SS0 = PortCPin(25); +constexpr GpioPinFunction SPIPeriphMode = GpioPinFunction::C; + +constexpr Pin APIN_SerialWiFi_TXD = PortDPin(19); +constexpr Pin APIN_SerialWiFi_RXD = PortDPin(18); +constexpr GpioPinFunction SerialWiFiPeriphMode = GpioPinFunction::C; + +constexpr Pin EspResetPin = PortCPin(14); // Low on this in holds the WiFi module in reset (ESP_RESET) +constexpr Pin EspEnablePin = NoPin; // High to enable the WiFi module, low to power it down (ESP_CH_PD) +constexpr Pin EspDataReadyPin = PortAPin(2); // Input from the WiFi module indicating that it wants to transfer data (ESP GPIO0) +constexpr Pin SamTfrReadyPin = PortEPin(2); // Output from the SAM to the WiFi module indicating we can accept a data transfer (ESP GPIO4 via 7474) +constexpr Pin SamCsPin = PortCPin(25); // SPI NPCS pin, input from WiFi module + // CAN constexpr Pin APIN_CAN0_RX = PortBPin(3); constexpr Pin APIN_CAN0_TX = PortBPin(2); @@ -417,8 +441,8 @@ constexpr Pin SbcTfrReadyPin = PortEPin(2); // DMA channel allocation constexpr DmaChannel DmacChanHsmci = 0; // this is hard coded in the ASF HSMCI driver -//constexpr DmaChannel DmacChanWiFiTx = 1; // only on v0.3 board -//constexpr DmaChannel DmacChanWiFiRx = 2; // only on v0.3 board +constexpr DmaChannel DmacChanWiFiTx = 1; +constexpr DmaChannel DmacChanWiFiRx = 2; constexpr DmaChannel DmacChanTmcTx = 3; constexpr DmaChannel DmacChanTmcRx = 4; constexpr DmaChannel DmacChanSbcTx = 5; diff --git a/src/Config/Pins_DuetNG.h b/src/Config/Pins_DuetNG.h index 09e53fe6..e9c507dd 100644 --- a/src/Config/Pins_DuetNG.h +++ b/src/Config/Pins_DuetNG.h @@ -139,7 +139,6 @@ constexpr size_t MaxSpindles = 4; // Maximum number of configurable spindles constexpr size_t NumSerialChannels = 2; // The number of serial IO channels not counting the WiFi serial connection (USB and one auxiliary UART) #define SERIAL_MAIN_DEVICE SerialUSB #define SERIAL_AUX_DEVICE Serial -#define SERIAL_WIFI_DEVICE Serial1 constexpr Pin UsbVBusPin = PortCPin(22); // Pin used to monitor VBUS on USB port @@ -483,9 +482,9 @@ constexpr Pin APIN_Serial0_TXD = PortAPin(10); constexpr GpioPinFunction Serial0PeriphMode = GpioPinFunction::A; // Serial1 -constexpr Pin APIN_Serial1_RXD = PortAPin(5); -constexpr Pin APIN_Serial1_TXD = PortAPin(6); -constexpr GpioPinFunction Serial1PeriphMode = GpioPinFunction::C; +constexpr Pin APIN_SerialWiFi_RXD = PortAPin(5); +constexpr Pin APIN_SerialWiFi_TXD = PortAPin(6); +constexpr GpioPinFunction SerialWiFiPeriphMode = GpioPinFunction::C; // Duet pin numbers to control the WiFi interface on the Duet WiFi #define ESP_SPI SPI diff --git a/src/Hardware/SAM4E/Devices.cpp b/src/Hardware/SAM4E/Devices.cpp index c5a5fcae..2dbbfc08 100644 --- a/src/Hardware/SAM4E/Devices.cpp +++ b/src/Hardware/SAM4E/Devices.cpp @@ -11,8 +11,8 @@ #include #include -AsyncSerial Serial (UART0, UART0_IRQn, ID_UART0, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); -AsyncSerial Serial1(UART1, UART1_IRQn, ID_UART1, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +AsyncSerial Serial(UART0, UART0_IRQn, ID_UART0, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); +AsyncSerial SerialWiFi(UART1, UART1_IRQn, ID_UART1, 512, 512, [](AsyncSerial*) noexcept { }, [](AsyncSerial*) noexcept { }); SerialCDC SerialUSB; void UART0_Handler(void) noexcept @@ -22,7 +22,7 @@ void UART0_Handler(void) noexcept void UART1_Handler(void) noexcept { - Serial1.IrqHandler(); + SerialWiFi.IrqHandler(); } void SerialInit() noexcept @@ -31,9 +31,9 @@ void SerialInit() noexcept SetPinFunction(APIN_Serial0_TXD, Serial0PeriphMode); EnablePullup(APIN_Serial0_RXD); - SetPinFunction(APIN_Serial1_RXD, Serial1PeriphMode); - SetPinFunction(APIN_Serial1_TXD, Serial1PeriphMode); - EnablePullup(APIN_Serial1_RXD); + SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); + SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); + EnablePullup(APIN_SerialWiFi_RXD); } void SdhcInit() noexcept diff --git a/src/Hardware/SAM4E/Devices.h b/src/Hardware/SAM4E/Devices.h index dbac6b94..df072e76 100644 --- a/src/Hardware/SAM4E/Devices.h +++ b/src/Hardware/SAM4E/Devices.h @@ -11,7 +11,7 @@ #include extern AsyncSerial Serial; -extern AsyncSerial Serial1; +extern AsyncSerial SerialWiFi; #define SUPPORT_USB 1 // needed by SerialCDC.h #include diff --git a/src/Hardware/SAME70/Devices.cpp b/src/Hardware/SAME70/Devices.cpp index 2af3ed6a..1e47f4a5 100644 --- a/src/Hardware/SAME70/Devices.cpp +++ b/src/Hardware/SAME70/Devices.cpp @@ -37,6 +37,21 @@ USARTClass Serial1(USART2, USART2_IRQn, ID_USART2, 512, 512, } ); +#if defined(DUET3_MB6HC) +AsyncSerial SerialWiFi(UART4, UART4_IRQn, ID_UART4, 512, 512, + [](AsyncSerial*) noexcept + { + SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); + SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); + }, + [](AsyncSerial*) noexcept + { + ClearPinFunction(APIN_SerialWiFi_RXD); + ClearPinFunction(APIN_SerialWiFi_TXD); + } + ); +#endif + SerialCDC SerialUSB; void UART2_Handler(void) noexcept @@ -49,6 +64,13 @@ void USART2_Handler(void) noexcept Serial1.IrqHandler(); } +#if defined(DUET3_MB6HC) +void UART4_Handler(void) noexcept +{ + SerialWiFi.IrqHandler(); +} +#endif + void SdhcInit() noexcept { SetPinFunction(HsmciMclkPin, HsmciMclkPinFunction); diff --git a/src/Hardware/SAME70/Devices.h b/src/Hardware/SAME70/Devices.h index 22e03e47..87b5de23 100644 --- a/src/Hardware/SAME70/Devices.h +++ b/src/Hardware/SAME70/Devices.h @@ -14,6 +14,10 @@ extern AsyncSerial Serial; extern USARTClass Serial1; +#if defined(DUET3_MB6HC) +extern AsyncSerial SerialWiFi; +#endif + #define SUPPORT_USB 1 // needed by SerialCDC.h #include "SerialCDC.h" diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 9e08438b..07ea4e6b 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -36,7 +36,10 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and # define USE_DMAC_MANAGER 0 // use SAMD/SAME DMA controller via DmacManager module # define USE_XDMAC 0 // use SAME7 XDMA controller -#elif defined(DUET3_V03) || defined(SAME70XPLD) +#elif defined(DUET3_MB6HC) + +# include +# include # define USE_PDC 0 // use SAM4 peripheral DMA controller # define USE_DMAC 0 // use SAM4 general DMA controller @@ -186,6 +189,10 @@ void SERIAL_WIFI_ISR3() noexcept SerialWiFiDevice->Interrupt3(); } +#else + +#define SERIAL_WIFI_DEVICE (SerialWiFi) + #endif static volatile bool transferPending = false; @@ -2042,8 +2049,8 @@ void WiFiInterface::StartWiFi() noexcept #endif #if !SAME5x && !defined(__LPC17xx__) - SetPinFunction(APIN_Serial1_TXD, Serial1PeriphMode); // connect the pins to the UART - SetPinFunction(APIN_Serial1_RXD, Serial1PeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif SERIAL_WIFI_DEVICE.begin(WiFiBaudRate); // initialise the UART, to receive debug info debugMessageChars = 0; @@ -2061,8 +2068,8 @@ void WiFiInterface::ResetWiFi() noexcept #endif #if !defined(SAME5x) - pinMode(APIN_Serial1_TXD, INPUT_PULLUP); // just enable pullups on TxD and RxD pins - pinMode(APIN_Serial1_RXD, INPUT_PULLUP); + pinMode(APIN_SerialWiFi_TXD, INPUT_PULLUP); // just enable pullups on TxD and RxD pins + pinMode(APIN_SerialWiFi_RXD, INPUT_PULLUP); #endif currentMode = WiFiState::disabled; @@ -2113,15 +2120,15 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept if (external) { #if !defined(DUET3MINI) - pinMode(APIN_Serial1_TXD, INPUT_PULLUP); // just enable pullups on TxD and RxD pins - pinMode(APIN_Serial1_RXD, INPUT_PULLUP); + pinMode(APIN_SerialWiFi_TXD, INPUT_PULLUP); // just enable pullups on TxD and RxD pins + pinMode(APIN_SerialWiFi_RXD, INPUT_PULLUP); #endif } else { #if !SAME5x && !defined(__LPC17xx__) - SetPinFunction(APIN_Serial1_TXD, Serial1PeriphMode); // connect the pins to the UART - SetPinFunction(APIN_Serial1_RXD, Serial1PeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif } diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp index 376b90f6..91193ca5 100644 --- a/src/Networking/Network.cpp +++ b/src/Networking/Network.cpp @@ -86,23 +86,17 @@ Network::Network(Platform& p) noexcept : platform(p) #endif { #if HAS_NETWORKING -#if defined(DUET3_MB6HC) || defined(DUET3_MB6XD) +# if defined(DUET3_MB6HC) || defined(DUET3_MB6XD) interfaces[0] = new LwipEthernetInterface(p); -#elif defined(DUET_NG) || defined(DUET3MINI_V04) +# elif defined(DUET_NG) || defined(DUET3MINI_V04) interfaces[0] = nullptr; // we set this up in Init() -#elif defined(FMDC_V02) || defined(FMDC_V03) +# elif defined(FMDC_V02) || defined(FMDC_V03) interfaces[0] = new WiFiInterface(p); -#elif defined(DUET_M) +# elif defined(DUET_M) interfaces[0] = new W5500Interface(p); -#elif defined(__LPC17xx__) -# if HAS_WIFI_NETWORKING - interfaces[0] = new WiFiInterface(p); - #else - interfaces[0] = new RTOSPlusTCPEthernetInterface(p); - #endif -#else -# error Unknown board -#endif +# else +# error Unknown board +# endif #endif // HAS_NETWORKING } @@ -113,8 +107,10 @@ Network::Network(Platform& p) noexcept : platform(p) constexpr ObjectModelArrayDescriptor Network::interfacesArrayDescriptor = { - nullptr, - [] (const ObjectModel *self, const ObjectExplorationContext& context) noexcept -> size_t { return NumNetworkInterfaces; }, + // 0. Interfaces + { + nullptr, + [] (const ObjectModel *self, const ObjectExplorationContext& context) noexcept -> size_t { return ((Network*)self)->GetNumNetworkInterfaces(); }, #if HAS_NETWORKING [] (const ObjectModel *self, ObjectExplorationContext& context) noexcept -> ExpressionValue { return ExpressionValue(((Network*)self)->interfaces[context.GetIndex(0)]); } #endif @@ -200,10 +196,24 @@ void Network::Init() noexcept slowLoop = 0; } +#if defined(DUET3_MB6HC) + +// Create the additional interface. Called after we have established that we are not running in SBC mode but before config.g is run. +void Network::CreateAdditionalInterface() noexcept +{ + if (platform.GetBoardType() >= BoardType::Duet3_6HC_v102) + { + interfaces[1] = new WiFiInterface(platform); + numActualNetworkInterfaces = 2; + } +} + +#endif + GCodeResult Network::EnableProtocol(unsigned int interface, NetworkProtocol protocol, int port, int secure, const StringRef& reply) noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { return interfaces[interface]->EnableProtocol(protocol, port, secure, reply); } @@ -219,7 +229,7 @@ GCodeResult Network::EnableProtocol(unsigned int interface, NetworkProtocol prot GCodeResult Network::DisableProtocol(unsigned int interface, NetworkProtocol protocol, const StringRef& reply) noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { NetworkInterface * const iface = interfaces[interface]; const GCodeResult ret = iface->DisableProtocol(protocol, reply); @@ -280,7 +290,7 @@ GCodeResult Network::DisableProtocol(unsigned int interface, NetworkProtocol pro GCodeResult Network::ReportProtocols(unsigned int interface, const StringRef& reply) const noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { return interfaces[interface]->ReportProtocols(reply); } @@ -296,7 +306,7 @@ GCodeResult Network::ReportProtocols(unsigned int interface, const StringRef& re GCodeResult Network::EnableInterface(unsigned int interface, int mode, const StringRef& ssid, const StringRef& reply) noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { NetworkInterface * const iface = interfaces[interface]; const GCodeResult ret = iface->EnableInterface(mode, ssid, reply); @@ -485,7 +495,7 @@ void Network::Exit() noexcept GCodeResult Network::GetNetworkState(unsigned int interface, const StringRef& reply) noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { return interfaces[interface]->GetNetworkState(reply); } @@ -501,7 +511,7 @@ GCodeResult Network::GetNetworkState(unsigned int interface, const StringRef& re bool Network::IsWiFiInterface(unsigned int interface) const noexcept { #if HAS_NETWORKING - return interface < NumNetworkInterfaces && interfaces[interface]->IsWiFiInterface(); + return interface < GetNumNetworkInterfaces() && interfaces[interface]->IsWiFiInterface(); #else return false; #endif @@ -601,7 +611,7 @@ void Network::Diagnostics(MessageType mtype) noexcept int Network::EnableState(unsigned int interface) const noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { return interfaces[interface]->EnableState(); } @@ -626,7 +636,7 @@ IPAddress Network::GetIPAddress(unsigned int interface) const noexcept { return #if HAS_NETWORKING - (interface < NumNetworkInterfaces) ? interfaces[interface]->GetIPAddress() : + (interface < GetNumNetworkInterfaces()) ? interfaces[interface]->GetIPAddress() : #endif IPAddress(); } @@ -635,7 +645,7 @@ IPAddress Network::GetNetmask(unsigned int interface) const noexcept { return #if HAS_NETWORKING - (interface < NumNetworkInterfaces) ? interfaces[interface]->GetNetmask() : + (interface < GetNumNetworkInterfaces()) ? interfaces[interface]->GetNetmask() : #endif IPAddress(); } @@ -644,7 +654,7 @@ IPAddress Network::GetGateway(unsigned int interface) const noexcept { return #if HAS_NETWORKING - (interface < NumNetworkInterfaces) ? interfaces[interface]->GetGateway() : + (interface < GetNumNetworkInterfaces()) ? interfaces[interface]->GetGateway() : #endif IPAddress(); } @@ -652,7 +662,7 @@ IPAddress Network::GetGateway(unsigned int interface) const noexcept bool Network::UsingDhcp(unsigned int interface) const noexcept { #if HAS_NETWORKING - return interface < NumNetworkInterfaces && interfaces[interface]->UsingDhcp(); + return interface < GetNumNetworkInterfaces() && interfaces[interface]->UsingDhcp(); #else return false; #endif @@ -696,7 +706,7 @@ void Network::SetHostname(const char *name) noexcept GCodeResult Network::SetMacAddress(unsigned int interface, const MacAddress& mac, const StringRef& reply) noexcept { #if HAS_NETWORKING - if (interface < NumNetworkInterfaces) + if (interface < GetNumNetworkInterfaces()) { return interfaces[interface]->SetMacAddress(mac, reply); } @@ -711,7 +721,7 @@ GCodeResult Network::SetMacAddress(unsigned int interface, const MacAddress& mac const MacAddress& Network::GetMacAddress(unsigned int interface) const noexcept { #if HAS_NETWORKING - if (interface >= NumNetworkInterfaces) + if (interface >= GetNumNetworkInterfaces()) { interface = 0; } diff --git a/src/Networking/Network.h b/src/Networking/Network.h index 2543443d..eef40cd5 100644 --- a/src/Networking/Network.h +++ b/src/Networking/Network.h @@ -14,10 +14,10 @@ #include #include -#if defined(DUET3_V03) -const size_t NumNetworkInterfaces = 2; +#if defined(DUET3_MB6HC) && HAS_WIFI_NETWORKING +const size_t MaxNetworkInterfaces = 2; #elif defined(DUET3_MB6HC) || defined(DUET3_MB6XD) || defined(DUET_NG) || defined(DUET_M) || defined(__LPC17xx__) || defined(PCCB) || defined(DUET3MINI) -const size_t NumNetworkInterfaces = 1; +const size_t MaxNetworkInterfaces = 1; #else # error Wrong Network.h file included #endif @@ -78,6 +78,10 @@ public: void Diagnostics(MessageType mtype) noexcept; bool IsWiFiInterface(unsigned int interface) const noexcept; +#if defined(DUET3_MB6HC) + void CreateAdditionalInterface() noexcept; +#endif + GCodeResult EnableInterface(unsigned int interface, int mode, const StringRef& ssid, const StringRef& reply) noexcept; GCodeResult EnableProtocol(unsigned int interface, NetworkProtocol protocol, int port, int secure, const StringRef& reply) noexcept; GCodeResult DisableProtocol(unsigned int interface, NetworkProtocol protocol, const StringRef& reply) noexcept; @@ -121,12 +125,13 @@ protected: OBJECT_MODEL_ARRAY(interfaces) private: + unsigned int GetNumNetworkInterfaces() const noexcept; WiFiInterface *FindWiFiInterface() const noexcept; Platform& platform; #if HAS_NETWORKING - NetworkInterface *interfaces[NumNetworkInterfaces]; + NetworkInterface *interfaces[MaxNetworkInterfaces]; #endif #if HAS_RESPONDERS @@ -146,7 +151,21 @@ private: #if SUPPORT_HTTP String corsSite; #endif + +#ifdef DUET3_MB6HC + unsigned int numActualNetworkInterfaces = 1; // don't add a second interface until we know whether the board supports it +#endif + char hostname[16]; // Limit DHCP hostname to 15 characters + terminating 0 }; +inline unsigned int Network::GetNumNetworkInterfaces() const noexcept +{ +#if defined(DUET3_MB6HC) + return numActualNetworkInterfaces; +#else + return MaxNetworkInterfaces; +#endif +} + #endif /* SRC_NETWORK_NETWORK_H_ */ diff --git a/src/Platform/RepRap.cpp b/src/Platform/RepRap.cpp index cf3d9cbb..0353012c 100644 --- a/src/Platform/RepRap.cpp +++ b/src/Platform/RepRap.cpp @@ -607,6 +607,9 @@ void RepRap::Init() noexcept if (rslt == GCodeResult::ok) { +# if defined(DUET3_MB6HC) + network->CreateAdditionalInterface(); // do this now because config.g may refer to it +# endif // Run the configuration file if (!RunStartupFile(GCodes::CONFIG_FILE) && !RunStartupFile(GCodes::CONFIG_BACKUP_FILE)) { -- cgit v1.2.3 From 13376e04d1da83d2010a7728315e7d5b98bf1b52 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Mon, 19 Sep 2022 13:51:07 +0100 Subject: Redirect SPI1 interrupt on MB6HC when SBC interface not being used --- src/Config/Pins_Duet3_MB6HC.h | 2 +- src/SBC/DataTransfer.cpp | 11 +++++++++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index 5705b09d..a8d8ae47 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -392,7 +392,7 @@ constexpr GpioPinFunction SBCPinPeriphMode = GpioPinFunction::C; #define ESP_SPI SPI1 #define ESP_SPI_INTERFACE_ID ID_SPI1 #define ESP_SPI_IRQn SPI1_IRQn -#define ESP_SPI_HANDLER SPI1_Handler +#define ESP_SPI_HANDLER SPI1_WiFi_Handler // SBC interface redirects the interrupt to here constexpr Pin APIN_ESP_SPI_MOSI = PortCPin(27); constexpr Pin APIN_ESP_SPI_MISO = PortCPin(26); diff --git a/src/SBC/DataTransfer.cpp b/src/SBC/DataTransfer.cpp index 4505f320..2ec9051d 100644 --- a/src/SBC/DataTransfer.cpp +++ b/src/SBC/DataTransfer.cpp @@ -57,6 +57,10 @@ constexpr IRQn SBC_SPI_IRQn = SbcSpiSercomIRQn; # include #endif +#if defined(DUET3_MB6HC) && HAS_WIFI_NETWORKING +extern void ESP_SPI_HANDLER() noexcept; +#endif + #include #include #include @@ -356,6 +360,13 @@ extern "C" void SBC_SPI_HANDLER() noexcept TaskBase::GiveFromISR(sbcTaskHandle); } #else +# if defined(DUET3_MB6HC) && HAS_WIFI_NETWORKING + if (!reprap.UsingSbcInterface()) + { + ESP_SPI_HANDLER(); + return; + } +# endif const uint32_t status = SBC_SPI->SPI_SR; // read status and clear interrupt SBC_SPI->SPI_IDR = SPI_IER_NSSR; // disable the interrupt if ((status & SPI_SR_NSSR) != 0) -- cgit v1.2.3 From 052380267cdcb7b3a3c66c7f755159dba5d24baa Mon Sep 17 00:00:00 2001 From: David Crocker Date: Mon, 19 Sep 2022 15:45:12 +0100 Subject: Fixed MB6HC network initialisation issues --- src/Networking/Network.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp index 91193ca5..e7140eb3 100644 --- a/src/Networking/Network.cpp +++ b/src/Networking/Network.cpp @@ -186,10 +186,8 @@ void Network::Init() noexcept SafeStrncpy(hostname, DEFAULT_HOSTNAME, ARRAY_SIZE(hostname)); - for (NetworkInterface *iface : interfaces) - { - iface->Init(); - } + // Only the MB6HC has more than one interface, and at this point we haven't created the second one yet. So initialise just the first. + interfaces[0]->Init(); #endif fastLoop = UINT32_MAX; @@ -205,6 +203,8 @@ void Network::CreateAdditionalInterface() noexcept { interfaces[1] = new WiFiInterface(platform); numActualNetworkInterfaces = 2; + interfaces[1]->Init(); + interfaces[1]->UpdateHostname(hostname); } } @@ -695,9 +695,9 @@ void Network::SetHostname(const char *name) noexcept strcpy(hostname, DEFAULT_HOSTNAME); } - for (NetworkInterface *iface : interfaces) + for (unsigned int i = 0; i < GetNumNetworkInterfaces(); ++i) { - iface->UpdateHostname(hostname); + interfaces[i]->UpdateHostname(hostname); } #endif } -- cgit v1.2.3 From 618b88829bad5ffe780e8d681bcd8c60bd3f6f32 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Mon, 19 Sep 2022 18:13:09 +0100 Subject: Corrections to WiFi interface --- src/Config/Pins_Duet3_MB6HC.h | 14 +++++++------- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 20 +++----------------- src/Platform/Platform.cpp | 6 +++++- 3 files changed, 15 insertions(+), 25 deletions(-) diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index a8d8ae47..9d41ac77 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -14,7 +14,7 @@ #define IAP_CAN_LOADER_FILE "Duet3_CANiap32_" BOARD_SHORT_NAME ".bin" constexpr uint32_t IAP_IMAGE_START = 0x20458000; // last 32kb of RAM -#define WIFI_FIRMWARE_FILE "DuetWiFiServer_32S3.bin" +#define WIFI_FIRMWARE_FILE "DuetWiFiModule_32S3.bin" // Features definition // Networking support @@ -388,6 +388,9 @@ constexpr Pin APIN_SBC_SPI_SCK = PortCPin(24); constexpr Pin APIN_SBC_SPI_SS0 = PortCPin(25); constexpr GpioPinFunction SBCPinPeriphMode = GpioPinFunction::C; +constexpr Pin SbcTfrReadyPin = PortEPin(2); +// Note, the DMAC peripheral IDs are hard-coded in DataTransfer + // WiFi pins, mostly shared with the SBC interface #define ESP_SPI SPI1 #define ESP_SPI_INTERFACE_ID ID_SPI1 @@ -404,11 +407,11 @@ constexpr Pin APIN_SerialWiFi_TXD = PortDPin(19); constexpr Pin APIN_SerialWiFi_RXD = PortDPin(18); constexpr GpioPinFunction SerialWiFiPeriphMode = GpioPinFunction::C; -constexpr Pin EspResetPin = PortCPin(14); // Low on this in holds the WiFi module in reset (ESP_RESET) -constexpr Pin EspEnablePin = NoPin; // High to enable the WiFi module, low to power it down (ESP_CH_PD) +constexpr Pin EspResetPin = PortCPin(14); // Low on this in holds the WiFi module in reset (ESP_EN) constexpr Pin EspDataReadyPin = PortAPin(2); // Input from the WiFi module indicating that it wants to transfer data (ESP GPIO0) -constexpr Pin SamTfrReadyPin = PortEPin(2); // Output from the SAM to the WiFi module indicating we can accept a data transfer (ESP GPIO4 via 7474) +constexpr Pin SamTfrReadyPin = PortEPin(2); // Output from the SAM to the WiFi module indicating we can accept a data transfer (ESP GPIO8) constexpr Pin SamCsPin = PortCPin(25); // SPI NPCS pin, input from WiFi module +// Note, the DMAC peripheral IDs are hard-coded in WiFiInterface // CAN constexpr Pin APIN_CAN0_RX = PortBPin(3); @@ -426,9 +429,6 @@ constexpr unsigned int CanDeviceNumber = 1; // CAN-FD device number constexpr unsigned int SecondaryCanDeviceNumber = 0; // plan CAN device number #endif -constexpr Pin SbcTfrReadyPin = PortEPin(2); -// Note, the DMAC peripheral IDs are hard-coded in DataTransfer - // Timer allocation // Step timer is timer 0 aka TC0 channel 0. Also used as the CAN timestamp counter. #define STEP_TC (TC0) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 07ea4e6b..22ae7a52 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -40,6 +40,7 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and # include # include +# include # define USE_PDC 0 // use SAM4 peripheral DMA controller # define USE_DMAC 0 // use SAM4 general DMA controller @@ -63,18 +64,6 @@ constexpr Pin APIN_ESP_SPI_MISO = EspMisoPin; constexpr Pin APIN_ESP_SPI_SCK = EspSclkPin; constexpr IRQn ESP_SPI_IRQn = WiFiSpiSercomIRQn; -#elif defined(__LPC17xx__) - -# 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 0 // use SAME7 XDMA controller - -// Compatibility with existing RRF Code -constexpr Pin APIN_ESP_SPI_MISO = SPI0_MOSI; -constexpr Pin APIN_ESP_SPI_SCK = SPI0_SCK; -constexpr SSPChannel ESP_SPI = SSP0; - #else # error Unknown board #endif @@ -1421,9 +1410,6 @@ static Pdc *spi_pdc; #if USE_XDMAC // XDMAC hardware -const uint32_t SPI0_XDMAC_TX_CH_NUM = 1; -const uint32_t SPI0_XDMAC_RX_CH_NUM = 2; - static xdmac_channel_config_t xdmac_tx_cfg, xdmac_rx_cfg; #endif @@ -1594,7 +1580,7 @@ static void spi_tx_dma_setup(const void *buf, uint32_t transferLength) noexcept XDMAC_CC_DIF_AHB_IF1 | XDMAC_CC_SAM_INCREMENTED_AM | XDMAC_CC_DAM_FIXED_AM | - XDMAC_CC_PERID(SPI0_XDMAC_TX_CH_NUM); + XDMAC_CC_PERID((uint32_t)DmaTrigSource::spi1tx); xdmac_tx_cfg.mbr_bc = 0; xdmac_tx_cfg.mbr_ds = 0; xdmac_tx_cfg.mbr_sus = 0; @@ -1655,7 +1641,7 @@ static void spi_rx_dma_setup(void *buf, uint32_t transferLength) noexcept XDMAC_CC_DIF_AHB_IF0 | XDMAC_CC_SAM_FIXED_AM | XDMAC_CC_DAM_INCREMENTED_AM | - XDMAC_CC_PERID(SPI0_XDMAC_RX_CH_NUM); + XDMAC_CC_PERID((uint32_t)DmaTrigSource::spi1rx); xdmac_rx_cfg.mbr_bc = 0; xdmac_tx_cfg.mbr_ds = 0; xdmac_rx_cfg.mbr_sus = 0; diff --git a/src/Platform/Platform.cpp b/src/Platform/Platform.cpp index e82780c4..0a91998c 100644 --- a/src/Platform/Platform.cpp +++ b/src/Platform/Platform.cpp @@ -270,6 +270,9 @@ constexpr ObjectModelTableEntry Platform::objectModelTable[] = #if HAS_VOLTAGE_MONITOR { "vIn", OBJECT_MODEL_FUNC(self, 2), ObjectModelEntryFlags::live }, #endif +#if HAS_WIFI_NETWORKING + { "wifiFirmwareFileName", OBJECT_MODEL_FUNC_NOSELF(WIFI_FIRMWARE_FILE), ObjectModelEntryFlags::none }, +#endif #if HAS_CPU_TEMP_SENSOR // 1. mcuTemp members { "current", OBJECT_MODEL_FUNC(self->GetMcuTemperatures().current, 1), ObjectModelEntryFlags::live }, @@ -357,7 +360,8 @@ constexpr ObjectModelTableEntry Platform::objectModelTable[] = constexpr uint8_t Platform::objectModelTableDescriptor[] = { 10, // number of sections - 9 + SUPPORT_ACCELEROMETERS + HAS_SBC_INTERFACE + HAS_MASS_STORAGE + HAS_VOLTAGE_MONITOR + HAS_12V_MONITOR + HAS_CPU_TEMP_SENSOR + SUPPORT_CAN_EXPANSION + SUPPORT_12864_LCD + MCU_HAS_UNIQUE_ID, // section 0: boards[0] + 9 + SUPPORT_ACCELEROMETERS + HAS_SBC_INTERFACE + HAS_MASS_STORAGE + HAS_VOLTAGE_MONITOR + HAS_12V_MONITOR + HAS_CPU_TEMP_SENSOR + + SUPPORT_CAN_EXPANSION + SUPPORT_DIRECT_LCD + MCU_HAS_UNIQUE_ID + HAS_WIFI_NETWORKING, // section 0: boards[0] #if HAS_CPU_TEMP_SENSOR 3, // section 1: mcuTemp #else -- cgit v1.2.3 From e73b4fbe803033d2fc6e9f3193ae2b5bb1c9e08b Mon Sep 17 00:00:00 2001 From: David Crocker Date: Mon, 19 Sep 2022 18:36:51 +0100 Subject: Use correct baud rate to receive data from ESP32 --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 22ae7a52..f54a52a9 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -2035,10 +2035,15 @@ void WiFiInterface::StartWiFi() noexcept #endif #if !SAME5x && !defined(__LPC17xx__) - SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART - SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART + SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif + +#if defined(DUET3_MB6HC) + SERIAL_WIFI_DEVICE.begin(WiFiBaudRate_ESP32); // initialise the UART, to receive debug info +#else SERIAL_WIFI_DEVICE.begin(WiFiBaudRate); // initialise the UART, to receive debug info +#endif debugMessageChars = 0; serialRunning = true; debugPrintPending = false; -- cgit v1.2.3 From f966947e7eb87154b09716fda3f716a2a486564a Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 09:17:48 +0100 Subject: Added WIFI_USES_ESP32 configuration definition --- src/Config/Pins.h | 4 ++++ src/Config/Pins_Duet3_MB6HC.h | 1 + src/Networking/ESP8266WiFi/WiFiInterface.cpp | 2 +- 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/Config/Pins.h b/src/Config/Pins.h index 69d7f45d..7e34e13d 100644 --- a/src/Config/Pins.h +++ b/src/Config/Pins.h @@ -153,6 +153,10 @@ # define HAS_WIFI_NETWORKING 0 #endif +#if HAS_WIFI_NETWORKING && !defined(WIFI_USES_ESP32) +# define WIFI_USES_ESP32 0 +#endif + #ifndef HAS_W5500_NETWORKING # define HAS_W5500_NETWORKING 0 #endif diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index 9d41ac77..ba4f363f 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -20,6 +20,7 @@ constexpr uint32_t IAP_IMAGE_START = 0x20458000; // last 32kb of RAM // Networking support #define HAS_LWIP_NETWORKING 1 #define HAS_WIFI_NETWORKING 1 +#define WIFI_USES_ESP32 1 // Storage support #define HAS_SBC_INTERFACE 1 diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index f54a52a9..ba4aec9a 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -2039,7 +2039,7 @@ void WiFiInterface::StartWiFi() noexcept SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif -#if defined(DUET3_MB6HC) +#if WIFI_USES_ESP32 SERIAL_WIFI_DEVICE.begin(WiFiBaudRate_ESP32); // initialise the UART, to receive debug info #else SERIAL_WIFI_DEVICE.begin(WiFiBaudRate); // initialise the UART, to receive debug info -- cgit v1.2.3 From bcca8c9a38a36788f68446560248def2e9a2fbd9 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 10:25:54 +0100 Subject: When updating ESP32 modules, send commands to set up flash SPI --- .../ESP8266WiFi/WifiFirmwareUploader.cpp | 88 +++++++++++++++------- src/Networking/ESP8266WiFi/WifiFirmwareUploader.h | 4 + 2 files changed, 65 insertions(+), 27 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index d2f5f2a2..1b55a882 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -15,16 +15,23 @@ #include #include +#if WIFI_USES_ESP32 +constexpr uint32_t Esp32FlashModuleSize = 4 * 1024 * 1024; // assume at least 4Mbytes flash +#endif + // ESP8266 command codes -const uint8_t ESP_FLASH_BEGIN = 0x02; -const uint8_t ESP_FLASH_DATA = 0x03; -const uint8_t ESP_FLASH_END = 0x04; -const uint8_t ESP_MEM_BEGIN = 0x05; -const uint8_t ESP_MEM_END = 0x06; -const uint8_t ESP_MEM_DATA = 0x07; -const uint8_t ESP_SYNC = 0x08; -const uint8_t ESP_WRITE_REG = 0x09; -const uint8_t ESP_READ_REG = 0x0a; +const uint8_t ESP_FLASH_BEGIN = 0x02; // Four 32-bit words: size to erase, number of data packets, data size in one packet, flash offset. +const uint8_t ESP_FLASH_DATA = 0x03; // Four 32-bit words: data size, sequence number, 0, 0, then data. Uses Checksum. +const uint8_t ESP_FLASH_END = 0x04; // One 32-bit word: 0 to reboot, 1 “run to user code”. Not necessary to send this command if you wish to stay in the loader +const uint8_t ESP_MEM_BEGIN = 0x05; // total size, number of data packets, data size in one packet, memory offset +const uint8_t ESP_MEM_END = 0x06; // Two 32-bit words: execute flag, entry point address +const uint8_t ESP_MEM_DATA = 0x07; // Four 32-bit words: data size, sequence number, 0, 0, then data. Uses Checksum. +const uint8_t ESP_SYNC = 0x08; // 36 bytes: 0x07 0x07 0x12 0x20, followed by 32 x 0x55 +const uint8_t ESP_WRITE_REG = 0x09; // Four 32-bit words: address, value, mask and delay (in microseconds) +const uint8_t ESP_READ_REG = 0x0a; // Address as 32-bit word. Returns read data as 32-bit word in value field. +// The following two commands are needed by the ESP32 ROM loader +const uint8_t ESP_SPI_SET_PARAMS = 0x0b; // Six 32-bit words: id, total size in bytes, block size, sector size, page size, status mask. +const uint8_t ESP_SPI_ATTACH = 0x0d; // 32-bit word: Zero for normal SPI flash. A second 32-bit word (should be 0) is passed to ROM loader only. // MAC address storage locations const uint32_t ESP_OTP_MAC0 = 0x3ff00050; @@ -479,24 +486,35 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashBegin(uint32_t addr &= ~(EspFlashBlockSize - 1); // begin the Flash process - uint8_t buf[16]; - putData(size, 4, buf, 0); - putData(blkCnt, 4, buf, 4); - putData(EspFlashBlockSize, 4, buf, 8); - putData(addr, 4, buf, 12); - - uint32_t timeout = (size != 0) ? eraseTimeout : defaultTimeout; - return doCommand(ESP_FLASH_BEGIN, buf, sizeof(buf), 0, nullptr, timeout); + const uint32_t buf[4] = { size, blkCnt, EspFlashBlockSize, addr }; + + const uint32_t timeout = (size != 0) ? eraseTimeout : defaultTimeout; + return doCommand(ESP_FLASH_BEGIN, (const uint8_t*)buf, sizeof(buf), 0, nullptr, timeout); } // Send a command to the device to terminate the Flash process WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashFinish(bool reboot) noexcept { - uint8_t buf[4]; - putData(reboot ? 0 : 1, 4, buf, 0); - return doCommand(ESP_FLASH_END, buf, sizeof(buf), 0, nullptr, defaultTimeout); + const uint32_t data = (reboot) ? 0 : 1; + return doCommand(ESP_FLASH_END, (const uint8_t*)&data, sizeof(data), 0, nullptr, defaultTimeout); +} + +#if WIFI_USES_ESP32 + +WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashSpiSetParameters(uint32_t size) noexcept +{ + const uint32_t buf[6] = { 0, size, 64 * 1024, 4 * 1024, 256, 0x0000FFFF }; // id, size, block size, sector size, page size, status mask + return doCommand(ESP_SPI_SET_PARAMS, (const uint8_t*)buf, sizeof(buf), 0, nullptr, defaultTimeout); +} + +WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashSpiAttach() noexcept +{ + const uint32_t buf[2] = { 0, 0 }; + return doCommand(ESP_SPI_SET_PARAMS, (const uint8_t*)buf, sizeof(buf), 0, nullptr, defaultTimeout); } +#endif + // Compute the checksum of a block of data uint16_t WifiFirmwareUploader::checksum(const uint8_t *data, uint16_t dataLen, uint16_t cksum) noexcept { @@ -515,17 +533,16 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashWriteBlock(uint const uint32_t blkSize = EspFlashBlockSize; // Allocate a data buffer for the combined header and block data - const uint16_t hdrOfst = 0; const uint16_t dataOfst = 16; const uint16_t blkBufSize = dataOfst + blkSize; uint32_t blkBuf32[blkBufSize/4]; uint8_t * const blkBuf = reinterpret_cast(blkBuf32); // Prepare the header for the block - putData(blkSize, 4, blkBuf, hdrOfst + 0); - putData(uploadBlockNumber, 4, blkBuf, hdrOfst + 4); - putData(0, 4, blkBuf, hdrOfst + 8); - putData(0, 4, blkBuf, hdrOfst + 12); + blkBuf32[0] = blkSize; + blkBuf32[1] = uploadBlockNumber; + blkBuf32[2] = 0; + blkBuf32[3] = 0; // Get the data for the block size_t cnt = uploadFile->Read(reinterpret_cast(blkBuf + dataOfst), blkSize); @@ -546,12 +563,12 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashWriteBlock(uint if (uploadBlockNumber == 0 && uploadAddress == 0 && blkBuf[dataOfst] == ESP_IMAGE_MAGIC && flashParmMask != 0) { // update the Flash parameters - uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; + const uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; putData(flashParm | flashParmVal, 2, blkBuf + dataOfst + 2, 0); } // Calculate the block checksum - uint16_t cksum = checksum(blkBuf + dataOfst, blkSize, ESP_CHECKSUM_MAGIC); + const uint16_t cksum = checksum(blkBuf + dataOfst, blkSize, ESP_CHECKSUM_MAGIC); EspUploadResult stat; for (int i = 0; i < 3; i++) { @@ -623,6 +640,23 @@ void WifiFirmwareUploader::Spin() noexcept // Successful connection // MessageF(" success on attempt %d\n", (connectAttemptNumber % retriesPerBaudRate) + 1); MessageF(" success\n"); +#if WIFI_USES_ESP32 + res = flashSpiSetParameters(Esp32FlashModuleSize); + if (res != EspUploadResult::success) + { + MessageF("Failed to set SPI parameters\n"); + state = UploadState::resetting; // try a reset and a lower baud rate + break; + } + res = flashSpiAttach(); + if (res != EspUploadResult::success) + { + MessageF("Failed to attach SPI flash\n"); + state = UploadState::resetting; // try a reset and a lower baud rate + break; + } + MessageF("SPI flash parameters set\n"); +#endif state = UploadState::erasing1; } else diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h index 551a2abb..00f99b1d 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h @@ -82,6 +82,10 @@ private: EspUploadResult Sync(uint16_t timeout) noexcept; EspUploadResult flashBegin(uint32_t addr, uint32_t size) noexcept; EspUploadResult flashFinish(bool reboot) noexcept; +#if WIFI_USES_ESP32 + EspUploadResult flashSpiSetParameters(uint32_t size) noexcept; + EspUploadResult flashSpiAttach() noexcept; +#endif static uint16_t checksum(const uint8_t *data, uint16_t dataLen, uint16_t cksum) noexcept; EspUploadResult flashWriteBlock(uint16_t flashParmVal, uint16_t flashParmMask) noexcept; EspUploadResult DoErase(uint32_t address, uint32_t size) noexcept; -- cgit v1.2.3 From e002d41b88a68ba1c839b0f7134b1702bacefebb Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 12:32:18 +0100 Subject: Simplified some WiFiFirmwareUploader code to save space on Duet 2 --- .../ESP8266WiFi/WifiFirmwareUploader.cpp | 77 ++++++---------------- src/Networking/ESP8266WiFi/WifiFirmwareUploader.h | 2 - 2 files changed, 19 insertions(+), 60 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index 1b55a882..59e4fed1 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -44,14 +44,6 @@ const size_t EspFlashBlockSize = 0x0400; // 1K byte blocks const uint8_t ESP_IMAGE_MAGIC = 0xe9; const uint8_t ESP_CHECKSUM_MAGIC = 0xef; -const uint32_t ESP_ERASE_CHIP_ADDR = 0x40004984; // &SPIEraseChip -const uint32_t ESP_SEND_PACKET_ADDR = 0x40003c80; // &send_packet -const uint32_t ESP_SPI_READ_ADDR = 0x40004b1c; // &SPIRead -const uint32_t ESP_UNKNOWN_ADDR = 0x40001121; // not used -const uint32_t ESP_USER_DATA_RAM_ADDR = 0x3ffe8000; // &user data ram -const uint32_t ESP_IRAM_ADDR = 0x40100000; // instruction RAM -const uint32_t ESP_FLASH_ADDR = 0x40200000; // address of start of Flash - // Messages corresponding to result codes, should make sense when followed by " error" const char * const resultMessages[] = { @@ -102,42 +94,6 @@ void WifiFirmwareUploader::flushInput() noexcept } } -// Extract 1-4 bytes of a value in little-endian order from a buffer beginning at a specified offset -uint32_t WifiFirmwareUploader::getData(unsigned byteCnt, const uint8_t *buf, int ofst) noexcept -{ - uint32_t val = 0; - - if (buf && byteCnt) - { - unsigned int shiftCnt = 0; - if (byteCnt > 4) - byteCnt = 4; - do - { - val |= (uint32_t)buf[ofst++] << shiftCnt; - shiftCnt += 8; - } while (--byteCnt); - } - return(val); -} - -// Put 1-4 bytes of a value in little-endian order into a buffer beginning at a specified offset. -void WifiFirmwareUploader::putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) noexcept -{ - if (buf && byteCnt) - { - if (byteCnt > 4) - { - byteCnt = 4; - } - do - { - buf[ofst++] = (uint8_t)(val & 0xff); - val >>= 8; - } while (--byteCnt); - } -} - // Read a byte optionally performing SLIP decoding. The return values are: // // 2 - an escaped byte was read successfully @@ -248,7 +204,7 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t o const size_t headerLength = 8; uint32_t startTime = millis(); - uint8_t hdr[headerLength]; + alignas(4) uint8_t hdr[headerLength]; uint16_t hdrIdx = 0; bodyLen = 0; uint16_t bodyIdx = 0; @@ -314,12 +270,12 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t o if (hdrIdx >= headerLength) { // get the body length, prepare a buffer for it - bodyLen = (uint16_t)getData(2, hdr, 2); + bodyLen = *(const uint16_t*)(hdr + 2); // extract the value, if requested if (valp != nullptr) { - *valp = getData(4, hdr, 4); + *valp = *(const uint32_t*)(hdr + 4); } if (bodyLen != 0) @@ -356,8 +312,9 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t o } // Extract elements from the header - const uint8_t resp = (uint8_t)getData(1, hdr, 0); - const uint8_t opRet = (uint8_t)getData(1, hdr, 1); + const uint8_t resp = hdr[0]; + const uint8_t opRet = hdr[1]; + // Sync packets often provoke a response with a zero opcode instead of ESP_SYNC if (resp != 0x01 || opRet != op) { @@ -403,22 +360,26 @@ void WifiFirmwareUploader::writePacketRaw(const uint8_t *hdr, size_t hdrLen, con // The data is supplied via a list of one or more segments. void WifiFirmwareUploader::sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) noexcept { + struct __attribute__((packed)) CommandHeader + { + uint8_t zero; + uint8_t op; + uint16_t dataLen; + uint32_t checkVal; + }; + // populate the header - uint8_t hdr[8]; - putData(0, 1, hdr, 0); - putData(op, 1, hdr, 1); - putData(dataLen, 2, hdr, 2); - putData(checkVal, 4, hdr, 4); + CommandHeader cmdHdr = { 0, op, (uint16_t)dataLen, checkVal }; // send the packet flushInput(); if (op == ESP_SYNC) { - writePacketRaw(hdr, sizeof(hdr), data, dataLen); + writePacketRaw((const uint8_t*)&cmdHdr, sizeof(cmdHdr), data, dataLen); } else { - writePacket(hdr, sizeof(hdr), data, dataLen); + writePacket((const uint8_t*)&cmdHdr, sizeof(cmdHdr), data, dataLen); } } @@ -563,8 +524,8 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashWriteBlock(uint if (uploadBlockNumber == 0 && uploadAddress == 0 && blkBuf[dataOfst] == ESP_IMAGE_MAGIC && flashParmMask != 0) { // update the Flash parameters - const uint32_t flashParm = getData(2, blkBuf + dataOfst + 2, 0) & ~(uint32_t)flashParmMask; - putData(flashParm | flashParmVal, 2, blkBuf + dataOfst + 2, 0); + const uint32_t flashParm = (blkBuf32[dataOfst/4] >> 16) & ~(uint32_t)flashParmMask; + blkBuf32[dataOfst/4] = (blkBuf32[dataOfst/4] & 0x0000FFFF) | ((flashParm | flashParmVal) << 16); } // Calculate the block checksum diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h index 00f99b1d..b574315d 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h @@ -66,8 +66,6 @@ private: }; void MessageF(const char *fmt, ...) noexcept; - uint32_t getData(unsigned byteCnt, const uint8_t *buf, int ofst) noexcept; - void putData(uint32_t val, unsigned byteCnt, uint8_t *buf, int ofst) noexcept; int ReadByte(uint8_t& data, bool slipDecode) noexcept; void WriteByteRaw(uint8_t b) noexcept; void WriteByteSlip(uint8_t b) noexcept; -- cgit v1.2.3 From eec28eb306a63ef1a6d40c09ec8859d37826df1a Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 12:47:46 +0100 Subject: In WiFiFirmwareUpload do flash SPI attach before SPI set parameters --- src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index 59e4fed1..c718fcd9 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -602,17 +602,17 @@ void WifiFirmwareUploader::Spin() noexcept // MessageF(" success on attempt %d\n", (connectAttemptNumber % retriesPerBaudRate) + 1); MessageF(" success\n"); #if WIFI_USES_ESP32 - res = flashSpiSetParameters(Esp32FlashModuleSize); + res = flashSpiAttach(); if (res != EspUploadResult::success) { - MessageF("Failed to set SPI parameters\n"); + MessageF("Failed to attach SPI flash\n"); state = UploadState::resetting; // try a reset and a lower baud rate break; } - res = flashSpiAttach(); + res = flashSpiSetParameters(Esp32FlashModuleSize); if (res != EspUploadResult::success) { - MessageF("Failed to attach SPI flash\n"); + MessageF("Failed to set SPI parameters\n"); state = UploadState::resetting; // try a reset and a lower baud rate break; } -- cgit v1.2.3 From 31066ea427b7283b896ddc389a6d4cf17b8f59c6 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 13:19:54 +0100 Subject: Don't erase system parameters when using ESP32 --- src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index c718fcd9..b7849109 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -617,8 +617,10 @@ void WifiFirmwareUploader::Spin() noexcept break; } MessageF("SPI flash parameters set\n"); -#endif + state = UploadState::erasing2; +#else state = UploadState::erasing1; +#endif } else { @@ -637,6 +639,9 @@ void WifiFirmwareUploader::Spin() noexcept break; case UploadState::erasing1: +#if WIFI_USES_ESP32 + // no break +#else if (millis() - lastAttemptTime >= blockWriteInterval) { uploadResult = DoErase(systemParametersAddress, systemParametersSize); @@ -651,6 +656,7 @@ void WifiFirmwareUploader::Spin() noexcept } } break; +#endif case UploadState::erasing2: if (millis() - lastAttemptTime >= blockWriteInterval) -- cgit v1.2.3 From 0e912ef5bbc7d784334c706cd8b6b5fabc2c7129 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 15:41:59 +0100 Subject: Check status return after sending a command to ESP module --- .../ESP8266WiFi/WifiFirmwareUploader.cpp | 78 ++++++++++++++++++---- src/Networking/ESP8266WiFi/WifiFirmwareUploader.h | 28 +++++--- 2 files changed, 84 insertions(+), 22 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index b7849109..b0ce3b00 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -47,8 +47,18 @@ const uint8_t ESP_CHECKSUM_MAGIC = 0xef; // Messages corresponding to result codes, should make sense when followed by " error" const char * const resultMessages[] = { - "no", - "timeout", + "no", // 0 + "unknown", "unknown", "unknown", "unknown", // 0x01 to 0x04 + "invalidMessage", // 0x05 + "failedToAct", // 0x06 + "invalidCrc", // 0x07 + "flashWriteError", // 0x08 + "flashReadError", // 0x09 + "unknown", // 0x0a + "deflateError", // 0x0b + "unknown", "unknown", "unknown", "unknown", // 0x0c to 0x0f + + "timeout", // 0x10 "comm write", "connect", "bad reply", @@ -190,7 +200,7 @@ inline void WifiFirmwareUploader::WriteByteSlip(uint8_t b) noexcept // // If an error occurs, return a negative value. Otherwise, return the number // of bytes in the response (or zero if the response was not the standard "two bytes of zero"). -WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t op, uint32_t *valp, size_t& bodyLen, uint32_t msTimeout) noexcept +WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t op, uint32_t *valp, size_t& bodyLen, uint32_t *status, uint32_t msTimeout) noexcept { enum class PacketState { @@ -208,7 +218,7 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t o uint16_t hdrIdx = 0; bodyLen = 0; uint16_t bodyIdx = 0; - uint8_t respBuf[2]; + alignas(4) uint8_t respBuf[4]; // wait for the response uint16_t needBytes = 1; @@ -322,6 +332,11 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::readPacket(uint8_t o return EspUploadResult::respHeader; } + if (status != nullptr) + { + *status = (bodyLen == 2) ? *(const uint16_t*)respBuf : *(const uint32_t*)respBuf; + } + return EspUploadResult::success; } @@ -383,22 +398,57 @@ void WifiFirmwareUploader::sendCommand(uint8_t op, uint32_t checkVal, const uint } } +// Calculate the number of bytes to erase +/*static*/ uint32_t WifiFirmwareUploader::getEraseSize(uint32_t offset, uint32_t size) noexcept +{ +#if WIFI_USES_ESP32 + return size; +#else + // This works around a bug in the ESP8266 ROM + const uint32_t sectors_per_block = 16; + const uint32_t sector_size = 4 * 1024; + const uint32_t num_sectors = (size + sector_size - 1) / sector_size; + const uint32_t start_sector = offset / sector_size; + + uint32_t head_sectors = sectors_per_block - (start_sector % sectors_per_block); + if (num_sectors < head_sectors) + { + head_sectors = num_sectors; + } + + return (num_sectors < 2 * head_sectors) + ? (num_sectors + 1) / 2 * sector_size + : (num_sectors - head_sectors) * sector_size; +#endif +} + // Send a command to the attached device together with the supplied data, if any, and get the response WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) noexcept { sendCommand(op, checkVal, data, dataLen); size_t bodyLen; - EspUploadResult stat = readPacket(op, valp, bodyLen, msTimeout); - if (stat == EspUploadResult::success && bodyLen != 2) + uint32_t status; + EspUploadResult stat = readPacket(op, valp, bodyLen, &status, msTimeout); + if (stat == EspUploadResult::success) { - stat = EspUploadResult::badReply; + if (!(bodyLen == 2 || bodyLen == 4)) + { + stat = EspUploadResult::badReply; + } + else if ((status & 0xFF) != 0) + { + stat = (EspUploadResult)((status >> 8) & 0xFF); + if (reprap.Debug(moduleWiFi)) + { + debugPrintf("opcode %u returned length %u status 0x%" PRIx32 "\n", op, bodyLen, status); + } + } } return stat; } -// Send a synchronising packet to the serial port in an attempt to induce -// the ESP8266 to auto-baud lock on the baud rate. +// Send a synchronising packet to the serial port in an attempt to induce the ESP8266 to auto-baud lock on the baud rate. WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::Sync(uint16_t timeout) noexcept { uint8_t buf[36]; @@ -416,7 +466,7 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::Sync(uint16_t timeou for (int i = 0; i < 10 && stat == EspUploadResult::respHeader; ++i) { size_t bodyLen; - stat = readPacket(ESP_SYNC, nullptr, bodyLen, timeout); + stat = readPacket(ESP_SYNC, nullptr, bodyLen, nullptr, timeout); } if (stat == EspUploadResult::success) @@ -425,8 +475,8 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::Sync(uint16_t timeou for (;;) { size_t bodyLen; - EspUploadResult rc = readPacket(ESP_SYNC, nullptr, bodyLen, defaultTimeout); - if (rc != EspUploadResult::success || bodyLen != 2) + EspUploadResult rc = readPacket(ESP_SYNC, nullptr, bodyLen, nullptr, defaultTimeout); + if (rc != EspUploadResult::success || !(bodyLen == 2 || bodyLen == 4)) { break; } @@ -471,7 +521,7 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashSpiSetParameter WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashSpiAttach() noexcept { const uint32_t buf[2] = { 0, 0 }; - return doCommand(ESP_SPI_SET_PARAMS, (const uint8_t*)buf, sizeof(buf), 0, nullptr, defaultTimeout); + return doCommand(ESP_SPI_ATTACH, (const uint8_t*)buf, sizeof(buf), 0, nullptr, defaultTimeout); } #endif @@ -661,7 +711,7 @@ void WifiFirmwareUploader::Spin() noexcept case UploadState::erasing2: if (millis() - lastAttemptTime >= blockWriteInterval) { - uploadResult = DoErase(uploadAddress, fileSize); + uploadResult = DoErase(uploadAddress, getEraseSize(uploadAddress, fileSize)); if (uploadResult == EspUploadResult::success) { MessageF("Uploading file...\n"); diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h index b574315d..e1332e92 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h @@ -26,24 +26,35 @@ public: static const uint32_t WebFilesAddress = 0x00100000; private: - static const uint32_t defaultTimeout = 500; // default timeout in milliseconds + static const uint32_t defaultTimeout = 500; // default timeout in milliseconds static const uint32_t syncTimeout = 1000; static const unsigned int retriesPerBaudRate = 9; static const unsigned int retriesPerReset = 3; static const uint32_t connectAttemptInterval = 50; static const uint32_t resetDelay = 500; - static const uint32_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short + static const uint32_t blockWriteInterval = 15; // 15ms is long enough, 10ms is mostly too short static const uint32_t blockWriteTimeout = 200; - static const uint32_t eraseTimeout = 15000; // increased from 12 to 15 seconds because Roland's board was timing out - static const unsigned int percentToReportIncrement = 5; // how often we report % complete + static const uint32_t eraseTimeout = 15000; // increased from 12 to 15 seconds because Roland's board was timing out + static const unsigned int percentToReportIncrement = 5; // how often we report % complete static const uint32_t systemParametersAddress = 0x3FE000; // the address of the system + user parameter area that needs to be cleared when changing SDK version static const uint32_t systemParametersSize = 0x2000; // the size of the system + user parameter area - // Return codes - this list must be kept in step with the corresponding messages - enum class EspUploadResult + // Return codes + // *** This list must be kept in step with the corresponding messages! *** + enum class EspUploadResult : uint8_t { success = 0, - timeout, + + // The following are status codes return by the ESP + invalidMessage = 0x05, + failedToAct = 0x06, + invalidCrc = 0x07, + flashWriteError = 0x08, + flashReadError = 0x09, + deflateError = 0x0b, + + // The remainder are our own status codes + timeout = 0x10, connect, badReply, fileRead, @@ -70,12 +81,13 @@ private: void WriteByteRaw(uint8_t b) noexcept; void WriteByteSlip(uint8_t b) noexcept; void flushInput() noexcept; - EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t& bodyLen, uint32_t msTimeout) noexcept; + EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t& bodyLen, uint32_t *status, uint32_t msTimeout) noexcept; void writePacket(const uint8_t *data, size_t len) noexcept; void writePacketRaw(const uint8_t *buf, size_t len) noexcept; void writePacket(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) noexcept; void writePacketRaw(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) noexcept; void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) noexcept; + static uint32_t getEraseSize(uint32_t offset, uint32_t size) noexcept; EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) noexcept; EspUploadResult Sync(uint16_t timeout) noexcept; EspUploadResult flashBegin(uint32_t addr, uint32_t size) noexcept; -- cgit v1.2.3 From b30426ffd005721ba226d5e67a40a4883f24dd36 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 18:57:44 +0100 Subject: Fixed an issue uploading firmware to ESP32 --- .../ESP8266WiFi/WifiFirmwareUploader.cpp | 70 ++++++++++++---------- src/Networking/ESP8266WiFi/WifiFirmwareUploader.h | 8 ++- 2 files changed, 45 insertions(+), 33 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index b0ce3b00..4b2dc953 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -39,7 +39,7 @@ const uint32_t ESP_OTP_MAC1 = 0x3ff00054; const uint32_t ESP_OTP_MAC2 = 0x3ff00058; const uint32_t ESP_OTP_MAC3 = 0x3ff0005c; -const size_t EspFlashBlockSize = 0x0400; // 1K byte blocks +const size_t EspFlashBlockSize = 0x0400; // we send 1K byte blocks const uint8_t ESP_IMAGE_MAGIC = 0xe9; const uint8_t ESP_CHECKSUM_MAGIC = 0xef; @@ -398,30 +398,6 @@ void WifiFirmwareUploader::sendCommand(uint8_t op, uint32_t checkVal, const uint } } -// Calculate the number of bytes to erase -/*static*/ uint32_t WifiFirmwareUploader::getEraseSize(uint32_t offset, uint32_t size) noexcept -{ -#if WIFI_USES_ESP32 - return size; -#else - // This works around a bug in the ESP8266 ROM - const uint32_t sectors_per_block = 16; - const uint32_t sector_size = 4 * 1024; - const uint32_t num_sectors = (size + sector_size - 1) / sector_size; - const uint32_t start_sector = offset / sector_size; - - uint32_t head_sectors = sectors_per_block - (start_sector % sectors_per_block); - if (num_sectors < head_sectors) - { - head_sectors = num_sectors; - } - - return (num_sectors < 2 * head_sectors) - ? (num_sectors + 1) / 2 * sector_size - : (num_sectors - head_sectors) * sector_size; -#endif -} - // Send a command to the attached device together with the supplied data, if any, and get the response WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) noexcept { @@ -488,18 +464,52 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::Sync(uint16_t timeou } // Send a command to the device to begin the Flash process. -WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashBegin(uint32_t addr, uint32_t size) noexcept +WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashBegin(uint32_t offset, uint32_t size) noexcept { // determine the number of blocks represented by the size const uint32_t blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; // ensure that the address is on a block boundary - addr &= ~(EspFlashBlockSize - 1); + size += offset & (EspFlashBlockSize - 1); + offset &= ~(EspFlashBlockSize - 1); + + // Calculate the number of sectors to erase + const uint32_t sector_size = 4 * 1024; + uint32_t num_sectors = (size + (sector_size - 1))/sector_size; + +#if !WIFI_USES_ESP32 + const uint32_t start_sector = offset / sector_size; + const uint32_t sectors_per_block = 16; + + uint32_t head_sectors = sectors_per_block - (start_sector % sectors_per_block); + if (num_sectors < head_sectors) + { + head_sectors = num_sectors; + } + + // SPI EraseArea function in the esp8266 ROM has a bug which causes extra area to be erased. + // If the address range to be erased crosses the block boundary then extra head_sector_count sectors are erased. + // If the address range doesn't cross the block boundary, then extra total_sector_count sectors are erased. + if (num_sectors < 2 * head_sectors) + { + num_sectors = ((num_sectors + 1) / 2); + } + else + { + num_sectors = (num_sectors - head_sectors); + } +#endif + + const uint32_t erase_size = num_sectors * sector_size; // begin the Flash process - const uint32_t buf[4] = { size, blkCnt, EspFlashBlockSize, addr }; +#if WIFI_USES_ESP32 + const uint32_t buf[5] = { erase_size, blkCnt, EspFlashBlockSize, offset, 0 }; // last word means not encrypted +#else + const uint32_t buf[4] = { erase_size, blkCnt, EspFlashBlockSize, offset }; +#endif - const uint32_t timeout = (size != 0) ? eraseTimeout : defaultTimeout; + const uint32_t timeout = (erase_size != 0) ? eraseTimeout : defaultTimeout; return doCommand(ESP_FLASH_BEGIN, (const uint8_t*)buf, sizeof(buf), 0, nullptr, timeout); } @@ -711,7 +721,7 @@ void WifiFirmwareUploader::Spin() noexcept case UploadState::erasing2: if (millis() - lastAttemptTime >= blockWriteInterval) { - uploadResult = DoErase(uploadAddress, getEraseSize(uploadAddress, fileSize)); + uploadResult = DoErase(uploadAddress, fileSize); if (uploadResult == EspUploadResult::success) { MessageF("Uploading file...\n"); diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h index e1332e92..5ea07ed9 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.h @@ -22,8 +22,8 @@ public: void SendUpdateFile(const char *file, uint32_t address) noexcept; void Spin() noexcept; + // Offsets in flash memory static const uint32_t FirmwareAddress = 0x00000000; - static const uint32_t WebFilesAddress = 0x00100000; private: static const uint32_t defaultTimeout = 500; // default timeout in milliseconds @@ -36,8 +36,11 @@ private: static const uint32_t blockWriteTimeout = 200; static const uint32_t eraseTimeout = 15000; // increased from 12 to 15 seconds because Roland's board was timing out static const unsigned int percentToReportIncrement = 5; // how often we report % complete + +#if !WIFI_USES_ESP32 static const uint32_t systemParametersAddress = 0x3FE000; // the address of the system + user parameter area that needs to be cleared when changing SDK version static const uint32_t systemParametersSize = 0x2000; // the size of the system + user parameter area +#endif // Return codes // *** This list must be kept in step with the corresponding messages! *** @@ -87,10 +90,9 @@ private: void writePacket(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) noexcept; void writePacketRaw(const uint8_t *hdr, size_t hdrLen, const uint8_t *data, size_t dataLen) noexcept; void sendCommand(uint8_t op, uint32_t checkVal, const uint8_t *data, size_t dataLen) noexcept; - static uint32_t getEraseSize(uint32_t offset, uint32_t size) noexcept; EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint32_t checkVal, uint32_t *valp, uint32_t msTimeout) noexcept; EspUploadResult Sync(uint16_t timeout) noexcept; - EspUploadResult flashBegin(uint32_t addr, uint32_t size) noexcept; + EspUploadResult flashBegin(uint32_t offset, uint32_t size) noexcept; EspUploadResult flashFinish(bool reboot) noexcept; #if WIFI_USES_ESP32 EspUploadResult flashSpiSetParameters(uint32_t size) noexcept; -- cgit v1.2.3 From de9eede5f17bc6adf8c058e7ab227ed2161c94bc Mon Sep 17 00:00:00 2001 From: David Crocker Date: Tue, 20 Sep 2022 20:47:13 +0100 Subject: Moved wifi transfer buffers into non-cached RAM on SAME70 --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 13 +++++++++++-- src/Networking/ESP8266WiFi/WiFiInterface.h | 24 ++++++++++++------------ 2 files changed, 23 insertions(+), 14 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index ba4aec9a..a0ca3dbe 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -25,7 +25,7 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and // Define exactly one of the following as 1, the other as zero -#if defined(DUET_NG) +#if SAM4E # include # include @@ -36,7 +36,7 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and # define USE_DMAC_MANAGER 0 // use SAMD/SAME DMA controller via DmacManager module # define USE_XDMAC 0 // use SAME7 XDMA controller -#elif defined(DUET3_MB6HC) +#elif SAME70 # include # include @@ -47,6 +47,9 @@ static_assert(SsidLength == SsidBufferLength, "SSID lengths in NetworkDefs.h and # 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 @@ -467,8 +470,14 @@ void WiFiInterface::Activate() noexcept { activated = true; +#if SAME70 + bufferOut = &messageBufferOut; + bufferIn = &messageBufferIn; +#else bufferOut = new MessageBufferOut; bufferIn = new MessageBufferIn; +#endif + #if HAS_MASS_STORAGE || HAS_EMBEDDED_FILES uploader = new WifiFirmwareUploader(SERIAL_WIFI_DEVICE, *this); #endif diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.h b/src/Networking/ESP8266WiFi/WiFiInterface.h index 5776f1e6..42a41f9b 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.h +++ b/src/Networking/ESP8266WiFi/WiFiInterface.h @@ -32,6 +32,18 @@ private: uint32_t padding; }; +struct MessageBufferOut +{ + MessageHeaderSamToEsp hdr; + uint8_t data[MaxDataLength]; // data to send +}; + +struct alignas(16) MessageBufferIn +{ + MessageHeaderEspToSam hdr; + uint8_t data[MaxDataLength]; // data to send +}; + // The main network class that drives the network. class WiFiInterface : public NetworkInterface { @@ -123,18 +135,6 @@ private: bool lastDataReadyPinState; uint8_t risingEdges; - struct MessageBufferOut - { - MessageHeaderSamToEsp hdr; - uint8_t data[MaxDataLength]; // data to send - }; - - struct alignas(16) MessageBufferIn - { - MessageHeaderEspToSam hdr; - uint8_t data[MaxDataLength]; // data to send - }; - MessageBufferOut *bufferOut; MessageBufferIn *bufferIn; -- cgit v1.2.3 From a4364ff94d955d6f158e3bebeaed9430af1dd68d Mon Sep 17 00:00:00 2001 From: David Crocker Date: Wed, 21 Sep 2022 00:53:09 +0100 Subject: Removed LPC support from WiFiInterface --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 79 +++++++++++----------------- src/RepRapFirmware.h | 2 +- 2 files changed, 33 insertions(+), 48 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index a0ca3dbe..a8cb72cf 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -83,8 +83,7 @@ constexpr IRQn ESP_SPI_IRQn = WiFiSpiSercomIRQn; # include "xdmac/xdmac.h" #endif -#if SAME5x -#elif !defined(__LPC17xx__) +#if !SAME5x # include "matrix/matrix.h" #endif @@ -216,10 +215,6 @@ static void debugPrintBuffer(const char *msg, void *buf, size_t dataLength) noex } #endif -#ifdef __LPC17xx__ -# include "WiFiInterface_LPC.hpp" -#endif - static void EspTransferRequestIsr(CallbackParameter) noexcept { wifiInterface->EspRequestsTransfer(); @@ -540,7 +535,7 @@ void WiFiInterface::Start() noexcept // Make sure the ESP8266 is in the reset state pinMode(EspResetPin, OUTPUT_LOW); -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 pinMode(EspEnablePin, OUTPUT_LOW); #endif @@ -595,7 +590,7 @@ void WiFiInterface::Stop() noexcept digitalWrite(SamTfrReadyPin, false); // tell the ESP we can't receive digitalWrite(EspResetPin, false); // put the ESP back into reset -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 digitalWrite(EspEnablePin, false); #endif DisableEspInterrupt(); // ignore IRQs from the transfer request pin @@ -1410,8 +1405,6 @@ void WiFiInterface::TerminateDataPort() noexcept } } -#ifndef __LPC17xx__ - #if USE_PDC static Pdc *spi_pdc; #endif @@ -1427,58 +1420,58 @@ static xdmac_channel_config_t xdmac_tx_cfg, xdmac_rx_cfg; static inline void spi_rx_dma_enable() noexcept { -#if USE_DMAC +# if USE_DMAC dmac_channel_enable(DMAC, DmacChanWiFiRx); -#endif +# endif -#if USE_XDMAC +# if USE_XDMAC xdmac_channel_enable(XDMAC, DmacChanWiFiRx); -#endif +# endif -#if USE_DMAC_MANAGER +# if USE_DMAC_MANAGER DmacManager::EnableChannel(DmacChanWiFiRx, DmacPrioWiFi); -#endif +# endif } static inline void spi_tx_dma_enable() noexcept { -#if USE_DMAC +# if USE_DMAC dmac_channel_enable(DMAC, DmacChanWiFiTx); -#endif +# endif -#if USE_XDMAC +# if USE_XDMAC xdmac_channel_enable(XDMAC, DmacChanWiFiTx); -#endif +# endif -#if USE_DMAC_MANAGER +# if USE_DMAC_MANAGER DmacManager::EnableChannel(DmacChanWiFiTx, DmacPrioWiFi); -#endif +# endif } static inline void spi_rx_dma_disable() noexcept { -#if USE_DMAC +# if USE_DMAC dmac_channel_disable(DMAC, DmacChanWiFiRx); -#endif +# endif -#if USE_XDMAC +# if USE_XDMAC xdmac_channel_disable(XDMAC, DmacChanWiFiRx); -#endif +# endif -#if USE_DMAC_MANAGER +# if USE_DMAC_MANAGER DmacManager::DisableChannel(DmacChanWiFiRx); -#endif +# endif } static inline void spi_tx_dma_disable() noexcept { -#if USE_DMAC +# if USE_DMAC dmac_channel_disable(DMAC, DmacChanWiFiTx); -#endif +# endif -#if USE_XDMAC +# if USE_XDMAC xdmac_channel_disable(XDMAC, DmacChanWiFiTx); -#endif +# endif #if USE_DMAC_MANAGER DmacManager::DisableChannel(DmacChanWiFiTx); @@ -1760,8 +1753,6 @@ void WiFiInterface::SetupSpi() noexcept NVIC_EnableIRQ(ESP_SPI_IRQn); } -#endif //end ifndef __LPC17xx__ - // Send a command to the ESP and get the result int32_t WiFiInterface::SendCommand(NetworkCommand cmd, SocketNumber socketNum, uint8_t flags, uint32_t param32, const void *dataOut, size_t dataOutLength, void* dataIn, size_t dataInLength) noexcept { @@ -1825,8 +1816,6 @@ int32_t WiFiInterface::SendCommand(NetworkCommand cmd, SocketNumber socketNum, u WiFiSpiSercom->SPI.INTFLAG.reg = 0xFF; // clear any pending interrupts WiFiSpiSercom->SPI.INTENSET.reg = SERCOM_SPI_INTENSET_TXC; // enable the end of transmit interrupt EnableSpi(); -#elif defined(__LPC17xx__) - spi_slave_dma_setup(dataOutLength, dataInLength); #else // DMA may have transferred an extra word to the SPI transmit data register. We need to clear this. // The only way I can find to do this is to issue a software reset to the SPI system. @@ -1972,8 +1961,6 @@ void WiFiInterface::GetNewStatus() noexcept } } -#if !defined(__LPC17xx__) - # ifndef ESP_SPI_HANDLER # error ESP_SPI_HANDLER not defined # endif @@ -2024,26 +2011,24 @@ void WiFiInterface::SpiInterrupt() noexcept #endif if (transferPending) { - digitalWrite(SamTfrReadyPin, false); // stop signalling that we are ready for another transfer + digitalWrite(SamTfrReadyPin, false); // stop signalling that we are ready for another transfer transferPending = false; TaskBase::GiveFromISR(espWaitingTask); } } } -#endif //ifndef __LPC17xx__ - // Start the ESP void WiFiInterface::StartWiFi() noexcept { digitalWrite(EspResetPin, true); -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 delayMicroseconds(150); // ESP8266 datasheet specifies minimum 100us from releasing reset to power up digitalWrite(EspEnablePin, true); #endif -#if !SAME5x && !defined(__LPC17xx__) +#if !SAME5x SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif @@ -2063,7 +2048,7 @@ void WiFiInterface::ResetWiFi() noexcept { pinMode(EspResetPin, OUTPUT_LOW); // assert ESP8266 /RESET -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 pinMode(EspEnablePin, OUTPUT_LOW); #endif @@ -2097,7 +2082,7 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept // Make sure the ESP8266 is in the reset state pinMode(EspResetPin, OUTPUT_LOW); -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 // Power down the ESP8266 pinMode(EspEnablePin, OUTPUT_LOW); #endif @@ -2126,7 +2111,7 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept } else { -#if !SAME5x && !defined(__LPC17xx__) +#if !SAME5x SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART #endif @@ -2135,7 +2120,7 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept // Release the reset on the ESP8266 digitalWrite(EspResetPin, true); -#if defined(DUET_NG) || defined(DUET3MINI) +#if !WIFI_USES_ESP32 // Take the ESP8266 out of power down delayMicroseconds(150); // ESP8266 datasheet specifies minimum 100us from releasing reset to power up digitalWrite(EspEnablePin, true); diff --git a/src/RepRapFirmware.h b/src/RepRapFirmware.h index 179b865a..ccff0616 100644 --- a/src/RepRapFirmware.h +++ b/src/RepRapFirmware.h @@ -605,7 +605,7 @@ const NvicPriority NvicPriorityEthernet = 7; // priority for Ethernet interface # endif const NvicPriority NvicPriorityDMA = 7; // end-of-DMA interrupt used by TMC drivers and HSMCI -const NvicPriority NvicPrioritySpi = 7; // SPI is used for network transfers on Duet WiFi/Duet vEthernet +const NvicPriority NvicPrioritySpi = 7; // SPI is used for network transfers on Duet WiFi/Duet Ethernet and for SBC transfers #elif __NVIC_PRIO_BITS >= 4 // We have at least 16 priority levels -- cgit v1.2.3 From 0ad254fc9d0eff9df0eeed71a48c66a5fc3057db Mon Sep 17 00:00:00 2001 From: David Crocker Date: Wed, 21 Sep 2022 08:53:49 +0100 Subject: Fixes for ESP32C3 on D3Mini --- src/Config/Pins_Duet3_MB6HC.h | 2 +- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 62 +++++++++------------- .../ESP8266WiFi/WifiFirmwareUploader.cpp | 33 ++++-------- 3 files changed, 35 insertions(+), 62 deletions(-) diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index ba4f363f..2af57679 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -408,7 +408,7 @@ constexpr Pin APIN_SerialWiFi_TXD = PortDPin(19); constexpr Pin APIN_SerialWiFi_RXD = PortDPin(18); constexpr GpioPinFunction SerialWiFiPeriphMode = GpioPinFunction::C; -constexpr Pin EspResetPin = PortCPin(14); // Low on this in holds the WiFi module in reset (ESP_EN) +constexpr Pin EspEnablePin = PortCPin(14); // Low on this in holds the WiFi module in reset (ESP_EN) constexpr Pin EspDataReadyPin = PortAPin(2); // Input from the WiFi module indicating that it wants to transfer data (ESP GPIO0) constexpr Pin SamTfrReadyPin = PortEPin(2); // Output from the SAM to the WiFi module indicating we can accept a data transfer (ESP GPIO8) constexpr Pin SamCsPin = PortCPin(25); // SPI NPCS pin, input from WiFi module diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index a8cb72cf..e30509aa 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -533,11 +533,11 @@ 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 -#if !WIFI_USES_ESP32 pinMode(EspEnablePin, OUTPUT_LOW); -#endif // Set up our transfer request pin (GPIO4) as an output and set it low pinMode(SamTfrReadyPin, OUTPUT_LOW); @@ -589,10 +589,11 @@ void WiFiInterface::Stop() noexcept MutexLocker lock(interfaceMutex); digitalWrite(SamTfrReadyPin, false); // tell the ESP we can't receive - digitalWrite(EspResetPin, false); // put the ESP back into reset + #if !WIFI_USES_ESP32 - digitalWrite(EspEnablePin, false); + 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); @@ -1522,16 +1523,17 @@ static bool spi_dma_check_rx_complete() noexcept #endif #if USE_XDMAC - const uint32_t status = xdmac_channel_get_status(XDMAC); - const uint32_t channelStatus = XDMAC->XDMAC_CHID[DmacChanWiFiRx].XDMAC_CC; - if ( ((status & (1 << DmacChanWiFiRx)) == 0) // channel is not enabled - || (((channelStatus & XDMAC_CC_RDIP) == XDMAC_CC_RDIP_DONE) && ((channelStatus & XDMAC_CC_WRIP) == XDMAC_CC_WRIP_DONE)) // controller is neither reading nor writing via this channel - ) + if ((XDMAC->XDMAC_GS & (1u << DmacChanWiFiRx)) == 0) { - // Disable the channel. - // We also need to set the resume bit, otherwise it remains suspended when we re-enable it. - xdmac_channel_disable(XDMAC, DmacChanWiFiRx); - xdmac_channel_readwrite_resume(XDMAC, DmacChanWiFiRx); + return true; // channel is not enabled + } + + if ((XDMAC->XDMAC_CHID[DmacChanWiFiRx].XDMAC_CC & (XDMAC_CC_RDIP | XDMAC_CC_WRIP)) == 0) + { +// XDMAC->XDMAC_GSWF = (1u << DmacChanWiFiRx); // flush the channel +// while ((XDMAC->XDMAC_CHID[DmacChanWiFiRx].XDMAC_CIS & XDMAC_CIS_FIS) == 0) { } + XDMAC->XDMAC_GD = (1u << DmacChanWiFiRx); // disable the channel + while ((XDMAC->XDMAC_GS & (1u << DmacChanWiFiRx)) != 0) { } // wait for disable to complete return true; } #endif @@ -1563,12 +1565,6 @@ static void spi_tx_dma_setup(const void *buf, uint32_t transferLength) noexcept #if USE_XDMAC xdmac_disable_interrupt(XDMAC, DmacChanWiFiTx); - const uint32_t xdmaint = (XDMAC_CIE_BIE | - XDMAC_CIE_DIE | - XDMAC_CIE_FIE | - XDMAC_CIE_RBIE | - XDMAC_CIE_WBIE | - XDMAC_CIE_ROIE); xdmac_tx_cfg.mbr_ubc = transferLength; xdmac_tx_cfg.mbr_sa = reinterpret_cast(buf); @@ -1590,7 +1586,6 @@ static void spi_tx_dma_setup(const void *buf, uint32_t transferLength) noexcept xdmac_configure_transfer(XDMAC, DmacChanWiFiTx, &xdmac_tx_cfg); xdmac_channel_set_descriptor_control(XDMAC, DmacChanWiFiTx, 0); - xdmac_channel_disable_interrupt(XDMAC, DmacChanWiFiTx, xdmaint); #endif #if USE_DMAC_MANAGER @@ -1624,12 +1619,6 @@ static void spi_rx_dma_setup(void *buf, uint32_t transferLength) noexcept #if USE_XDMAC xdmac_disable_interrupt(XDMAC, DmacChanWiFiRx); - const uint32_t xdmaint = (XDMAC_CIE_BIE | - XDMAC_CIE_DIE | - XDMAC_CIE_FIE | - XDMAC_CIE_RBIE | - XDMAC_CIE_WBIE | - XDMAC_CIE_ROIE); xdmac_rx_cfg.mbr_ubc = transferLength; xdmac_rx_cfg.mbr_da = reinterpret_cast(buf); @@ -1651,7 +1640,6 @@ static void spi_rx_dma_setup(void *buf, uint32_t transferLength) noexcept xdmac_configure_transfer(XDMAC, DmacChanWiFiRx, &xdmac_rx_cfg); xdmac_channel_set_descriptor_control(XDMAC, DmacChanWiFiRx, 0); - xdmac_channel_disable_interrupt(XDMAC, DmacChanWiFiRx, xdmaint); #endif #if USE_DMAC_MANAGER @@ -2021,13 +2009,13 @@ void WiFiInterface::SpiInterrupt() noexcept // Start the ESP void WiFiInterface::StartWiFi() noexcept { - digitalWrite(EspResetPin, true); - #if !WIFI_USES_ESP32 + digitalWrite(EspResetPin, true); delayMicroseconds(150); // ESP8266 datasheet specifies minimum 100us from releasing reset to power up - digitalWrite(EspEnablePin, true); #endif + digitalWrite(EspEnablePin, true); + #if !SAME5x SetPinFunction(APIN_SerialWiFi_TXD, SerialWiFiPeriphMode); // connect the pins to the UART SetPinFunction(APIN_SerialWiFi_RXD, SerialWiFiPeriphMode); // connect the pins to the UART @@ -2046,11 +2034,11 @@ void WiFiInterface::StartWiFi() noexcept // Reset the ESP8266 and leave held in reset void WiFiInterface::ResetWiFi() noexcept { +#if !WIFI_USES_ESP32 pinMode(EspResetPin, OUTPUT_LOW); // assert ESP8266 /RESET +#endif -#if !WIFI_USES_ESP32 pinMode(EspEnablePin, OUTPUT_LOW); -#endif #if !defined(SAME5x) pinMode(APIN_SerialWiFi_TXD, INPUT_PULLUP); // just enable pullups on TxD and RxD pins @@ -2079,13 +2067,13 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept serialRunning = false; } +#if !WIFI_USES_ESP32 // Make sure the ESP8266 is in the reset state pinMode(EspResetPin, OUTPUT_LOW); +#endif -#if !WIFI_USES_ESP32 // Power down the ESP8266 pinMode(EspEnablePin, OUTPUT_LOW); -#endif // Set up our transfer request pin (GPIO4) as an output and set it low pinMode(SamTfrReadyPin, OUTPUT_LOW); @@ -2117,14 +2105,14 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept #endif } +#if !WIFI_USES_ESP32 // Release the reset on the ESP8266 digitalWrite(EspResetPin, true); + delayMicroseconds(150); // ESP8266 datasheet specifies minimum 100us from releasing reset to power up +#endif -#if !WIFI_USES_ESP32 // Take the ESP8266 out of power down - delayMicroseconds(150); // ESP8266 datasheet specifies minimum 100us from releasing reset to power up digitalWrite(EspEnablePin, true); -#endif } #endif // HAS_WIFI_NETWORKING diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index 4b2dc953..c9fc3e3f 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -466,18 +466,17 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::Sync(uint16_t timeou // Send a command to the device to begin the Flash process. WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashBegin(uint32_t offset, uint32_t size) noexcept { - // determine the number of blocks represented by the size - const uint32_t blkCnt = (size + EspFlashBlockSize - 1) / EspFlashBlockSize; - - // ensure that the address is on a block boundary - size += offset & (EspFlashBlockSize - 1); - offset &= ~(EspFlashBlockSize - 1); + // Determine the number of blocks represented by the size + const uint32_t blkCnt = (size + (EspFlashBlockSize - 1)) / EspFlashBlockSize; + // Determine the erase size parameter to pass in the FLASH_BEGIN command +#if WIFI_USES_ESP32 + const uint32_t erase_size = size; +#else // Calculate the number of sectors to erase const uint32_t sector_size = 4 * 1024; uint32_t num_sectors = (size + (sector_size - 1))/sector_size; -#if !WIFI_USES_ESP32 const uint32_t start_sector = offset / sector_size; const uint32_t sectors_per_block = 16; @@ -498,9 +497,9 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashBegin(uint32_t { num_sectors = (num_sectors - head_sectors); } -#endif const uint32_t erase_size = num_sectors * sector_size; +#endif // begin the Flash process #if WIFI_USES_ESP32 @@ -604,22 +603,8 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashWriteBlock(uint WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::DoErase(uint32_t address, uint32_t size) noexcept { - const uint32_t sectorsPerBlock = 16; - const uint32_t sectorSize = 4096; - const uint32_t numSectors = (size + sectorSize - 1)/sectorSize; - const uint32_t startSector = address/sectorSize; - uint32_t headSectors = sectorsPerBlock - (startSector % sectorsPerBlock); - - if (numSectors < headSectors) - { - headSectors = numSectors; - } - const uint32_t eraseSize = (numSectors < 2 * headSectors) - ? (numSectors + 1) / 2 * sectorSize - : (numSectors - headSectors) * sectorSize; - - MessageF("Erasing %u bytes...\n", eraseSize); - return flashBegin(uploadAddress, eraseSize); + MessageF("Erasing %u bytes...\n", size); + return flashBegin(uploadAddress, size); } void WifiFirmwareUploader::Spin() noexcept -- cgit v1.2.3 From 9a5246892c8cb36f822b84db6bf3233555935348 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Wed, 21 Sep 2022 14:51:08 +0100 Subject: More changes to WiFiInterface --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index e30509aa..1b864938 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -542,15 +542,19 @@ void WiFiInterface::Start() noexcept // Set up our transfer request pin (GPIO4) as an output and set it low pinMode(SamTfrReadyPin, OUTPUT_LOW); - // Set up our data ready pin (ESP GPIO0) as an output and set it high ready to boot the ESP from flash + // 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); - // 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); - - // Set our CS input (ESP GPIO15) low ready for booting the ESP. This also clears the transfer ready latch. +#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); @@ -564,8 +568,10 @@ void WiFiInterface::Start() noexcept // - 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); @@ -2084,8 +2090,10 @@ void WiFiInterface::ResetWiFiForUpload(bool external) noexcept // GPIO2 also needs to be high to boot up. It's connected to MISO on the SAM, so set the pullup resistor on that pin pinMode(APIN_ESP_SPI_MISO, INPUT_PULLUP); +#if !WIFI_USES_ESP32 // Set our CS input (ESP GPIO15) low ready for booting the ESP. This also clears the transfer ready latch. pinMode(SamCsPin, OUTPUT_LOW); +#endif // Make sure it has time to reset - no idea how long it needs, but 50ms should be plenty delay(50); -- cgit v1.2.3 From d46c789974c2fe60316aed01bb2d7518a88e42fc Mon Sep 17 00:00:00 2001 From: David Crocker Date: Wed, 21 Sep 2022 15:54:22 +0100 Subject: Fixes for XDMAC with WiFi --- src/Config/Pins_Duet3_MB6HC.h | 5 +++++ src/Networking/ESP8266WiFi/WiFiInterface.cpp | 8 ++------ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/Config/Pins_Duet3_MB6HC.h b/src/Config/Pins_Duet3_MB6HC.h index 2af57679..1517acdd 100644 --- a/src/Config/Pins_Duet3_MB6HC.h +++ b/src/Config/Pins_Duet3_MB6HC.h @@ -396,7 +396,12 @@ constexpr Pin SbcTfrReadyPin = PortEPin(2); #define ESP_SPI SPI1 #define ESP_SPI_INTERFACE_ID ID_SPI1 #define ESP_SPI_IRQn SPI1_IRQn + +#if HAS_SBC_INTERFACE #define ESP_SPI_HANDLER SPI1_WiFi_Handler // SBC interface redirects the interrupt to here +#else +#define ESP_SPI_HANDLER SPI1_Handler // SBC interface redirects the interrupt to here +#endif constexpr Pin APIN_ESP_SPI_MOSI = PortCPin(27); constexpr Pin APIN_ESP_SPI_MISO = PortCPin(26); diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 1b864938..25cc5632 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -1536,9 +1536,7 @@ static bool spi_dma_check_rx_complete() noexcept if ((XDMAC->XDMAC_CHID[DmacChanWiFiRx].XDMAC_CC & (XDMAC_CC_RDIP | XDMAC_CC_WRIP)) == 0) { -// XDMAC->XDMAC_GSWF = (1u << DmacChanWiFiRx); // flush the channel -// while ((XDMAC->XDMAC_CHID[DmacChanWiFiRx].XDMAC_CIS & XDMAC_CIS_FIS) == 0) { } - XDMAC->XDMAC_GD = (1u << DmacChanWiFiRx); // disable the channel + XDMAC->XDMAC_GD = (1u << DmacChanWiFiRx); // disable the channel, which flushes the FIFO while ((XDMAC->XDMAC_GS & (1u << DmacChanWiFiRx)) != 0) { } // wait for disable to complete return true; } @@ -1989,10 +1987,8 @@ void WiFiInterface::SpiInterrupt() noexcept # endif # if USE_XDMAC - spi_tx_dma_disable(); - xdmac_channel_readwrite_suspend(XDMAC, DmacChanWiFiRx); // suspend the receive channel + spi_tx_dma_disable(); // don't suspend receive, it prevents the FIFO from being emptied in checkRxComplete # endif - DisableSpi(); if ((status & SPI_SR_OVRES) != 0) { -- cgit v1.2.3 From 9a21472e4912ad9ef14618fb9b3f6b96ee8887b9 Mon Sep 17 00:00:00 2001 From: rechrtb Date: Thu, 22 Sep 2022 12:21:55 +0800 Subject: Increase timeouts for wifi module operations --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 25cc5632..56b72e5a 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -87,9 +87,10 @@ constexpr IRQn ESP_SPI_IRQn = WiFiSpiSercomIRQn; # include "matrix/matrix.h" #endif -const uint32_t WiFiResponseTimeoutMillis = 500; // Timeout includes time-intensive flash-access operations; highest measured is 234 ms. +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 = 20; // SPI timeout when when the ESP does not have to access SPIFFS filesystem. const uint32_t WiFiWaitReadyMillis = 100; -const uint32_t WiFiStartupMillis = 8000; +const uint32_t WiFiStartupMillis = 15000; // Formatting the SPIFFS partition can take up to 10s. const uint32_t WiFiStableMillis = 100; const unsigned int MaxHttpConnections = 4; @@ -1828,6 +1829,12 @@ int32_t WiFiInterface::SendCommand(NetworkCommand cmd, SocketNumber socketNum, u digitalWrite(SamTfrReadyPin, true); // Wait until the DMA transfer is complete, with timeout + // On factory reset, use the startup timeout, as it involves re-formatting the SPIFFS + // partition. + const uint32_t timeout = (cmd == NetworkCommand::networkFactoryReset) ? WiFiStartupMillis : + (cmd == NetworkCommand::networkAddSsid || cmd == NetworkCommand::networkDeleteSsid || + cmd == NetworkCommand::networkConfigureAccessPoint || cmd == NetworkCommand::networkRetrieveSsidData + ? WiFiSlowResponseTimeoutMillis : WiFiFastResponseTimeoutMillis); do { if (!TaskBase::Take(WiFiResponseTimeoutMillis)) -- cgit v1.2.3 -- cgit v1.2.3 From 213402614353349b7f62612ecb348a76dad7378a Mon Sep 17 00:00:00 2001 From: David Crocker Date: Fri, 23 Sep 2022 13:59:07 +0100 Subject: Corrections to previous cherry-pick --- src/Networking/ESP8266WiFi/WiFiInterface.cpp | 2 +- src/Networking/Network.cpp | 6 ++---- src/Platform/Platform.cpp | 2 +- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/src/Networking/ESP8266WiFi/WiFiInterface.cpp b/src/Networking/ESP8266WiFi/WiFiInterface.cpp index 56b72e5a..e978e071 100644 --- a/src/Networking/ESP8266WiFi/WiFiInterface.cpp +++ b/src/Networking/ESP8266WiFi/WiFiInterface.cpp @@ -1837,7 +1837,7 @@ int32_t WiFiInterface::SendCommand(NetworkCommand cmd, SocketNumber socketNum, u ? WiFiSlowResponseTimeoutMillis : WiFiFastResponseTimeoutMillis); do { - if (!TaskBase::Take(WiFiResponseTimeoutMillis)) + if (!TaskBase::Take(timeout)) { if (reprap.Debug(moduleNetwork)) { diff --git a/src/Networking/Network.cpp b/src/Networking/Network.cpp index e7140eb3..428c097f 100644 --- a/src/Networking/Network.cpp +++ b/src/Networking/Network.cpp @@ -107,10 +107,8 @@ Network::Network(Platform& p) noexcept : platform(p) constexpr ObjectModelArrayDescriptor Network::interfacesArrayDescriptor = { - // 0. Interfaces - { - nullptr, - [] (const ObjectModel *self, const ObjectExplorationContext& context) noexcept -> size_t { return ((Network*)self)->GetNumNetworkInterfaces(); }, + nullptr, + [] (const ObjectModel *self, const ObjectExplorationContext& context) noexcept -> size_t { return ((Network*)self)->GetNumNetworkInterfaces(); }, #if HAS_NETWORKING [] (const ObjectModel *self, ObjectExplorationContext& context) noexcept -> ExpressionValue { return ExpressionValue(((Network*)self)->interfaces[context.GetIndex(0)]); } #endif diff --git a/src/Platform/Platform.cpp b/src/Platform/Platform.cpp index 0a91998c..731c1e2e 100644 --- a/src/Platform/Platform.cpp +++ b/src/Platform/Platform.cpp @@ -361,7 +361,7 @@ constexpr uint8_t Platform::objectModelTableDescriptor[] = { 10, // number of sections 9 + SUPPORT_ACCELEROMETERS + HAS_SBC_INTERFACE + HAS_MASS_STORAGE + HAS_VOLTAGE_MONITOR + HAS_12V_MONITOR + HAS_CPU_TEMP_SENSOR - + SUPPORT_CAN_EXPANSION + SUPPORT_DIRECT_LCD + MCU_HAS_UNIQUE_ID + HAS_WIFI_NETWORKING, // section 0: boards[0] + + SUPPORT_CAN_EXPANSION + SUPPORT_12864_LCD + MCU_HAS_UNIQUE_ID + HAS_WIFI_NETWORKING, // section 0: boards[0] #if HAS_CPU_TEMP_SENSOR 3, // section 1: mcuTemp #else -- cgit v1.2.3 From f94d04a9406f7c21a52f3c72b45c42a6a2268652 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Wed, 21 Sep 2022 02:25:10 +0100 Subject: Improved error message when M950 D used in SBC mode --- src/Platform/Platform.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/Platform/Platform.cpp b/src/Platform/Platform.cpp index 0a91998c..22c8fa31 100644 --- a/src/Platform/Platform.cpp +++ b/src/Platform/Platform.cpp @@ -4583,16 +4583,21 @@ GCodeResult Platform::ConfigurePort(GCodeBuffer& gb, const StringRef& reply) THR #ifdef DUET3_MB6HC case 64: // D # if HAS_SBC_INTERFACE - if (!reprap.UsingSbcInterface()) -# endif + if (reprap.UsingSbcInterface()) { - return MassStorage::ConfigureSdCard(gb, reply); + reply.copy("SD card not supported in SBC mode"); + return GCodeResult::error; } +# endif + return MassStorage::ConfigureSdCard(gb, reply); #endif - //no break default: +#ifdef DUET3_MB6HC + reply.copy("exactly one of FHJPSRD must be given"); +#else reply.copy("exactly one of FHJPSR must be given"); +#endif return GCodeResult::error; } } -- cgit v1.2.3 From 6c176eb1ba04a32cf050a3d0ade7f58a00a8b2e1 Mon Sep 17 00:00:00 2001 From: David Crocker Date: Fri, 23 Sep 2022 15:01:16 +0100 Subject: Correction to WiFiFirmwareUploader --- src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp index c9fc3e3f..3160457c 100644 --- a/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp +++ b/src/Networking/ESP8266WiFi/WifiFirmwareUploader.cpp @@ -604,7 +604,7 @@ WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::flashWriteBlock(uint WifiFirmwareUploader::EspUploadResult WifiFirmwareUploader::DoErase(uint32_t address, uint32_t size) noexcept { MessageF("Erasing %u bytes...\n", size); - return flashBegin(uploadAddress, size); + return flashBegin(address, size); } void WifiFirmwareUploader::Spin() noexcept -- cgit v1.2.3