Selaa lähdekoodia

added web interface and nvs parameter save

Andrew Tridgell 3 vuotta sitten
vanhempi
sitoutus
aaa37c3792

+ 8 - 0
RemoteIDModule/BLE_TX.cpp

@@ -68,6 +68,10 @@ static BLEMultiAdvertising advert(3);
 
 bool BLE_TX::init(void)
 {
+    if (initialised) {
+        return true;
+    }
+    initialised = true;
     BLEDevice::init("");
 
     // generate random mac address
@@ -102,6 +106,8 @@ bool BLE_TX::init(void)
 
 bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data)
 {
+    init();
+
     //set BLE name
     uint8_t legacy_name_payload[36];
     char legacy_name[28] {};
@@ -125,6 +131,7 @@ bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data)
 
 bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 {
+    init();
     // create a packed UAS data message
     uint8_t payload[250];
     int length = odid_message_build_pack(&UAS_data, payload, 255);
@@ -153,6 +160,7 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data)
 
 bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data)
 {
+    init();
     static uint8_t legacy_phase = 0;
     int legacy_length = 0;
     // setup ASTM header

+ 1 - 0
RemoteIDModule/BLE_TX.h

@@ -13,6 +13,7 @@ public:
     bool transmit_legacy(ODID_UAS_Data &UAS_data);
 
 private:
+    bool initialised;
     uint8_t msg_counters[ODID_MSG_COUNTER_AMOUNT];
     uint8_t legacy_payload[36];
     uint8_t longrange_payload[250];

+ 9 - 7
RemoteIDModule/DroneCAN.cpp

@@ -22,11 +22,13 @@
 #include <dronecan.remoteid.OperatorID.h>
 #include <dronecan.remoteid.ArmStatus.h>
 
-#define BOARD_ID 10001
+#ifndef CAN_BOARD_ID
+#define CAN_BOARD_ID 10001
+#endif
+
 #ifndef CAN_APP_NODE_NAME
 #define CAN_APP_NODE_NAME "ArduPilot RemoteIDModule"
 #endif
-#define CAN_DEFAULT_NODE_ID 0 // use DNA
 
 #define UNUSED(x) (void)(x)
 
@@ -44,9 +46,9 @@ void DroneCAN::init(void)
 
     canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool),
                onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, NULL);
-#if CAN_DEFAULT_NODE_ID
-    canardSetLocalNodeID(&canard, CAN_DEFAULT_NODE_ID);
-#endif
+    if (g.can_node > 0 && g.can_node < 128) {
+        canardSetLocalNodeID(&canard, g.can_node);
+    }
     canard.user_reference = (void*)this;
 }
 
@@ -341,8 +343,8 @@ void DroneCAN::handle_get_node_info(CanardInstance* ins, CanardRxTransfer* trans
 
     readUniqueID(pkt.hardware_version.unique_id);
 
-    pkt.hardware_version.major = BOARD_ID >> 8;
-    pkt.hardware_version.minor = BOARD_ID & 0xFF;
+    pkt.hardware_version.major = CAN_BOARD_ID >> 8;
+    pkt.hardware_version.minor = CAN_BOARD_ID & 0xFF;
     snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME);
     pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data));
 

+ 6 - 2
RemoteIDModule/Makefile

@@ -38,11 +38,15 @@ headers:
 	@../scripts/git-version.sh
 	@cd .. && scripts/regen_headers.sh
 
-ArduRemoteID-%.bin: *.cpp *.ino *.h
+romfs_files.h: web/*.html
+	@../scripts/make_romfs.py romfs_files.h web/*.html
+
+ArduRemoteID-%.bin: *.cpp *.ino *.h romfs_files.h
 	@echo "Building $* on $(CHIP)"
 	@BUILD_FLAGS="-DBOARD_$*"
 	@rm -rf build build-$*
-	@$(ARDUINO_CLI) compile -b esp32:esp32:$(CHIP) --export-binaries --build-property build.extra_flags=-DBOARD_$* --build-property upload.maximum_size=$(APP_PARTITION_SIZE)  .
+	@$(ARDUINO_CLI) compile -b esp32:esp32:$(CHIP) --export-binaries --build-property build.extra_flags=-DBOARD_$* --build-property upload.maximum_size=$(APP_PARTITION_SIZE)
+	@cp build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bin ArduRemoteID_$*_OTA.bin
 	@echo "Merging $*"
 	@python3 $(ESPTOOL) --chip $(CHIP) merge_bin -o ArduRemoteID-$*.bin --flash_size 4MB 0x0 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bootloader.bin 0x8000 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.partitions.bin 0xe000 $(ESP32_TOOLS)/partitions/boot_app0.bin 0x10000 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bin
 	@mv build build-$*

+ 48 - 49
RemoteIDModule/RemoteIDModule.ino

@@ -17,6 +17,8 @@
 #include "WiFi_TX.h"
 #include "BLE_TX.h"
 #include "parameters.h"
+#include "webinterface.h"
+#include <esp_ota_ops.h>
 
 #if AP_DRONECAN_ENABLED
 static DroneCAN dronecan;
@@ -27,13 +29,8 @@ static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0};
 static MAVLinkSerial mavlink2{Serial,  MAVLINK_COMM_1};
 #endif
 
-#if AP_WIFI_NAN_ENABLED
 static WiFi_NAN wifi;
-#endif
-
-#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
 static BLE_TX ble;
-#endif
 
 #define DEBUG_BAUDRATE 57600
 #define MAVLINK_BAUDRATE 57600
@@ -41,13 +38,20 @@ static BLE_TX ble;
 // OpenDroneID output data structure
 static ODID_UAS_Data UAS_data;
 static uint32_t last_location_ms;
+static WebInterface webif;
+
+#include "soc/soc.h"
+#include "soc/rtc_cntl_reg.h"
 
 /*
   setup serial ports
  */
 void setup()
 {
-    g.load_defaults();
+    // disable brownout checking
+    WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0);
+
+    g.init();
 
     // Serial for debug printf
     Serial.begin(DEBUG_BAUDRATE);
@@ -65,12 +69,6 @@ void setup()
 #if AP_DRONECAN_ENABLED
     dronecan.init();
 #endif
-#if AP_WIFI_NAN_ENABLED
-    wifi.init();
-#endif
-#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
-    ble.init();
-#endif
 
 #if defined(PIN_CAN_EN)
     // optional CAN enable pin
@@ -89,6 +87,10 @@ void setup()
     pinMode(PIN_CAN_TERM, OUTPUT);
     digitalWrite(PIN_CAN_TERM, HIGH);
 #endif
+
+    esp_log_level_set("*", ESP_LOG_DEBUG);
+
+    esp_ota_mark_app_valid_cancel_rollback();
 }
 
 #define IMIN(x,y) ((x)<(y)?(x):(y))
@@ -222,8 +224,6 @@ static uint8_t loop_counter = 0;
 
 void loop()
 {
-    static uint32_t last_update;
-
 #if AP_MAVLINK_ENABLED
     mavlink1.update();
     mavlink2.update();
@@ -234,16 +234,6 @@ void loop()
 
     const uint32_t now_ms = millis();
 
-    // we call BT4 send at 5x the desired rate as it has to split the pkts 5 ways
-    const uint32_t rate_divider = 5;
-
-    if (now_ms - last_update < 1000UL/(OUTPUT_RATE_HZ*rate_divider)) {
-        // not ready for a new frame yet
-        return;
-    }
-    loop_counter++;
-    loop_counter %= rate_divider;
-
     // the transports have common static data, so we can just use the
     // first for status
 #if AP_MAVLINK_ENABLED
@@ -258,19 +248,19 @@ void loop()
     const uint32_t last_location_ms = transport.get_last_location_ms();
     const uint32_t last_system_ms = transport.get_last_system_ms();
 
-#if AP_BROADCAST_ON_POWER_UP
-    // if we are broadcasting on powerup we always mark location valid
-    // so the location with default data is sent
-    if (!UAS_data.LocationValid) {
-        UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
-        UAS_data.LocationValid = 1;
-    }
-#else
-    // only broadcast if we have received a location at least once
-    if (last_location_ms == 0) {
-        return;
+    if (g.bcast_powerup) {
+        // if we are broadcasting on powerup we always mark location valid
+        // so the location with default data is sent
+        if (!UAS_data.LocationValid) {
+            UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE;
+            UAS_data.LocationValid = 1;
+        }
+    } else {
+        // only broadcast if we have received a location at least once
+        if (last_location_ms == 0) {
+            return;
+        }
     }
-#endif
 
     if (last_location_ms == 0 ||
         now_ms - last_location_ms > 5000) {
@@ -287,24 +277,33 @@ void loop()
     }
     
     set_data(transport);
-    last_update = now_ms;
-#if AP_WIFI_NAN_ENABLED
-    if (loop_counter == 0) { //only run on the original update rate
+
+    static uint32_t last_update_wifi_ms;
+    if (g.wifi_nan_rate > 0 &&
+        now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) {
+        last_update_wifi_ms = now_ms;
         wifi.transmit(UAS_data);
     }
-#endif
 
-#if AP_BLE_LONGRANGE_ENABLED
-    if (loop_counter == 0) { //only run on the original update rate
+    static uint32_t last_update_bt5_ms;
+    if (g.bt5_rate > 0 &&
+        now_ms - last_update_bt5_ms > 1000/g.bt5_rate) {
+        last_update_bt5_ms = now_ms;
         ble.transmit_longrange(UAS_data);
     }
-#endif
 
-#if AP_BLE_LEGACY_ENABLED
-    ble.transmit_legacy(UAS_data);
-#endif
+    static uint32_t last_update_bt4_ms;
+    if (g.bt4_rate > 0 &&
+        now_ms - last_update_bt4_ms > 200/g.bt4_rate) {
+        last_update_bt4_ms = now_ms;
+        ble.transmit_legacy(UAS_data);
+        ble.transmit_legacy_name(UAS_data);
+    }
 
-#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED
-    ble.transmit_legacy_name(UAS_data);
-#endif
+    if (g.webserver_enable) {
+        webif.update();
+    }
+
+    // sleep for a bit for power saving
+    delay(1);
 }

+ 4 - 0
RemoteIDModule/WiFi_TX.cpp

@@ -45,6 +45,10 @@ bool WiFi_NAN::init(void)
 
 bool WiFi_NAN::transmit(ODID_UAS_Data &UAS_data)
 {
+    if (!initialised) {
+        initialised = true;
+        init();
+    }
     uint8_t buffer[1024] {};
 
     int length;

+ 1 - 0
RemoteIDModule/WiFi_TX.h

@@ -11,6 +11,7 @@ public:
     bool transmit(ODID_UAS_Data &UAS_data);
 
 private:
+    bool initialised;
     char ssid[32];
     uint8_t WiFi_mac_addr[6];
     uint8_t wifi_channel = 6;

+ 0 - 3
RemoteIDModule/options.h

@@ -21,6 +21,3 @@
 
 // do we support MAVLink connnection to flight controller?
 #define AP_MAVLINK_ENABLED 1
-
-// define the output update rate
-#define OUTPUT_RATE_HZ 1 //this is the minimum update rate according to the docs. More transmissions will increase interferency to other radio modules.

+ 48 - 9
RemoteIDModule/parameters.cpp

@@ -1,15 +1,23 @@
+#include "options.h"
+#include <Arduino.h>
 #include "parameters.h"
+#include <nvs_flash.h>
 #include <string.h>
 
 Parameters g;
+static nvs_handle handle;
 
 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 },
-    { "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 },
+    { "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 },
+    { "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 },
+    { "WIFI_SSID",         Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, },
+    { "WIFI_PASSWORD",     Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, },
+    { "BCAST_POWERUP",     Parameters::ParamType::UINT8,  (const void*)&g.bcast_powerup,    1, 0, 1 },
     { "",                  Parameters::ParamType::NONE,   nullptr,  },
 };
 
@@ -41,20 +49,25 @@ void Parameters::Param::set(uint8_t v) const
 {
     auto *p = (uint8_t *)ptr;
     *p = v;
-    g.dirty = true;
+    nvs_set_u8(handle, name, *p);
 }
 
 void Parameters::Param::set(float v) const
 {
     auto *p = (float *)ptr;
     *p = v;
-    g.dirty = true;
+    union {
+        float f;
+        uint32_t u32;
+    } u;
+    u.f = v;
+    nvs_set_u32(handle, name, u.u32);
 }
 
 void Parameters::Param::set(const char *v) const
 {
     strncpy((char *)ptr, v, PARAM_NAME_MAX_LEN);
-    g.dirty = true;
+    nvs_set_str(handle, name, v);
 }
 
 uint8_t Parameters::Param::get_uint8() const
@@ -92,3 +105,29 @@ void Parameters::load_defaults(void)
         }
     }
 }
+
+void Parameters::init(void)
+{
+    load_defaults();
+
+    if (nvs_flash_init() != ESP_OK ||
+        nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) {
+        Serial.printf("NVS init failed\n");
+    }
+    // load values from NVS
+    for (const auto &p : params) {
+        switch (p.ptype) {
+        case ParamType::UINT8:
+            nvs_get_u8(handle, p.name, (uint8_t *)p.ptr);
+            break;
+        case ParamType::FLOAT:
+            nvs_get_u32(handle, p.name, (uint32_t *)p.ptr);
+            break;
+        case ParamType::CHAR20: {
+            size_t len = 21;
+            nvs_get_str(handle, p.name, (char *)p.ptr, &len);
+            break;
+        }
+        }
+    }
+}

+ 6 - 5
RemoteIDModule/parameters.h

@@ -10,18 +10,19 @@ class Parameters {
 public:
     uint8_t lock_level;
     uint8_t can_node;
+    uint8_t bcast_powerup;
     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";
 
     /*
       header at the front of storage
      */
     struct header {
-        uint32_t format_version;
-        uint32_t flash_counter;
-        uint32_t crc;
         struct public_key {
             uint8_t key[PUBLIC_KEY_LEN];
         } public_keys[MAX_PUBLIC_KEYS];
@@ -54,8 +55,8 @@ public:
     static const Param *find(const char *name);
     static const Param *find_by_index(uint16_t idx);
 
-    bool dirty;
-
+    void init(void);
+private:
     void load_defaults(void);
 };
 

+ 13 - 0
RemoteIDModule/romfs.cpp

@@ -0,0 +1,13 @@
+#include "romfs.h"
+#include "romfs_files.h"
+#include <string.h>
+
+const char *ROMFS::find_string(const char *fname)
+{
+    for (const auto &f : files) {
+        if (strcmp(fname, f.filename) == 0) {
+            return (const char *)f.contents;
+        }
+    }
+    return nullptr;
+}

+ 16 - 0
RemoteIDModule/romfs.h

@@ -0,0 +1,16 @@
+#pragma once
+
+#include <stdint.h>
+
+class ROMFS {
+public:
+    static const char *find_string(const char *fname);
+private:
+
+    struct embedded_file {
+        const char *filename;
+        uint32_t size;
+        const uint8_t *contents;
+    };
+    static const struct embedded_file files[];
+};

+ 1 - 1
RemoteIDModule/version.h

@@ -1,4 +1,4 @@
 #define FW_VERSION_MAJOR 1
-#define FW_VERSION_MINOR 6
+#define FW_VERSION_MINOR 7
 
 #include "git-version.h"

+ 66 - 0
RemoteIDModule/webinterface.cpp

@@ -0,0 +1,66 @@
+#include "webinterface.h"
+
+#include <WiFi.h>
+#include <WiFiClient.h>
+#include <WebServer.h>
+#include <WiFiAP.h>
+#include <ESPmDNS.h>
+#include <Update.h>
+#include "parameters.h"
+#include "romfs.h"
+
+static WebServer server(80);
+
+/*
+  init web server
+ */
+void WebInterface::init(void)
+{
+  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();
+}
+
+void WebInterface::update()
+{
+    if (!initialised) {
+        init();
+        initialised = true;
+    }
+    server.handleClient();
+}

+ 16 - 0
RemoteIDModule/webinterface.h

@@ -0,0 +1,16 @@
+/*
+  web interface
+ */
+#pragma once
+
+#include "options.h"
+#include <Arduino.h>
+#include "version.h"
+
+class WebInterface {
+public:
+    void init(void);
+    void update(void);
+private:
+    bool initialised = false;
+};

+ 88 - 0
scripts/make_romfs.py

@@ -0,0 +1,88 @@
+#!/usr/bin/env python3
+
+'''
+script to create romfs.h from a set of files
+
+Andrew Tridgell
+May 2017
+'''
+
+import os, sys, tempfile, gzip
+
+def write_encode(out, s):
+    out.write(s.encode())
+
+def embed_file(out, f, idx, embedded_name):
+    '''embed one file'''
+    try:
+        contents = open(f,'rb').read()
+    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)
+
+    outf.seek(0)
+    b = bytearray(outf.read())
+    outf.close()
+
+    for c in b:
+        write_encode(out, '%u,' % c)
+    write_encode(out, '};\n\n');
+
+def create_embedded_h(filename, files):
+    '''create a romfs_embedded.h file'''
+
+    out = open(filename, "wb")
+    write_encode(out, '''// generated embedded files\n\n''')
+
+    # remove duplicates and sort
+    files = sorted(list(set(files)))
+    for i in range(len(files)):
+        (name, filename) = files[i]
+        try:
+            embed_file(out, filename, i, name)
+        except Exception as e:
+            print(e)
+            return False
+
+    write_encode(out, '''const ROMFS::embedded_file ROMFS::files[] = {\n''')
+
+    for i in range(len(files)):
+        (name, filename) = files[i]
+        print("Embedding file %s:%s" % (name, filename))
+        write_encode(out, '{ "%s", sizeof(romfs_%u), romfs_%u },\n' % (name, i, i))
+    write_encode(out, '};\n')
+    out.close()
+    return True
+
+if __name__ == '__main__':
+    import sys
+    flist = []
+    if len(sys.argv) < 2:
+        print("Usage: make_romfs.py romfs_files.h FILES...")
+        sys.exit(1)
+    for i in range(2, len(sys.argv)):
+        f = sys.argv[i]
+        flist.append((f, f))
+    create_embedded_h(sys.argv[1], flist)