incremental enhancements on train trip
This commit is contained in:
parent
b3ac2c5506
commit
e7360f2c1e
|
|
@ -1,17 +1,14 @@
|
||||||
#include <WiFi.h>
|
#include <WiFi.h>
|
||||||
#include <ESPAsyncWebServer.h>
|
#include <ESPAsyncWebServer.h>
|
||||||
#include <SPIFFS.h>
|
#include <SPIFFS.h>
|
||||||
|
|
||||||
#include <U8x8lib.h>
|
#include <U8x8lib.h>
|
||||||
|
#include <SPI.h>
|
||||||
|
|
||||||
|
#include <SX1278FSK.h>
|
||||||
#include <Sonde.h>
|
#include <Sonde.h>
|
||||||
#include <Scanner.h>
|
#include <Scanner.h>
|
||||||
|
//#include <RS41.h>
|
||||||
|
//#include <DFM.h>
|
||||||
#include <RS41.h>
|
|
||||||
#include <SX1278FSK.h>
|
|
||||||
#include <rsc.h>
|
|
||||||
|
|
||||||
#include <SPI.h>
|
|
||||||
|
|
||||||
#define LORA_LED 9
|
#define LORA_LED 9
|
||||||
|
|
||||||
|
|
@ -26,24 +23,9 @@ U8X8_SSD1306_128X64_NONAME_SW_I2C u8x8(/* clock=*/ OLED_SCL, /* data=*/ OLED_SDA
|
||||||
//U8G2_SSD1306_128X64_NONAME_F_SW_I2C Display(U8G2_R0, /* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Full framebuffer, SW I2C
|
//U8G2_SSD1306_128X64_NONAME_F_SW_I2C Display(U8G2_R0, /* clock=*/ OLED_SCL, /* data=*/ OLED_SDA, /* reset=*/ OLED_RST); // Full framebuffer, SW I2C
|
||||||
|
|
||||||
int e;
|
int e;
|
||||||
char my_packet[100];
|
|
||||||
|
|
||||||
//const char* ssid = "DinoGast";
|
|
||||||
//const char* password = "Schokolade";
|
|
||||||
const char *ssid="AndroidDD";
|
|
||||||
const char *password="dl9rdzhr";
|
|
||||||
|
|
||||||
AsyncWebServer server(80);
|
AsyncWebServer server(80);
|
||||||
|
|
||||||
//pthread_t wifithread;
|
|
||||||
|
|
||||||
|
|
||||||
int conn = 0;
|
|
||||||
String currentLine;
|
|
||||||
WiFiClient client;
|
|
||||||
unsigned long lastdu;
|
|
||||||
|
|
||||||
|
|
||||||
// Set LED GPIO
|
// Set LED GPIO
|
||||||
const int ledPin = 2;
|
const int ledPin = 2;
|
||||||
// Stores LED state
|
// Stores LED state
|
||||||
|
|
@ -131,97 +113,38 @@ const char *fetchWifiPw(const char *id) {
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if 0
|
|
||||||
void wifiloop(void *arg){
|
|
||||||
lastdu=millis();
|
|
||||||
while(true) {
|
|
||||||
if(millis()-lastdu>500) {
|
|
||||||
// This is too slow to do in main loop
|
|
||||||
//u8x8.setFont(u8x8_font_chroma48medium8_r);
|
|
||||||
//u8x8.clearDisplay();
|
|
||||||
sonde.updateDisplay();
|
|
||||||
lastdu=millis();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
enum KeyPress { KP_NONE=0, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
||||||
delay(1);
|
|
||||||
if(!conn) {
|
|
||||||
client = server.available(); // listen for incoming clients
|
|
||||||
if (client) { // if you get a client,
|
|
||||||
Serial.println("New Client."); // print a message out the serial port
|
|
||||||
currentLine = ""; // make a String to hold incoming data from the client
|
|
||||||
conn = 1;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
if(!client.connected()) { // loop while the client's connected
|
|
||||||
conn = 0;
|
|
||||||
Serial.println("Client no longer connected");
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
while (client.available()) { // if there's bytes to read from the client,
|
|
||||||
char c = client.read(); // read a byte, then
|
|
||||||
Serial.write(c); // print it out the serial monitor
|
|
||||||
if (c == '\n') { // if the byte is a newline character
|
|
||||||
|
|
||||||
// if the current line is blank, you got two newline characters in a row.
|
|
||||||
// that's the end of the client HTTP request, so send a response:
|
|
||||||
if (currentLine.length() == 0) {
|
|
||||||
// HTTP headers always start with a response code (e.g. HTTP/1.1 200 OK)
|
|
||||||
// and a content-type so the client knows what's coming, then a blank line:
|
|
||||||
client.println("HTTP/1.1 200 OK");
|
|
||||||
client.println("Content-type:text/html");
|
|
||||||
client.println();
|
|
||||||
|
|
||||||
// the content of the HTTP response follows the header:
|
|
||||||
client.print("Click <a href=\"/H\">here</a> to turn the LED on pin 5 on.<br>");
|
|
||||||
client.print("Click <a href=\"/L\">here</a> to turn the LED on pin 5 off.<br>");
|
|
||||||
|
|
||||||
// The HTTP response ends with another blank line:
|
|
||||||
client.println();
|
|
||||||
// break out of the while loop:
|
|
||||||
// close the connection:
|
|
||||||
client.stop();
|
|
||||||
Serial.println("Client Disconnected.");
|
|
||||||
continue;
|
|
||||||
} else { // if you got a newline, then clear currentLine:
|
|
||||||
currentLine = "";
|
|
||||||
}
|
|
||||||
} else if (c != '\r') { // if you got anything else but a carriage return character,
|
|
||||||
currentLine += c; // add it to the end of the currentLine
|
|
||||||
}
|
|
||||||
|
|
||||||
// Check to see if the client request was "GET /H" or "GET /L":
|
|
||||||
if (currentLine.endsWith("GET /H")) {
|
|
||||||
digitalWrite(5, HIGH); // GET /H turns the LED on
|
|
||||||
}
|
|
||||||
if (currentLine.endsWith("GET /L")) {
|
|
||||||
digitalWrite(5, LOW); // GET /L turns the LED off
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
enum KeyPress { KP_NONE, KP_SHORT, KP_DOUBLE, KP_MID, KP_LONG };
|
|
||||||
|
|
||||||
struct Button {
|
struct Button {
|
||||||
const uint8_t PIN;
|
const uint8_t PIN;
|
||||||
uint32_t numberKeyPresses;
|
uint32_t numberKeyPresses;
|
||||||
KeyPress pressed;
|
KeyPress pressed;
|
||||||
unsigned long press;
|
unsigned long press_ts;
|
||||||
|
boolean doublepress;
|
||||||
};
|
};
|
||||||
Button button1 = {0, 0, KP_NONE, 0};
|
Button button1 = {0, 0, KP_NONE, 0, false};
|
||||||
|
|
||||||
void IRAM_ATTR buttonISR() {
|
void IRAM_ATTR buttonISR() {
|
||||||
if(digitalRead(0)==0) { // Button down
|
if(digitalRead(0)==0) { // Button down
|
||||||
button1.press = millis();
|
if(millis()-button1.press_ts<500) {
|
||||||
|
// Double press
|
||||||
|
button1.doublepress = true;
|
||||||
|
} else {
|
||||||
|
button1.doublepress = false;
|
||||||
|
}
|
||||||
|
button1.press_ts = millis();
|
||||||
} else { //Button up
|
} else { //Button up
|
||||||
unsigned int elapsed = millis()-button1.press;
|
unsigned int elapsed = millis()-button1.press_ts;
|
||||||
if(elapsed>1500) { if(elapsed<4000) { button1.pressed=KP_MID; } else { button1.pressed=KP_LONG; } }
|
if(elapsed>1500) {
|
||||||
else { button1.pressed=KP_SHORT; }
|
if(elapsed<4000) { button1.pressed=KP_MID; }
|
||||||
|
else { button1.pressed=KP_LONG; }
|
||||||
|
} else {
|
||||||
|
if(button1.doublepress) button1.pressed=KP_DOUBLE;
|
||||||
|
else button1.pressed=KP_SHORT;
|
||||||
|
}
|
||||||
button1.numberKeyPresses += 1;
|
button1.numberKeyPresses += 1;
|
||||||
|
button1.press_ts = millis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@ -230,6 +153,9 @@ int getKeyPress() {
|
||||||
button1.pressed = KP_NONE;
|
button1.pressed = KP_NONE;
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
|
int hasKeyPress() {
|
||||||
|
return button1.pressed;
|
||||||
|
}
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
|
@ -248,8 +174,7 @@ void setup()
|
||||||
|
|
||||||
setupWifiList();
|
setupWifiList();
|
||||||
|
|
||||||
rs41.setup();
|
#if 0
|
||||||
|
|
||||||
if(rs41.setFrequency(402700000)==0) {
|
if(rs41.setFrequency(402700000)==0) {
|
||||||
Serial.println(F("Setting freq: SUCCESS "));
|
Serial.println(F("Setting freq: SUCCESS "));
|
||||||
} else {
|
} else {
|
||||||
|
|
@ -258,8 +183,9 @@ void setup()
|
||||||
float f = sx1278.getFrequency();
|
float f = sx1278.getFrequency();
|
||||||
Serial.print("Frequency set to ");
|
Serial.print("Frequency set to ");
|
||||||
Serial.println(f);
|
Serial.println(f);
|
||||||
|
#endif
|
||||||
|
|
||||||
sx1278.setLNAGain(-48);
|
sx1278.setLNAGain(0); //-48);
|
||||||
int gain = sx1278.getLNAGain();
|
int gain = sx1278.getLNAGain();
|
||||||
Serial.print("RX LNA Gain is ");
|
Serial.print("RX LNA Gain is ");
|
||||||
Serial.println(gain);
|
Serial.println(gain);
|
||||||
|
|
@ -279,25 +205,84 @@ void setup()
|
||||||
|
|
||||||
// Handle button press
|
// Handle button press
|
||||||
attachInterrupt(0, buttonISR, CHANGE);
|
attachInterrupt(0, buttonISR, CHANGE);
|
||||||
|
|
||||||
|
sonde.clearSonde();
|
||||||
|
sonde.addSonde(402.300, STYPE_RS41);
|
||||||
|
sonde.addSonde(402.700, STYPE_RS41);
|
||||||
|
sonde.addSonde(403.450, STYPE_DFM09);
|
||||||
|
/// not here, done by sonde.setup(): rs41.setup();
|
||||||
|
sonde.setup();
|
||||||
}
|
}
|
||||||
|
|
||||||
enum MainState { ST_DECODER, ST_SCANNER, ST_SPECTRUM, ST_WIFISCAN };
|
enum MainState { ST_DECODER, ST_SCANNER, ST_SPECTRUM, ST_WIFISCAN };
|
||||||
|
|
||||||
static MainState mainState = ST_SPECTRUM;
|
static MainState mainState = ST_DECODER;
|
||||||
|
|
||||||
void loopDecoder() {
|
void enterMode(int mode) {
|
||||||
|
mainState = (MainState)mode;
|
||||||
|
sonde.clearDisplay();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void loopDecoder() {
|
||||||
|
switch(getKeyPress()) {
|
||||||
|
case KP_SHORT:
|
||||||
|
sonde.nextConfig();
|
||||||
|
break;
|
||||||
|
case KP_DOUBLE:
|
||||||
|
enterMode(ST_SCANNER);
|
||||||
|
return;
|
||||||
|
case KP_MID:
|
||||||
|
enterMode(ST_SPECTRUM);
|
||||||
|
return;
|
||||||
|
case KP_LONG:
|
||||||
|
enterMode(ST_WIFISCAN);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
// sonde knows the current type and frequency, and delegates to the right decoder
|
||||||
|
sonde.receiveFrame();
|
||||||
|
sonde.updateDisplay();
|
||||||
|
}
|
||||||
|
|
||||||
|
#define SCAN_MAXTRIES 1
|
||||||
void loopScanner() {
|
void loopScanner() {
|
||||||
|
sonde.updateDisplayScanner();
|
||||||
|
static int tries=0;
|
||||||
|
switch(getKeyPress()) {
|
||||||
|
case KP_SHORT:
|
||||||
|
enterMode(ST_DECODER);
|
||||||
|
return;
|
||||||
|
case KP_DOUBLE: break; /* ignored */
|
||||||
|
case KP_MID:
|
||||||
|
enterMode(ST_SPECTRUM);
|
||||||
|
return;
|
||||||
|
case KP_LONG:
|
||||||
|
enterMode(ST_WIFISCAN);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
// receiveFrame returns 0 on success, 1 on timeout
|
||||||
|
int res = sonde.receiveFrame(); // Maybe instead of receiveFrame, just detect if right type is present? TODO
|
||||||
|
Serial.print("Scanner: receiveFrame returned");
|
||||||
|
Serial.println(res);
|
||||||
|
if(res==0) {
|
||||||
|
enterMode(ST_DECODER);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if(++tries>=SCAN_MAXTRIES) {
|
||||||
|
sonde.nextConfig();
|
||||||
|
tries = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void loopSpectrum() {
|
void loopSpectrum() {
|
||||||
switch(getKeyPress()) {
|
switch(getKeyPress()) {
|
||||||
case KP_SHORT: /* move selection of peak, TODO */ break;
|
case KP_SHORT: /* move selection of peak, TODO */
|
||||||
|
sonde.nextConfig(); // TODO: Should be set specific frequency
|
||||||
|
enterMode(ST_DECODER);
|
||||||
|
return;
|
||||||
case KP_MID: /* restart, TODO */ break;
|
case KP_MID: /* restart, TODO */ break;
|
||||||
case KP_LONG: mainState = ST_WIFISCAN; return;
|
case KP_LONG:
|
||||||
|
enterMode(ST_WIFISCAN);
|
||||||
|
return;
|
||||||
case KP_DOUBLE: /* ignore */ break;
|
case KP_DOUBLE: /* ignore */ break;
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
|
|
@ -322,13 +307,21 @@ String translateEncryptionType(wifi_auth_mode_t encryptionType) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static char* _scan[2]={"/","\\"};
|
||||||
void loopWifiScan() {
|
void loopWifiScan() {
|
||||||
|
u8x8.setFont(u8x8_font_chroma48medium8_r);
|
||||||
|
u8x8.drawString(0,0,"WiFi Scan...");
|
||||||
|
int line=0;
|
||||||
|
int cnt=0;
|
||||||
|
|
||||||
WiFi.mode(WIFI_STA);
|
WiFi.mode(WIFI_STA);
|
||||||
const char *id, *pw;
|
const char *id, *pw;
|
||||||
int n = WiFi.scanNetworks();
|
int n = WiFi.scanNetworks();
|
||||||
for (int i = 0; i < n; i++) {
|
for (int i = 0; i < n; i++) {
|
||||||
Serial.print("Network name: ");
|
Serial.print("Network name: ");
|
||||||
Serial.println(WiFi.SSID(i));
|
Serial.println(WiFi.SSID(i));
|
||||||
|
u8x8.drawString(0,1+line,WiFi.SSID(i).c_str());
|
||||||
|
line = (line+1)%5;
|
||||||
Serial.print("Signal strength: ");
|
Serial.print("Signal strength: ");
|
||||||
Serial.println(WiFi.RSSI(i));
|
Serial.println(WiFi.RSSI(i));
|
||||||
Serial.print("MAC address: ");
|
Serial.print("MAC address: ");
|
||||||
|
|
@ -343,17 +336,22 @@ void loopWifiScan() {
|
||||||
}
|
}
|
||||||
if(!pw) { id="test"; pw="test"; }
|
if(!pw) { id="test"; pw="test"; }
|
||||||
Serial.print("Connecting to: "); Serial.println(id);
|
Serial.print("Connecting to: "); Serial.println(id);
|
||||||
|
u8x8.drawString(0,6, "Conn:");
|
||||||
|
u8x8.drawString(6,6, id);
|
||||||
WiFi.begin(id, pw);
|
WiFi.begin(id, pw);
|
||||||
while(WiFi.status() != WL_CONNECTED) {
|
while(WiFi.status() != WL_CONNECTED) {
|
||||||
delay(500);
|
delay(500);
|
||||||
Serial.print(".");
|
Serial.print(".");
|
||||||
|
u8x8.drawString(15,7,_scan[cnt&1]);
|
||||||
|
cnt++;
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.println("");
|
Serial.println("");
|
||||||
Serial.println("WiFi connected");
|
Serial.println("WiFi connected");
|
||||||
Serial.println("IP address: ");
|
Serial.println("IP address: ");
|
||||||
Serial.println(WiFi.localIP());
|
Serial.println(WiFi.localIP());
|
||||||
|
sonde.setIP(WiFi.localIP().toString().c_str());
|
||||||
|
sonde.updateDisplayIP();
|
||||||
SetupAsyncServer();
|
SetupAsyncServer();
|
||||||
delay(5000);
|
delay(5000);
|
||||||
mainState=ST_SPECTRUM;
|
mainState=ST_SPECTRUM;
|
||||||
|
|
@ -369,17 +367,9 @@ void loop() {
|
||||||
case ST_WIFISCAN: loopWifiScan(); break;
|
case ST_WIFISCAN: loopWifiScan(); break;
|
||||||
}
|
}
|
||||||
#if 0
|
#if 0
|
||||||
if (button1.pressed) {
|
|
||||||
Serial.print( ((const char *[]){"SHORT PRESS -","LONG PRESS -","VERYLONG PRESS -"})[button1.pressed-1]);
|
|
||||||
Serial.printf("Button 1 has been pressed %u times\n", button1.numberKeyPresses);
|
|
||||||
button1.pressed = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
//wifiloop(NULL);
|
//wifiloop(NULL);
|
||||||
//e = dfm.receiveFrame();
|
//e = dfm.receiveFrame();
|
||||||
//e = rs41.receiveFrame();
|
//e = rs41.receiveFrame();
|
||||||
scanner.scan();
|
|
||||||
scanner.plotResult();
|
|
||||||
delay(1000);
|
delay(1000);
|
||||||
int rssi = sx1278.getRSSI();
|
int rssi = sx1278.getRSSI();
|
||||||
Serial.print(" RSSI: ");
|
Serial.print(" RSSI: ");
|
||||||
|
|
|
||||||
|
|
@ -8,9 +8,27 @@
|
||||||
</head>
|
</head>
|
||||||
<body>
|
<body>
|
||||||
<h1>ESP32 Web Server</h1>
|
<h1>ESP32 Web Server</h1>
|
||||||
|
<!--
|
||||||
<p>GPIO state: <strong> %STATE%</strong></p>
|
<p>GPIO state: <strong> %STATE%</strong></p>
|
||||||
<p><a href="/on"><button class="button">ON</button></a></p>
|
<p><a href="/on"><button class="button">ON</button></a></p>
|
||||||
<p><a href="/off"><button class="button button2">OFF</button></a></p>
|
<p><a href="/off"><button class="button button2">OFF</button></a></p>
|
||||||
|
-->
|
||||||
|
<table class="KKK">
|
||||||
|
<tr>
|
||||||
|
<th></th>
|
||||||
|
<th style="width:100px">ID</th>
|
||||||
|
<th style="width:100px">PW</th>
|
||||||
|
</tr>
|
||||||
|
<tr>
|
||||||
|
<td>1</td>
|
||||||
|
<td contenteditable>DinoGast</td>
|
||||||
|
<td contenteditable>Schokolade</td>
|
||||||
|
<tr>
|
||||||
|
<td>2</td>
|
||||||
|
<td contenteditable></td>
|
||||||
|
<td contenteditable></td>
|
||||||
|
</tr>
|
||||||
|
|
||||||
</body>
|
</body>
|
||||||
</html>
|
</html>
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -649,6 +649,9 @@ uint8_t SX1278FSK::receive()
|
||||||
return state;
|
return state;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// ugly. shouldn't be here in a nice software design
|
||||||
|
extern int hasKeyPress();
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Function: Configures the module to receive a packet
|
Function: Configures the module to receive a packet
|
||||||
Returns: Integer that determines if there has been any error
|
Returns: Integer that determines if there has been any error
|
||||||
|
|
@ -683,7 +686,7 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
|
||||||
value = readRegister(REG_IRQ_FLAGS2);
|
value = readRegister(REG_IRQ_FLAGS2);
|
||||||
byte ready=0;
|
byte ready=0;
|
||||||
// while not yet done or FIFO not yet empty
|
// while not yet done or FIFO not yet empty
|
||||||
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) )
|
while( (!ready || bitRead(value,6)==0) && (millis() - previous < wait) &&(!hasKeyPress()) )
|
||||||
{
|
{
|
||||||
if( bitRead(value,2)==1 ) ready=1;
|
if( bitRead(value,2)==1 ) ready=1;
|
||||||
if( bitRead(value, 6) == 0 ) { // FIFO not empty
|
if( bitRead(value, 6) == 0 ) { // FIFO not empty
|
||||||
|
|
@ -691,7 +694,7 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
|
||||||
if(di==1) {
|
if(di==1) {
|
||||||
int rssi=getRSSI();
|
int rssi=getRSSI();
|
||||||
Serial.print("Test: RSSI="); Serial.println(rssi);
|
Serial.print("Test: RSSI="); Serial.println(rssi);
|
||||||
si.rssi = rssi;
|
sonde.si()->rssi = rssi;
|
||||||
}
|
}
|
||||||
if(di>520) {
|
if(di>520) {
|
||||||
// TODO
|
// TODO
|
||||||
|
|
@ -707,7 +710,7 @@ uint8_t SX1278FSK::receivePacketTimeout(uint32_t wait, byte *data)
|
||||||
Serial.println(F("** The timeout has expired **"));
|
Serial.println(F("** The timeout has expired **"));
|
||||||
Serial.println();
|
Serial.println();
|
||||||
#endif
|
#endif
|
||||||
si.rssi = getRSSI();
|
sonde.si()->rssi = getRSSI();
|
||||||
writeRegister(REG_OP_MODE, FSK_STANDBY_MODE); // Setting standby FSK mode
|
writeRegister(REG_OP_MODE, FSK_STANDBY_MODE); // Setting standby FSK mode
|
||||||
return 1; // TIMEOUT
|
return 1; // TIMEOUT
|
||||||
}
|
}
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue