mirror of
https://github.com/DCC-EX/CommandStation-EX.git
synced 2024-11-24 08:36:14 +01:00
Merge 8223d30892
into d46a6f092a
This commit is contained in:
commit
b1be657e44
|
@ -45,8 +45,8 @@ INTERRUPT_CALLBACK interruptHandler=0;
|
||||||
|
|
||||||
//HardwareTimer* timer = NULL;
|
//HardwareTimer* timer = NULL;
|
||||||
//HardwareTimer* timerAux = NULL;
|
//HardwareTimer* timerAux = NULL;
|
||||||
HardwareTimer timer(TIM2);
|
HardwareTimer timer(TIM3);
|
||||||
HardwareTimer timerAux(TIM3);
|
HardwareTimer timerAux(TIM2);
|
||||||
|
|
||||||
static bool tim2ModeHA = false;
|
static bool tim2ModeHA = false;
|
||||||
static bool tim3ModeHA = false;
|
static bool tim3ModeHA = false;
|
||||||
|
@ -97,9 +97,9 @@ void DCCTimer::setPWM(byte pin, bool high) {
|
||||||
tim3ModeHA = true;
|
tim3ModeHA = true;
|
||||||
}
|
}
|
||||||
if (high)
|
if (high)
|
||||||
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
||||||
else
|
else
|
||||||
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
||||||
break;
|
break;
|
||||||
case 13:
|
case 13:
|
||||||
if (!tim2ModeHA) {
|
if (!tim2ModeHA) {
|
||||||
|
@ -107,9 +107,9 @@ void DCCTimer::setPWM(byte pin, bool high) {
|
||||||
tim2ModeHA = true;
|
tim2ModeHA = true;
|
||||||
}
|
}
|
||||||
if (high)
|
if (high)
|
||||||
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_0;
|
||||||
else
|
else
|
||||||
TIM3->CCMR1 = (TIM3->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
TIM2->CCMR1 = (TIM2->CCMR1 & ~TIM_CCMR1_OC1M_Msk) | TIM_CCMR1_OC1M_1;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -35,12 +35,21 @@ unsigned long MotorDriver::globalOverloadStart = 0;
|
||||||
volatile portreg_t shadowPORTA;
|
volatile portreg_t shadowPORTA;
|
||||||
volatile portreg_t shadowPORTB;
|
volatile portreg_t shadowPORTB;
|
||||||
volatile portreg_t shadowPORTC;
|
volatile portreg_t shadowPORTC;
|
||||||
#if defined(ARDUINO_ARCH_STM32)
|
#if defined(ARDUINO_ARCH_STM32) || (defined(ARDUINO_GIGA) && defined(XGIGA))
|
||||||
volatile portreg_t shadowPORTD;
|
volatile portreg_t shadowPORTD;
|
||||||
volatile portreg_t shadowPORTE;
|
volatile portreg_t shadowPORTE;
|
||||||
volatile portreg_t shadowPORTF;
|
volatile portreg_t shadowPORTF;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(ARDUINO_GIGA) && defined(XGIGA)
|
||||||
|
#define STM_PORT(X) (((uint32_t)(X) >> 4) & 0xF)
|
||||||
|
#define STM_PIN(X) ((uint32_t)(X) & 0xF)
|
||||||
|
#define STM_GPIO_PIN(X) ((uint16_t)(1<<STM_PIN(X)))
|
||||||
|
#define digitalPinToBitMask(p) (STM_GPIO_PIN(digitalPinToPinName(p)))
|
||||||
|
#define portOutputRegister(P) (&(P->ODR))
|
||||||
|
#define portInputRegister(P) (&(P->IDR))
|
||||||
|
#endif
|
||||||
|
|
||||||
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, int16_t brake_pin,
|
||||||
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
|
byte current_pin, float sense_factor, unsigned int trip_milliamps, int16_t fault_pin) {
|
||||||
const FSH * warnString = F("** WARNING **");
|
const FSH * warnString = F("** WARNING **");
|
||||||
|
@ -58,7 +67,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||||
getFastPin(F("SIG"),signalPin,fastSignalPin);
|
getFastPin(F("SIG"),signalPin,fastSignalPin);
|
||||||
pinMode(signalPin, OUTPUT);
|
pinMode(signalPin, OUTPUT);
|
||||||
|
|
||||||
#ifndef ARDUINO_GIGA // no giga
|
#if !defined(ARDUINO_GIGA) || (defined(ARDUINO_GIGA) && defined(XGIGA)) // no giga
|
||||||
fastSignalPin.shadowinout = NULL;
|
fastSignalPin.shadowinout = NULL;
|
||||||
if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) {
|
if (HAVE_PORTA(fastSignalPin.inout == &PORTA)) {
|
||||||
DIAG(F("Found PORTA pin %d"),signalPin);
|
DIAG(F("Found PORTA pin %d"),signalPin);
|
||||||
|
@ -97,7 +106,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
|
||||||
getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
|
getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
|
||||||
pinMode(signalPin2, OUTPUT);
|
pinMode(signalPin2, OUTPUT);
|
||||||
|
|
||||||
#ifndef ARDUINO_GIGA // no giga
|
#if !defined(ARDUINO_GIGA) || (defined(ARDUINO_GIGA) && defined(XGIGA)) // no giga
|
||||||
fastSignalPin2.shadowinout = NULL;
|
fastSignalPin2.shadowinout = NULL;
|
||||||
if (HAVE_PORTA(fastSignalPin2.inout == &PORTA)) {
|
if (HAVE_PORTA(fastSignalPin2.inout == &PORTA)) {
|
||||||
DIAG(F("Found PORTA pin %d"),signalPin2);
|
DIAG(F("Found PORTA pin %d"),signalPin2);
|
||||||
|
@ -508,7 +517,7 @@ unsigned int MotorDriver::mA2raw( unsigned int mA) {
|
||||||
|
|
||||||
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
|
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
|
||||||
// DIAG(F("MotorDriver %S Pin=%d,"),type,pin);
|
// DIAG(F("MotorDriver %S Pin=%d,"),type,pin);
|
||||||
#if defined(ARDUINO_GIGA) // yes giga
|
#if defined(ARDUINO_GIGA) && !defined(XGIGA) // yes giga
|
||||||
(void)type;
|
(void)type;
|
||||||
(void)input; // no warnings please
|
(void)input; // no warnings please
|
||||||
|
|
||||||
|
@ -520,6 +529,8 @@ void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & res
|
||||||
PortGroup *port = digitalPinToPort(pin);
|
PortGroup *port = digitalPinToPort(pin);
|
||||||
#elif defined(ARDUINO_ARCH_STM32)
|
#elif defined(ARDUINO_ARCH_STM32)
|
||||||
GPIO_TypeDef *port = digitalPinToPort(pin);
|
GPIO_TypeDef *port = digitalPinToPort(pin);
|
||||||
|
#elif defined(ARDUINO_GIGA)
|
||||||
|
auto * port = ((GPIO_TypeDef *)(GPIOA_BASE + (GPIOB_BASE - GPIOA_BASE) * (digitalPinToPinName(pin) >> 4)));
|
||||||
#else
|
#else
|
||||||
uint8_t port = digitalPinToPort(pin);
|
uint8_t port = digitalPinToPort(pin);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
// use powers of two so we can do logical and/or on the track modes in if clauses.
|
// use powers of two so we can do logical and/or on the track modes in if clauses.
|
||||||
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PROG = 4,
|
||||||
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
|
TRACK_MODE_DC = 8, TRACK_MODE_DCX = 16, TRACK_MODE_EXT = 32};
|
||||||
#if defined(ARDUINO_GIGA) // yes giga
|
#if defined(ARDUINO_GIGA) && !defined(XGIGA) // yes giga
|
||||||
|
|
||||||
#define setHIGH(fastpin) digitalWrite(fastpin,1)
|
#define setHIGH(fastpin) digitalWrite(fastpin,1)
|
||||||
#define setLOW(fastpin) digitalWrite(fastpin,0)
|
#define setLOW(fastpin) digitalWrite(fastpin,0)
|
||||||
|
@ -39,7 +39,7 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||||
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
|
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
|
||||||
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
|
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
|
||||||
#endif // giga
|
#endif // giga
|
||||||
#if defined(ARDUINO_GIGA) // yes giga
|
#if defined(ARDUINO_GIGA) && !defined(XGIGA) // yes giga
|
||||||
#define isHIGH(fastpin) ((PinStatus)digitalRead(fastpin)==1)
|
#define isHIGH(fastpin) ((PinStatus)digitalRead(fastpin)==1)
|
||||||
#define isLOW(fastpin) ((PinStatus)digitalRead(fastpin)==0)
|
#define isLOW(fastpin) ((PinStatus)digitalRead(fastpin)==0)
|
||||||
#else // no giga
|
#else // no giga
|
||||||
|
@ -82,6 +82,25 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(ARDUINO_GIGA) && defined(XGIGA)
|
||||||
|
#define PORTA GPIOA->ODR
|
||||||
|
#define HAVE_PORTA(X) X
|
||||||
|
#define PORTB GPIOB->ODR
|
||||||
|
#define HAVE_PORTB(X) X
|
||||||
|
#define PORTC GPIOC->ODR
|
||||||
|
#define HAVE_PORTC(X) X
|
||||||
|
#define PORTD GPIOD->ODR
|
||||||
|
#define HAVE_PORTD(X) X
|
||||||
|
#if defined(GPIOE)
|
||||||
|
#define PORTE GPIOE->ODR
|
||||||
|
#define HAVE_PORTE(X) X
|
||||||
|
#endif
|
||||||
|
#if defined(GPIOF)
|
||||||
|
#define PORTF GPIOF->ODR
|
||||||
|
#define HAVE_PORTF(X) X
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
// if macros not defined as pass-through we define
|
// if macros not defined as pass-through we define
|
||||||
// them here as someting that is valid as a
|
// them here as someting that is valid as a
|
||||||
// statement and evaluates to false.
|
// statement and evaluates to false.
|
||||||
|
@ -121,13 +140,13 @@ public:
|
||||||
byte invpin = UNUSED_PIN;
|
byte invpin = UNUSED_PIN;
|
||||||
};
|
};
|
||||||
|
|
||||||
#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
|
#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32) || (defined(ARDUINO_GIGA) && defined(XGIGA))
|
||||||
typedef uint32_t portreg_t;
|
typedef uint32_t portreg_t;
|
||||||
#else
|
#else
|
||||||
typedef uint8_t portreg_t;
|
typedef uint8_t portreg_t;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(ARDUINO_GIGA) // yes giga
|
#if defined(ARDUINO_GIGA) && !defined(XGIGA) // yes giga
|
||||||
typedef int FASTPIN;
|
typedef int FASTPIN;
|
||||||
|
|
||||||
|
|
||||||
|
@ -165,7 +184,7 @@ class MotorDriver {
|
||||||
// otherwise the call from interrupt context can undo whatever we do
|
// otherwise the call from interrupt context can undo whatever we do
|
||||||
// from outside interrupt
|
// from outside interrupt
|
||||||
void setBrake( bool on, bool interruptContext=false);
|
void setBrake( bool on, bool interruptContext=false);
|
||||||
#if defined(ARDUINO_GIGA) // yes giga
|
#if defined(ARDUINO_GIGA) && !defined(XGIGA) // yes giga
|
||||||
__attribute__((always_inline)) inline void setSignal( bool high) {
|
__attribute__((always_inline)) inline void setSignal( bool high) {
|
||||||
digitalWrite(signalPin, high);
|
digitalWrite(signalPin, high);
|
||||||
if (dualSignal) digitalWrite(signalPin2, !high);
|
if (dualSignal) digitalWrite(signalPin2, !high);
|
||||||
|
|
244
Wifi_NINA.cpp
244
Wifi_NINA.cpp
|
@ -2,6 +2,8 @@
|
||||||
© 2023 Paul M. Antoine
|
© 2023 Paul M. Antoine
|
||||||
© 2021 Harald Barth
|
© 2021 Harald Barth
|
||||||
© 2023 Nathan Kellenicki
|
© 2023 Nathan Kellenicki
|
||||||
|
© 2023 Travis Farmer
|
||||||
|
© 2023 Chris Harlow
|
||||||
|
|
||||||
This file is part of CommandStation-EX
|
This file is part of CommandStation-EX
|
||||||
|
|
||||||
|
@ -20,20 +22,19 @@
|
||||||
*/
|
*/
|
||||||
#include "defines.h"
|
#include "defines.h"
|
||||||
|
|
||||||
#ifdef WIFI_NINA
|
#ifdef WIFI_NINA || GIGA_WIFI
|
||||||
#include <vector>
|
//#include <vector>
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
#ifndef ARDUINO_GIGA
|
#ifndef ARDUINO_GIGA
|
||||||
#include <WifiNINA.h>
|
#include <WifiNINA.h>
|
||||||
#else
|
#else
|
||||||
|
#if defined(GIGA_WIFI)
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
|
#else
|
||||||
|
#include <WiFiNINA.h>
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#include "Wifi_NINA.h"
|
#include "Wifi_NINA.h"
|
||||||
// #include "ESPmDNS.h"
|
|
||||||
// #include <WiFi.h>
|
|
||||||
// #include "esp_wifi.h"
|
|
||||||
// #include "WifiESP32.h"
|
|
||||||
// #include <SPI.h>
|
|
||||||
#include "DIAG.h"
|
#include "DIAG.h"
|
||||||
#include "RingStream.h"
|
#include "RingStream.h"
|
||||||
#include "CommandDistributor.h"
|
#include "CommandDistributor.h"
|
||||||
|
@ -46,49 +47,22 @@
|
||||||
#define ESP32_RESETN PA10 // Reset pin
|
#define ESP32_RESETN PA10 // Reset pin
|
||||||
#define SPIWIFI_ACK PB3 // a.k.a BUSY or READY pin
|
#define SPIWIFI_ACK PB3 // a.k.a BUSY or READY pin
|
||||||
#define ESP32_GPIO0 -1
|
#define ESP32_GPIO0 -1
|
||||||
|
#elif defined(ARDUINO_GIGA)
|
||||||
|
#define SPIWIFI SPI
|
||||||
|
#define SPIWIFI_SS 10 // Chip select pin
|
||||||
|
#define SPIWIFI_ACK 7 // a.k.a BUSY or READY pin
|
||||||
|
#define ESP32_RESETN 5 // Reset pin
|
||||||
|
#define ESP32_GPIO0 -1 // Not connected
|
||||||
#else
|
#else
|
||||||
#warning "WiFiNINA has no SPI port or pin allocations for this archiecture yet!"
|
#warning "WiFiNINA has no SPI port or pin allocations for this archiecture yet!"
|
||||||
#endif
|
#endif
|
||||||
|
#define MAX_CLIENTS 10
|
||||||
|
|
||||||
class NetworkClient {
|
|
||||||
public:
|
|
||||||
NetworkClient(WiFiClient c) {
|
|
||||||
wifi = c;
|
|
||||||
};
|
|
||||||
bool ok() {
|
|
||||||
return (inUse && wifi.connected());
|
|
||||||
};
|
|
||||||
bool recycle(WiFiClient c) {
|
|
||||||
|
|
||||||
if (inUse == true) return false;
|
|
||||||
|
|
||||||
// return false here until we have
|
|
||||||
// implemented a LRU timer
|
|
||||||
// if (LRU too recent) return false;
|
|
||||||
return false;
|
|
||||||
|
|
||||||
wifi = c;
|
|
||||||
inUse = true;
|
|
||||||
return true;
|
|
||||||
};
|
|
||||||
WiFiClient wifi;
|
|
||||||
bool inUse = true;
|
|
||||||
};
|
|
||||||
|
|
||||||
static std::vector<NetworkClient> clients; // a list to hold all clients
|
|
||||||
static WiFiServer *server = NULL;
|
static WiFiServer *server = NULL;
|
||||||
static RingStream *outboundRing = new RingStream(10240);
|
static RingStream *outboundRing = new RingStream(10240);
|
||||||
static bool APmode = false;
|
static bool APmode = false;
|
||||||
static IPAddress ip;
|
static IPAddress ip;
|
||||||
|
|
||||||
// #ifdef WIFI_TASK_ON_CORE0
|
|
||||||
// void wifiLoop(void *){
|
|
||||||
// for(;;){
|
|
||||||
// WifiNINA::loop();
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// #endif
|
|
||||||
|
|
||||||
char asciitolower(char in) {
|
char asciitolower(char in) {
|
||||||
if (in <= 'Z' && in >= 'A')
|
if (in <= 'Z' && in >= 'A')
|
||||||
return in - ('Z' - 'z');
|
return in - ('Z' - 'z');
|
||||||
|
@ -107,7 +81,7 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
uint8_t tries = 40;
|
uint8_t tries = 40;
|
||||||
|
|
||||||
// Set up the pins!
|
// Set up the pins!
|
||||||
#ifndef ARDUINO_GIGA
|
#ifndef GIGA_WIFI
|
||||||
WiFi.setPins(SPIWIFI_SS, SPIWIFI_ACK, ESP32_RESETN, ESP32_GPIO0, &SPIWIFI);
|
WiFi.setPins(SPIWIFI_SS, SPIWIFI_ACK, ESP32_RESETN, ESP32_GPIO0, &SPIWIFI);
|
||||||
#endif
|
#endif
|
||||||
// check for the WiFi module:
|
// check for the WiFi module:
|
||||||
|
@ -121,14 +95,6 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
String fv = WiFi.firmwareVersion();
|
String fv = WiFi.firmwareVersion();
|
||||||
DIAG(F("WifiNINA Firmware version found:%s"), fv.c_str());
|
DIAG(F("WifiNINA Firmware version found:%s"), fv.c_str());
|
||||||
|
|
||||||
// clean start
|
|
||||||
// WiFi.mode(WIFI_STA);
|
|
||||||
// WiFi.disconnect(true);
|
|
||||||
// differnet settings that did not improve for haba
|
|
||||||
// WiFi.useStaticBuffers(true);
|
|
||||||
// WiFi.setScanMethod(WIFI_ALL_CHANNEL_SCAN);
|
|
||||||
// WiFi.setSortMethod(WIFI_CONNECT_AP_BY_SECURITY);
|
|
||||||
|
|
||||||
const char *yourNetwork = "Your network ";
|
const char *yourNetwork = "Your network ";
|
||||||
if (strncmp(yourNetwork, SSid, 13) == 0 || strncmp("", SSid, 13) == 0)
|
if (strncmp(yourNetwork, SSid, 13) == 0 || strncmp("", SSid, 13) == 0)
|
||||||
haveSSID = false;
|
haveSSID = false;
|
||||||
|
@ -148,8 +114,8 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
delay(500);
|
delay(500);
|
||||||
}
|
}
|
||||||
if (WiFi.status() == WL_CONNECTED) {
|
if (WiFi.status() == WL_CONNECTED) {
|
||||||
// String ip_str = sprintf("%xl", WiFi.localIP());
|
IPAddress ip = WiFi.localIP();
|
||||||
DIAG(F("Wifi STA IP %d.%d.%d.%d"), WiFi.localIP()[0], WiFi.localIP()[1],WiFi.localIP()[2],WiFi.localIP()[3],WiFi.localIP()[4],WiFi.localIP()[5]);
|
DIAG(F("Wifi STA IP %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
|
||||||
wifiUp = true;
|
wifiUp = true;
|
||||||
} else {
|
} else {
|
||||||
DIAG(F("Could not connect to Wifi SSID %s"),SSid);
|
DIAG(F("Could not connect to Wifi SSID %s"),SSid);
|
||||||
|
@ -164,7 +130,7 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
}
|
}
|
||||||
if (WiFi.status() == WL_CONNECTED) {
|
if (WiFi.status() == WL_CONNECTED) {
|
||||||
ip = WiFi.localIP();
|
ip = WiFi.localIP();
|
||||||
DIAG(F("Wifi STA IP 2nd try %s"), ip);
|
DIAG(F("Wifi STA IP 2nd try %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
|
||||||
wifiUp = true;
|
wifiUp = true;
|
||||||
} else {
|
} else {
|
||||||
DIAG(F("Wifi STA mode FAIL. Will revert to AP mode"));
|
DIAG(F("Wifi STA mode FAIL. Will revert to AP mode"));
|
||||||
|
@ -184,13 +150,13 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
strMac += String(mac[i], HEX);
|
strMac += String(mac[i], HEX);
|
||||||
}
|
}
|
||||||
|
|
||||||
DIAG(F("MAC address: %x:%x:%x:%x:%X;%x"), mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
|
DIAG(F("MAC address: %x:%x:%x:%x:%x:%x"), mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
|
||||||
|
|
||||||
strMac.remove(0,9);
|
strMac.remove(0,9);
|
||||||
strMac.replace(":","");
|
strMac.replace(":","");
|
||||||
strMac.replace(":","");
|
strMac.replace(":","");
|
||||||
// convert mac addr hex chars to lower case to be compatible with AT software
|
// convert mac addr hex chars to lower case to be compatible with AT software
|
||||||
std::transform(strMac.begin(), strMac.end(), strMac.begin(), asciitolower);
|
//std::transform(strMac.begin(), strMac.end(), strMac.begin(), asciitolower); ///TJF: why does this fail compile with WiFiNINA, but not giga WiFi???
|
||||||
strSSID.concat(strMac);
|
strSSID.concat(strMac);
|
||||||
strPass.concat(strMac);
|
strPass.concat(strMac);
|
||||||
}
|
}
|
||||||
|
@ -200,7 +166,7 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
channel) == WL_AP_LISTENING) {
|
channel) == WL_AP_LISTENING) {
|
||||||
DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str());
|
DIAG(F("Wifi AP SSID %s PASS %s"),strSSID.c_str(),havePassword ? password : strPass.c_str());
|
||||||
ip = WiFi.localIP();
|
ip = WiFi.localIP();
|
||||||
DIAG(F("Wifi AP IP %s"),ip);
|
DIAG(F("Wifi AP IP %d.%d.%d.%d"),ip[0], ip[1], ip[2], ip[3]);
|
||||||
wifiUp = true;
|
wifiUp = true;
|
||||||
APmode = true;
|
APmode = true;
|
||||||
} else {
|
} else {
|
||||||
|
@ -228,26 +194,11 @@ bool WifiNINA::setup(const char *SSid,
|
||||||
server->begin();
|
server->begin();
|
||||||
// server started here
|
// server started here
|
||||||
|
|
||||||
// #ifdef WIFI_TASK_ON_CORE0
|
|
||||||
// //start loop task
|
|
||||||
// if (pdPASS != xTaskCreatePinnedToCore(
|
|
||||||
// wifiLoop, /* Task function. */
|
|
||||||
// "wifiLoop",/* name of task. */
|
|
||||||
// 10000, /* Stack size of task */
|
|
||||||
// NULL, /* parameter of the task */
|
|
||||||
// 1, /* priority of the task */
|
|
||||||
// NULL, /* Task handle to keep track of created task */
|
|
||||||
// 0)) { /* pin task to core 0 */
|
|
||||||
// DIAG(F("Could not create wifiLoop task"));
|
|
||||||
// return false;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// // report server started after wifiLoop creation
|
|
||||||
// // when everything looks good
|
|
||||||
// DIAG(F("Server starting (core 0) port %d"),port);
|
|
||||||
// #else
|
|
||||||
DIAG(F("Server will be started on port %d"),port);
|
DIAG(F("Server will be started on port %d"),port);
|
||||||
// #endif
|
|
||||||
|
ip = WiFi.localIP();
|
||||||
|
LCD(4,F("IP: %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
|
||||||
|
LCD(5,F("Port:%d"), port);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -261,107 +212,78 @@ const char *wlerror[] = {
|
||||||
"WL_DISCONNECTED"
|
"WL_DISCONNECTED"
|
||||||
};
|
};
|
||||||
|
|
||||||
void WifiNINA::loop() {
|
WiFiClient * clients[MAX_CLIENTS]; // nulled in setup
|
||||||
int clientId; //tmp loop var
|
|
||||||
|
|
||||||
// really no good way to check for LISTEN especially in AP mode?
|
void WifiNINA::checkForNewClient() {
|
||||||
wl_status_t wlStatus;
|
auto newClient=server->available();
|
||||||
if (APmode || (wlStatus = (wl_status_t)WiFi.status()) == WL_CONNECTED) {
|
if (!newClient) return;
|
||||||
// loop over all clients and remove inactive
|
for (byte clientId=0; clientId<MAX_CLIENTS; clientId++){
|
||||||
for (clientId=0; clientId<clients.size(); clientId++){
|
if (!clients[clientId]) {
|
||||||
// check if client is there and alive
|
clients[clientId]= new WiFiClient(newClient); // use this slot
|
||||||
if(clients[clientId].inUse && !clients[clientId].wifi.connected()) {
|
clients[clientId]->flush(); // clear out the input buffer
|
||||||
|
DIAG(F("New client connected to slot %d"),clientId); //TJF: brought in for debugging.
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void WifiNINA::checkForLostClients() {
|
||||||
|
for (byte clientId=0; clientId<MAX_CLIENTS; clientId++){
|
||||||
|
auto c=clients[clientId];
|
||||||
|
if(c && !c->connected()) {
|
||||||
|
clients[clientId]->stop();
|
||||||
DIAG(F("Remove client %d"), clientId);
|
DIAG(F("Remove client %d"), clientId);
|
||||||
CommandDistributor::forget(clientId);
|
CommandDistributor::forget(clientId);
|
||||||
clients[clientId].wifi.stop();
|
//delete c; //TJF: this causes a crash when client drops.. commenting out for now.
|
||||||
clients[clientId].inUse = false;
|
clients[clientId]=nullptr; // TJF: what to do... what to do...
|
||||||
//Do NOT clients.erase(clients.begin()+clientId) as
|
|
||||||
//that would mix up clientIds for later.
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (server->available()) {
|
|
||||||
WiFiClient client;
|
|
||||||
while (client = server->available()) {
|
|
||||||
for (clientId=0; clientId<clients.size(); clientId++){
|
|
||||||
if (clients[clientId].recycle(client)) {
|
|
||||||
ip = client.remoteIP();
|
|
||||||
DIAG(F("Recycle client %d %s"), clientId, ip);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (clientId>=clients.size()) {
|
|
||||||
NetworkClient nc(client);
|
|
||||||
clients.push_back(nc);
|
|
||||||
ip = client.remoteIP();
|
|
||||||
DIAG(F("New client %d, %s"), clientId, ip);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// loop over all connected clients
|
|
||||||
for (clientId=0; clientId<clients.size(); clientId++){
|
void WifiNINA::checkForClientInput() {
|
||||||
if(clients[clientId].ok()) {
|
// Find a client providing input
|
||||||
int len;
|
for (byte clientId=0; clientId<MAX_CLIENTS; clientId++){
|
||||||
if ((len = clients[clientId].wifi.available()) > 0) {
|
auto c=clients[clientId];
|
||||||
|
if(c) {
|
||||||
|
auto len=c->available();
|
||||||
|
if (len) {
|
||||||
// read data from client
|
// read data from client
|
||||||
byte cmd[len+1];
|
byte cmd[len+1];
|
||||||
for(int i=0; i<len; i++) {
|
for(int i=0; i<len; i++) cmd[i]=c->read();
|
||||||
cmd[i]=clients[clientId].wifi.read();
|
|
||||||
}
|
|
||||||
cmd[len]=0;
|
cmd[len]=0;
|
||||||
CommandDistributor::parse(clientId,cmd,outboundRing);
|
CommandDistributor::parse(clientId,cmd,outboundRing);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} // all clients
|
}
|
||||||
|
}
|
||||||
WiThrottle::loop(outboundRing);
|
|
||||||
|
|
||||||
|
void WifiNINA::checkForClientOutput() {
|
||||||
// something to write out?
|
// something to write out?
|
||||||
clientId=outboundRing->read();
|
auto clientId=outboundRing->read();
|
||||||
if (clientId >= 0) {
|
if (clientId < 0) return;
|
||||||
// We have data to send in outboundRing
|
auto replySize=outboundRing->count();
|
||||||
// and we have a valid clientId.
|
if (replySize==0) return; // nothing to send
|
||||||
// First read it out to buffer
|
auto c=clients[clientId];
|
||||||
// and then look if it can be sent because
|
if (!c) {
|
||||||
// we can not leave it in the ring for ever
|
// client is gone, throw away msg
|
||||||
int count=outboundRing->count();
|
for (int i=0;i<replySize;i++) outboundRing->read();
|
||||||
{
|
DIAG(F("gone, drop message.")); //TJF: only for diag
|
||||||
char buffer[count+1]; // one extra for '\0'
|
return;
|
||||||
for(int i=0;i<count;i++) {
|
|
||||||
int c = outboundRing->read();
|
|
||||||
if (c >= 0) // Panic check, should never be false
|
|
||||||
buffer[i] = (char)c;
|
|
||||||
else {
|
|
||||||
DIAG(F("Ringread fail at %d"),i);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
// buffer filled, end with '\0' so we can use it as C string
|
|
||||||
buffer[count]='\0';
|
|
||||||
if((unsigned int)clientId <= clients.size() && clients[clientId].ok()) {
|
|
||||||
if (Diag::CMD || Diag::WITHROTTLE)
|
|
||||||
DIAG(F("SEND %d:%s"), clientId, buffer);
|
|
||||||
clients[clientId].wifi.write(buffer,count);
|
|
||||||
} else {
|
|
||||||
DIAG(F("Unsent(%d): %s"), clientId, buffer);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (!APmode) { // in STA mode but not connected any more
|
|
||||||
// kick it again
|
|
||||||
if (wlStatus <= 6) {
|
|
||||||
DIAG(F("Wifi aborted with error %s. Kicking Wifi!"), wlerror[wlStatus]);
|
|
||||||
// esp_wifi_start();
|
|
||||||
// esp_wifi_connect();
|
|
||||||
uint8_t tries=40;
|
|
||||||
while (WiFi.status() != WL_CONNECTED && tries) {
|
|
||||||
Serial.print('.');
|
|
||||||
tries--;
|
|
||||||
delay(500);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
// all well, probably
|
|
||||||
//DIAG(F("Running BT"));
|
|
||||||
}
|
}
|
||||||
|
// emit data to the client object
|
||||||
|
// This should work in theory, the
|
||||||
|
//DIAG(F("send message")); //TJF: only for diag
|
||||||
|
//TJF: the old code had to add a 0x00 byte to the end to terminate the
|
||||||
|
//TJF: c string, before sending it. i take it this is not needed?
|
||||||
|
for (int i=0;i<replySize;i++) c->write(outboundRing->read());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void WifiNINA::loop() {
|
||||||
|
checkForLostClients(); // ***
|
||||||
|
checkForNewClient();
|
||||||
|
checkForClientInput(); // ***
|
||||||
|
WiThrottle::loop(outboundRing); // allow withrottle to broadcast if needed
|
||||||
|
checkForClientOutput();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // WIFI_NINA
|
#endif // WIFI_NINA
|
|
@ -38,5 +38,9 @@ public:
|
||||||
const bool forceAP);
|
const bool forceAP);
|
||||||
static void loop();
|
static void loop();
|
||||||
private:
|
private:
|
||||||
|
static void checkForNewClient();
|
||||||
|
static void checkForLostClients();
|
||||||
|
static void checkForClientInput();
|
||||||
|
static void checkForClientOutput();
|
||||||
};
|
};
|
||||||
#endif //WifiNINA_h
|
#endif //WifiNINA_h
|
||||||
|
|
Loading…
Reference in New Issue
Block a user