Răsfoiți Sursa

only init WiFi if needed

allow WiFi to totally disable
Andrew Tridgell 3 ani în urmă
părinte
comite
e1684b86c5

+ 4 - 1
RemoteIDModule/RemoteIDModule.ino

@@ -63,7 +63,10 @@ void setup()
     led.set_state(Led::LedState::INIT);
     led.update();
 
-    wifi.init(); //always call the init function even if WiFi transmission modes are disabled.
+    if (g.webserver_enable) {
+        // need WiFi for web server
+        wifi.init();
+    }
 
     // Serial for debug printf
     Serial.begin(g.baudrate);

+ 13 - 13
RemoteIDModule/WiFi_TX.cpp

@@ -12,6 +12,11 @@
 
 bool WiFi_TX::init(void)
 {
+    if (initialised) {
+        return true;
+    }
+    initialised = true;
+
     //use a local MAC address to avoid tracking transponders based on their MAC address
     uint8_t mac_addr[6];
     generate_random_mac(mac_addr);
@@ -23,11 +28,10 @@ bool WiFi_TX::init(void)
     esp_base_mac_addr_set(mac_addr);
 
     if (g.webserver_enable == 0) {
-		WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 0); //make it visible and allow no connection
-	}
-	else {
-		WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 1); //make it visible and allow only 1 connection
-	}
+        WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 0); //make it visible and allow no connection
+    } else {
+        WiFi.softAP(g.wifi_ssid, g.wifi_password, g.wifi_channel, false, 1); //make it visible and allow only 1 connection
+    }
 
     if (esp_wifi_set_bandwidth(WIFI_IF_AP, WIFI_BW_HT20) != ESP_OK) {
         return false;
@@ -42,10 +46,8 @@ bool WiFi_TX::init(void)
 
 bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
 {
-    if (!initialised) {
-        initialised = true;
-        init();
-    }
+    init();
+
     uint8_t buffer[1024] {};
 
     int length;
@@ -70,10 +72,8 @@ bool WiFi_TX::transmit_nan(ODID_UAS_Data &UAS_data)
 //update the payload of the beacon frames in this function
 bool WiFi_TX::transmit_beacon(ODID_UAS_Data &UAS_data)
 {
-    if (!initialised) {
-        initialised = true;
-        init();
-    }
+    init();
+
     uint8_t buffer[1024] {};
 
     int length;

+ 1 - 1
RemoteIDModule/parameters.cpp

@@ -17,7 +17,7 @@ const Parameters::Param Parameters::params[] = {
     { "UAS_ID",            Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0],        0, 0, 0 },
     { "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 },
-    { "WIFI_BEACON_RATE",  Parameters::ParamType::FLOAT,  (const void*)&g.wifi_beacon_rate,    0, 0, 5 },
+    { "WIFI_BCN_RATE",     Parameters::ParamType::FLOAT,  (const void*)&g.wifi_beacon_rate,    0, 0, 5 },
     { "WIFI_POWER",        Parameters::ParamType::FLOAT,  (const void*)&g.wifi_power,       20, 2, 20 },
     { "BT4_RATE",          Parameters::ParamType::FLOAT,  (const void*)&g.bt4_rate,         1, 0, 5 },
     { "BT4_POWER",         Parameters::ParamType::FLOAT,  (const void*)&g.bt4_power,        18, -27, 18 },