Bläddra i källkod

use romfs to serve files compressed

Andrew Tridgell 3 år sedan
förälder
incheckning
09e23c930f

+ 23 - 4
RemoteIDModule/DroneCAN.cpp

@@ -572,20 +572,29 @@ void DroneCAN::handle_param_getset(CanardInstance* ins, CanardRxTransfer* transf
             if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
                 return;
             }
-            vp->set(uint8_t(req.value.integer_value));
+            vp->set_uint8(uint8_t(req.value.integer_value));
+            break;
+        case Parameters::ParamType::UINT32:
+            if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) {
+                return;
+            }
+            vp->set_uint32(uint32_t(req.value.integer_value));
             break;
         case Parameters::ParamType::FLOAT:
             if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) {
                 return;
             }
-            vp->set(req.value.real_value);
+            vp->set_float(req.value.real_value);
             break;
-        case Parameters::ParamType::CHAR20:
+        case Parameters::ParamType::CHAR20: {
             if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) {
                 return;
             }
-            vp->set((const char *)&req.value.string_value.data[0]);
+            char v[21] {};
+            strncpy(v, (const char *)&req.value.string_value.data[0], req.value.string_value.len);
+            vp->set_char20(v);
             break;
+        }
         default:
             return;
         }
@@ -602,6 +611,16 @@ void DroneCAN::handle_param_getset(CanardInstance* ins, CanardRxTransfer* transf
             pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
             pkt.max_value.integer_value = uint8_t(vp->max_value);
             break;
+        case Parameters::ParamType::UINT32:
+            pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
+            pkt.value.integer_value = vp->get_uint32();
+            pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE;
+            pkt.default_value.integer_value = uint32_t(vp->default_value);
+            pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
+            pkt.min_value.integer_value = uint32_t(vp->min_value);
+            pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE;
+            pkt.max_value.integer_value = uint32_t(vp->max_value);
+            break;
         case Parameters::ParamType::FLOAT:
             pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE;
             pkt.value.real_value = vp->get_float();

+ 6 - 2
RemoteIDModule/Makefile

@@ -38,8 +38,8 @@ headers:
 	@../scripts/git-version.sh
 	@cd .. && scripts/regen_headers.sh
 
-romfs_files.h: web/*.html
-	@../scripts/make_romfs.py romfs_files.h web/*.html
+romfs_files.h: web/*.html web/js/*.js
+	@../scripts/make_romfs.py romfs_files.h web/*.html web/js/*.js
 
 ArduRemoteID-%.bin: *.cpp *.ino *.h romfs_files.h
 	@echo "Building $* on $(CHIP)"
@@ -62,6 +62,10 @@ upload-%: checkdev
 	@echo "Flashing ArduRemoteID-$*.bin"
 	$(ESPTOOL) --port $(SERDEV) write_flash 0x0 ArduRemoteID-$*.bin
 
+uploadota-%: checkdev
+	@echo "Flashing ArduRemoteID-$*_OTA.bin"
+	$(ESPTOOL) --port $(SERDEV) write_flash 0x10000 ArduRemoteID_$*_OTA.bin
+
 upload: upload-ESP32S3_DEV
 
 clean:

+ 7 - 7
RemoteIDModule/RemoteIDModule.ino

@@ -33,7 +33,6 @@ static WiFi_NAN wifi;
 static BLE_TX ble;
 
 #define DEBUG_BAUDRATE 57600
-#define MAVLINK_BAUDRATE 57600
 
 // OpenDroneID output data structure
 static ODID_UAS_Data UAS_data;
@@ -54,10 +53,10 @@ void setup()
     g.init();
 
     // Serial for debug printf
-    Serial.begin(DEBUG_BAUDRATE);
+    Serial.begin(g.baudrate);
 
     // Serial1 for MAVLink
-    Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
+    Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX);
 
     // set all fields to invalid/initial values
     odid_initUasData(&UAS_data);
@@ -234,6 +233,10 @@ void loop()
 
     const uint32_t now_ms = millis();
 
+    if (g.webserver_enable) {
+        webif.update();
+    }
+
     // the transports have common static data, so we can just use the
     // first for status
 #if AP_MAVLINK_ENABLED
@@ -258,6 +261,7 @@ void loop()
     } else {
         // only broadcast if we have received a location at least once
         if (last_location_ms == 0) {
+            delay(1);
             return;
         }
     }
@@ -300,10 +304,6 @@ void loop()
         ble.transmit_legacy_name(UAS_data);
     }
 
-    if (g.webserver_enable) {
-        webif.update();
-    }
-
     // sleep for a bit for power saving
     delay(1);
 }

+ 36 - 5
RemoteIDModule/parameters.cpp

@@ -11,7 +11,8 @@ const Parameters::Param Parameters::params[] = {
     { "LOCK_LEVEL",        Parameters::ParamType::UINT8,  (const void*)&g.lock_level,       0, 0, 2 },
     { "CAN_NODE",          Parameters::ParamType::UINT8,  (const void*)&g.can_node,         0, 0, 127 },
     { "UAS_ID",            Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0],        0, 0, 0 },
-    { "WIFI_NAN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_nan_rate,    1, 0, 5 },
+    { "BAUDRATE",          Parameters::ParamType::UINT32, (const void*)&g.baudrate,         57600, 9600, 921600 },
+    { "WIFI_NAN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_nan_rate,    0, 0, 5 },
     { "BT4_RATE",          Parameters::ParamType::FLOAT,  (const void*)&g.bt4_rate,         1, 0, 5 },
     { "BT5_RATE",          Parameters::ParamType::FLOAT,  (const void*)&g.bt5_rate,         1, 0, 5 },
     { "WEBSERVER_ENABLE",  Parameters::ParamType::UINT8,  (const void*)&g.webserver_enable, 1, 0, 1 },
@@ -45,14 +46,21 @@ const Parameters::Param *Parameters::find_by_index(uint16_t index)
     return &params[index];
 }
 
-void Parameters::Param::set(uint8_t v) const
+void Parameters::Param::set_uint8(uint8_t v) const
 {
     auto *p = (uint8_t *)ptr;
     *p = v;
     nvs_set_u8(handle, name, *p);
 }
 
-void Parameters::Param::set(float v) const
+void Parameters::Param::set_uint32(uint32_t v) const
+{
+    auto *p = (uint32_t *)ptr;
+    *p = v;
+    nvs_set_u32(handle, name, *p);
+}
+
+void Parameters::Param::set_float(float v) const
 {
     auto *p = (float *)ptr;
     *p = v;
@@ -64,9 +72,11 @@ void Parameters::Param::set(float v) const
     nvs_set_u32(handle, name, u.u32);
 }
 
-void Parameters::Param::set(const char *v) const
+void Parameters::Param::set_char20(const char *v) const
 {
-    strncpy((char *)ptr, v, PARAM_NAME_MAX_LEN);
+    memset((void*)ptr, 0, 21);
+    strncpy((char *)ptr, v, 20);
+    Serial.printf("Set %s -> '%s'\n", name, (const char *)ptr);
     nvs_set_str(handle, name, v);
 }
 
@@ -76,6 +86,12 @@ uint8_t Parameters::Param::get_uint8() const
     return *p;
 }
 
+uint32_t Parameters::Param::get_uint32() const
+{
+    const auto *p = (const uint32_t *)ptr;
+    return *p;
+}
+
 float Parameters::Param::get_float() const
 {
     const auto *p = (const float *)ptr;
@@ -85,6 +101,7 @@ float Parameters::Param::get_float() const
 const char *Parameters::Param::get_char20() const
 {
     const char *p = (const char *)ptr;
+    Serial.printf("Get %s -> '%s'\n", name, p);
     return p;
 }
 
@@ -99,6 +116,9 @@ void Parameters::load_defaults(void)
         case ParamType::UINT8:
             *(uint8_t *)p.ptr = uint8_t(p.default_value);
             break;
+        case ParamType::UINT32:
+            *(uint32_t *)p.ptr = uint32_t(p.default_value);
+            break;
         case ParamType::FLOAT:
             *(float *)p.ptr = p.default_value;
             break;
@@ -120,6 +140,9 @@ void Parameters::init(void)
         case ParamType::UINT8:
             nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
             break;
+        case ParamType::UINT32:
+            nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
+            break;
         case ParamType::FLOAT:
             nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
             break;
@@ -130,4 +153,12 @@ void Parameters::init(void)
         }
         }
     }
+
+    if (strlen(g.wifi_ssid) == 0) {
+        uint8_t mac[6] {};
+        esp_read_mac(mac, ESP_MAC_WIFI_STA);
+        snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x",
+                 mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
+
+    }
 }

+ 11 - 7
RemoteIDModule/parameters.h

@@ -11,13 +11,14 @@ public:
     uint8_t lock_level;
     uint8_t can_node;
     uint8_t bcast_powerup;
+    uint32_t baudrate = 57600;
     char uas_id[21] = "ABCD123456789";
     float wifi_nan_rate;
     float bt4_rate;
     float bt5_rate;
     uint8_t webserver_enable;
-    char wifi_ssid[21] = "RemoteID_XXXXXXXX";
-    char wifi_password[21] = "SecretPassword";
+    char wifi_ssid[21] = "RID_123456";
+    char wifi_password[21] = "penguin1234";
 
     /*
       header at the front of storage
@@ -32,8 +33,9 @@ public:
     enum class ParamType {
         NONE=0,
         UINT8=1,
-        FLOAT=2,
-        CHAR20=3,
+        UINT32=2,
+        FLOAT=3,
+        CHAR20=4,
     };
 
     struct Param {
@@ -43,10 +45,12 @@ public:
         float default_value;
         float min_value;
         float max_value;
-        void set(float v) const;
-        void set(uint8_t v) const;
-        void set(const char *v) const;
+        void set_float(float v) const;
+        void set_uint8(uint8_t v) const;
+        void set_uint32(uint32_t v) const;
+        void set_char20(const char *v) const;
         uint8_t get_uint8() const;
+        uint32_t get_uint32() const;
         float get_float() const;
         const char *get_char20() const;
     };

+ 62 - 2
RemoteIDModule/romfs.cpp

@@ -1,13 +1,73 @@
+#include <Arduino.h>
 #include "romfs.h"
 #include "romfs_files.h"
 #include <string.h>
 
-const char *ROMFS::find_string(const char *fname)
+const ROMFS::embedded_file *ROMFS::find(const char *fname)
 {
     for (const auto &f : files) {
         if (strcmp(fname, f.filename) == 0) {
-            return (const char *)f.contents;
+            Serial.printf("ROMFS Returning '%s' size=%u len=%u\n",
+                          fname, f.size, strlen((const char *)f.contents));
+            return &f;
         }
     }
+    Serial.printf("ROMFS not found '%s'\n", fname);
     return nullptr;
 }
+
+bool ROMFS::exists(const char *fname)
+{
+    return find(fname) != nullptr;
+}
+
+ROMFS_Stream *ROMFS::find_stream(const char *fname)
+{
+    const auto *f = find(fname);
+    if (!f) {
+        return nullptr;
+    }
+    return new ROMFS_Stream(*f);
+}
+
+size_t ROMFS_Stream::size(void) const
+{
+    return f.size;
+}
+
+const char *ROMFS_Stream::name(void) const
+{
+    return f.filename;
+}
+
+int ROMFS_Stream::available(void)
+{
+    return f.size - offset;
+}
+
+size_t ROMFS_Stream::read(uint8_t* buf, size_t size)
+{
+    const auto avail = available();
+    if (size > avail) {
+        size = avail;
+    }
+    memcpy(buf, &f.contents[offset], size);
+    offset += size;
+    return size;
+}
+
+int ROMFS_Stream::peek(void)
+{
+    if (offset >= f.size) {
+        return -1;
+    }
+    return f.contents[offset];
+}
+
+int ROMFS_Stream::read(void)
+{
+    if (offset >= f.size) {
+        return -1;
+    }
+    return f.contents[offset++];
+}

+ 33 - 2
RemoteIDModule/romfs.h

@@ -2,15 +2,46 @@
 
 #include <stdint.h>
 
+class ROMFS_Stream;
+
 class ROMFS {
 public:
-    static const char *find_string(const char *fname);
-private:
+    static bool exists(const char *fname);
+    static ROMFS_Stream *find_stream(const char *fname);
 
     struct embedded_file {
         const char *filename;
         uint32_t size;
         const uint8_t *contents;
     };
+
+private:
+    static const struct embedded_file *find(const char *fname);
     static const struct embedded_file files[];
 };
+
+class ROMFS_Stream : public Stream
+{
+public:
+    ROMFS_Stream(const ROMFS::embedded_file &_f) :
+        f(_f) {}
+
+    size_t write(const uint8_t *buffer, size_t size) override { return 0; }
+    size_t write(uint8_t data) override { return 0; }
+    size_t size(void) const;
+    const char *name(void) const;
+
+    int available() override;
+    int read() override;
+    int peek() override;
+    void flush() override {}
+    size_t readBytes(char *buffer, size_t length) override {
+        return read((uint8_t*)buffer, length);
+    }
+
+private:
+    size_t read(uint8_t* buf, size_t size);
+    const ROMFS::embedded_file &f;
+    uint32_t offset = 0;
+};
+

+ 1 - 1
RemoteIDModule/web/login.html → RemoteIDModule/web/index.html

@@ -28,7 +28,7 @@
 <script>
   function check(form) {
       if(form.userid.value=='admin' && form.pwd.value=='admin') {
-          window.open('/serverIndex')
+          window.open('/uploader.html')
       } else {
           alert('Error Password or Username')/*displays error message*/
       }

+ 1 - 1
RemoteIDModule/web/uploader.html

@@ -1,4 +1,4 @@
-<script src='https://ajax.googleapis.com/ajax/libs/jquery/3.2.1/jquery.min.js'></script>
+<script src='js/jquery.min.js'></script>
 <form method='POST' action='#' enctype='multipart/form-data' id='upload_form'>
   <input type='file' name='update'>
   <input type='submit' value='Update'>

+ 85 - 37
RemoteIDModule/webinterface.cpp

@@ -11,49 +11,97 @@
 
 static WebServer server(80);
 
+/*
+  serve files from ROMFS
+ */
+class ROMFS_Handler : public RequestHandler
+{
+    bool canHandle(HTTPMethod method, String uri) {
+        if (uri == "/") {
+            uri = "/index.html";
+        }
+        Serial.printf("canHandle: %s\n", uri.c_str());
+        uri = "web" + uri;
+        if (ROMFS::exists(uri.c_str())) {
+            return true;
+        }
+        return false;
+    }
+
+    bool handle(WebServer& server, HTTPMethod requestMethod, String requestUri) {
+        if (requestUri == "/") {
+            requestUri = "/index.html";
+        }
+        String uri = "web" + requestUri;
+        Serial.printf("handle: '%s'\n", requestUri.c_str());
+        const char *content_type = "text/html";
+        if (uri.endsWith(".js")) {
+            content_type = "text/javascript";
+        }
+        auto *f = ROMFS::find_stream(uri.c_str());
+        if (f != nullptr) {
+            server.sendHeader("Content-Encoding", "gzip");
+            server.streamFile(*f, content_type);
+            delete f;
+            return true;
+        }
+        return false;
+    }
+
+} ROMFS_Handler;
+
 /*
   init web server
  */
 void WebInterface::init(void)
 {
-  WiFi.softAP(g.wifi_ssid, g.wifi_password);
-  IPAddress myIP = WiFi.softAPIP();
+    Serial.printf("WAP start %s %s\n", g.wifi_ssid, g.wifi_password);
+    WiFi.softAP(g.wifi_ssid, g.wifi_password);
+    IPAddress myIP = WiFi.softAPIP();
 
-  /*return index page which is stored in serverIndex */
-  server.on("/", HTTP_GET, []() {
-    server.sendHeader("Connection", "close");
-    server.send(200, "text/html", ROMFS::find_string("web/login.html"));
-  });
-  server.on("/serverIndex", HTTP_GET, []() {
-    server.sendHeader("Connection", "close");
-    server.send(200, "text/html", ROMFS::find_string("web/uploader.html"));
-  });
-  /*handling uploading firmware file */
-  server.on("/update", HTTP_POST, []() {
-    server.sendHeader("Connection", "close");
-    server.send(200, "text/plain", (Update.hasError()) ? "FAIL" : "OK");
-    ESP.restart();
-  }, []() {
-    HTTPUpload& upload = server.upload();
-    if (upload.status == UPLOAD_FILE_START) {
-      Serial.printf("Update: %s\n", upload.filename.c_str());
-      if (!Update.begin(UPDATE_SIZE_UNKNOWN)) { //start with max available size
-        Update.printError(Serial);
-      }
-    } else if (upload.status == UPLOAD_FILE_WRITE) {
-      /* flashing firmware to ESP*/
-      if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
-        Update.printError(Serial);
-      }
-    } else if (upload.status == UPLOAD_FILE_END) {
-      if (Update.end(true)) { //true to set the size to the current progress
-        Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
-      } else {
-        Update.printError(Serial);
-      }
-    }
-  });
-  server.begin();
+    server.addHandler( &ROMFS_Handler );
+#if 0
+    /*return index page which is stored in serverIndex */
+    server.on("/", HTTP_GET, []() {
+        server.sendHeader("Connection", "close");
+        server.send(200, "text/html", ROMFS::find_string("web/login.html"));
+    });
+    server.on("/serverIndex", HTTP_GET, []() {
+        server.sendHeader("Connection", "close");
+        server.send(200, "text/html", ROMFS::find_string("web/uploader.html"));
+    });
+    server.on("/js/jquery.min.js", HTTP_GET, []() {
+        server.sendHeader("Connection", "close");
+        server.send(200, "text/html", ROMFS::find_string("web/js/jquery.min.js"));
+    });
+#endif
+    /*handling uploading firmware file */
+    server.on("/update", HTTP_POST, []() {
+        server.sendHeader("Connection", "close");
+        server.send(200, "text/plain", (Update.hasError()) ? "FAIL" : "OK");
+        ESP.restart();
+    }, []() {
+        HTTPUpload& upload = server.upload();
+        if (upload.status == UPLOAD_FILE_START) {
+            Serial.printf("Update: %s\n", upload.filename.c_str());
+            if (!Update.begin(UPDATE_SIZE_UNKNOWN)) { //start with max available size
+                Update.printError(Serial);
+            }
+        } else if (upload.status == UPLOAD_FILE_WRITE) {
+            /* flashing firmware to ESP*/
+            if (Update.write(upload.buf, upload.currentSize) != upload.currentSize) {
+                Update.printError(Serial);
+            }
+        } else if (upload.status == UPLOAD_FILE_END) {
+            if (Update.end(true)) { //true to set the size to the current progress
+                Serial.printf("Update Success: %u\nRebooting...\n", upload.totalSize);
+            } else {
+                Update.printError(Serial);
+            }
+        }
+    });
+    Serial.printf("WAP started\n");
+    server.begin();
 }
 
 void WebInterface::update()

+ 2 - 19
scripts/make_romfs.py

@@ -19,28 +19,11 @@ def embed_file(out, f, idx, embedded_name):
     except Exception:
         raise Exception("Failed to embed %s" % f)
 
-    pad = 0
-    if embedded_name.endswith("bootloader.bin"):
-        # round size to a multiple of 32 bytes for bootloader, this ensures
-        # it can be flashed on a STM32H7 chip
-        blen = len(contents)
-        pad = (32 - (blen % 32)) % 32
-        if pad != 0:
-            if sys.version_info[0] >= 3:
-                contents += bytes([0xff]*pad)
-            else:
-                for i in range(pad):
-                    contents += bytes(chr(0xff))
-            print("Padded %u bytes for %s to %u" % (pad, embedded_name, len(contents)))
-
     write_encode(out, 'static const uint8_t romfs_%u[] = {' % idx)
 
     outf = tempfile.NamedTemporaryFile()
-    # ensure nul termination
-    nul = bytearray([0])
-    if contents[-1] != nul:
-        contents += nul
-    outf.write(contents)
+    with gzip.GzipFile(fileobj=outf, mode='wb', filename='', compresslevel=9, mtime=0) as g:
+        g.write(contents)
 
     outf.seek(0)
     b = bytearray(outf.read())