{n.abort()}),1e3),await fetch(t,{signal:n.signal}));if(!s.ok){const e=`An error has occured: ${s.status}`;throw conn_status=0,new Error(e)}return await s.json()}async function send_json(e,t){let n=ROOT_URL+e;const s=await fetch(n,{method:"POST",headers:{Accept:"application/json","Content-Type":"application/json",charset:"UTF-8"},body:t});if(!s.ok){conn_status=0;const e=`An error has occured: ${s.status}`;throw new Error(e)}return await s.json()}function get_system_info(){return get_json("api/system/info").then((e=>{console.log("Received settings: "+e),document.getElementById("about").innerHTML="DroneBridge for ESP32 - v"+e.major_version+"."+e.minor_version+" - esp-idf "+e.idf_version})).catch((e=>(conn_status=0,e.message,-1))),0}function update_conn_status(){conn_status?document.getElementById("web_conn_status").innerHTML=' connected to ESP32':(document.getElementById("web_conn_status").innerHTML=' disconnected from ESP32',document.getElementById("current_client_ip").innerHTML="")}function get_stats(){get_json("api/system/stats").then((e=>{conn_status=1;let t=parseInt(e.read_bytes);!isNaN(t)&&t>1e3?document.getElementById("read_bytes").innerHTML=t/1e3+" kb":isNaN(t)||(document.getElementById("read_bytes").innerHTML=t+" bytes");let n=parseInt(e.tcp_connected);!isNaN(n)&&n>1?document.getElementById("tcp_connected").innerHTML=n+" clients":isNaN(n)||(document.getElementById("tcp_connected").innerHTML=n+" client");let s=parseInt(e.udp_connected);!isNaN(s)&&s>1?document.getElementById("udp_connected").innerHTML=s+" clients":isNaN(s)||(document.getElementById("udp_connected").innerHTML=s+" client");let o=parseInt(e.rssi);!isNaN(o)&&o<0?document.getElementById("current_client_ip").innerHTML="IP Address: "+e.current_client_ip+"
RSSI: "+o+"dBm":isNaN(o)||(document.getElementById("current_client_ip").innerHTML="IP Address: "+e.current_client_ip)})).catch((e=>{conn_status=0,e.message}))}function get_settings(){return get_json("api/settings/request").then((e=>{console.log("Received settings: "+e),conn_status=1;for(const t in e)if(e.hasOwnProperty(t)){document.getElementById(t).value=e[t]+""}})).catch((e=>(conn_status=0,e.message,show_toast(e.message),-1))),change_ap_ip_visibility(),change_msp_ltm_visibility(),0}function show_toast(e){Toastify({text:e,duration:5e3,newWindow:!0,close:!0,gravity:"top",position:"center",backgroundColor:"linear-gradient(to right, #b6e026, #abdc28)",stopOnFocus:!0}).showToast()}function save_settings(){send_json("api/settings/change",toJSONString(document.getElementById("settings_form"))).then((e=>{console.log(e),conn_status=1,show_toast(e.msg),get_settings()})).catch((e=>{show_toast(e.message)}))}function trigger_reboot(){get_json("api/system/reboot").then((e=>{show_toast(e.msg)})).catch((e=>{e.message,show_toast(e.message)}))}
diff --git a/frontend_src/dronebridge.js b/frontend_src/dronebridge.js
index d1860c7..3b9010f 100644
--- a/frontend_src/dronebridge.js
+++ b/frontend_src/dronebridge.js
@@ -159,7 +159,12 @@ function get_stats() {
document.getElementById("udp_connected").innerHTML = udp_clients + " client"
}
- document.getElementById("current_client_ip").innerHTML = "IP Address: " + json_data["current_client_ip"]
+ let rssi = parseInt(json_data["rssi"])
+ if (!isNaN(rssi) && rssi < 0) {
+ document.getElementById("current_client_ip").innerHTML = "IP Address: " + json_data["current_client_ip"] + "
RSSI: " + rssi + "dBm"
+ } else if (!isNaN(rssi)) {
+ document.getElementById("current_client_ip").innerHTML = "IP Address: " + json_data["current_client_ip"]
+ }
}).catch(error => {
conn_status = 0
error.message;
diff --git a/main/db_esp32_control.c b/main/db_esp32_control.c
index 74c05b0..70fb8c9 100644
--- a/main/db_esp32_control.c
+++ b/main/db_esp32_control.c
@@ -24,6 +24,7 @@
#include
#include
#include
+#include
#include "esp_log.h"
#include "lwip/sockets.h"
#include "driver/uart.h"
@@ -32,6 +33,7 @@
#include "db_protocol.h"
#include "tcp_server.h"
#include "db_esp32_control.h"
+#include "main.h"
#define UART_NUM UART_NUM_1
@@ -387,6 +389,12 @@ void control_module_udp_tcp() {
// read: https://esp32developer.com/programming-in-c-c/tasks/tasks-vs-co-routines for reference
vTaskDelay(10/portTICK_PERIOD_MS);
delay_timer_cnt = 0;
+ if (DB_WIFI_MODE == DB_WIFI_MODE_STA) {
+ // update rssi variable - set to 0 when not available
+ if (esp_wifi_sta_get_rssi(&station_rssi) != ESP_OK) {
+ station_rssi = 0;
+ }
+ }
} else {
delay_timer_cnt++;
}
diff --git a/main/globals.h b/main/globals.h
index 2525f84..6669d57 100644
--- a/main/globals.h
+++ b/main/globals.h
@@ -42,6 +42,7 @@ extern int DB_UART_BAUD_RATE;
extern uint16_t TRANSPARENT_BUF_SIZE;
extern uint8_t LTM_FRAME_NUM_BUFFER; // Number of LTM frames per UDP packet (min = 1; max = 5)
extern uint8_t MSP_LTM_SAMEPORT; // 0 = no (1607 MSP, 1604 LTM); >0 = yes (1604)
+extern int station_rssi; // updated when ESP32 is in station mode and connected to an access point
extern uint32_t uart_byte_count;
extern int8_t num_connected_tcp_clients;
diff --git a/main/http_server.c b/main/http_server.c
index 38b60c7..d603200 100644
--- a/main/http_server.c
+++ b/main/http_server.c
@@ -256,6 +256,7 @@ static esp_err_t system_stats_get_handler(httpd_req_t *req) {
cJSON_AddNumberToObject(root, "tcp_connected", num_connected_tcp_clients);
cJSON_AddNumberToObject(root, "udp_connected", udp_conn_list->size);
cJSON_AddStringToObject(root, "current_client_ip", CURRENT_CLIENT_IP);
+ cJSON_AddNumberToObject(root, "rssi", station_rssi);
const char *sys_info = cJSON_Print(root);
httpd_resp_sendstr(req, sys_info);
free((void *) sys_info);
diff --git a/main/main.c b/main/main.c
index f953ce2..06f83fb 100644
--- a/main/main.c
+++ b/main/main.c
@@ -60,6 +60,7 @@ int32_t DB_UART_BAUD_RATE = 115200;
uint16_t TRANSPARENT_BUF_SIZE = 64;
uint8_t LTM_FRAME_NUM_BUFFER = 1;
uint8_t MSP_LTM_SAMEPORT = 0;
+int station_rssi = 0;
struct udp_conn_list_t *udp_conn_list;
@@ -284,7 +285,7 @@ int init_wifi_clientmode() {
.sta = {
.ssid = "DroneBridge_ESP32_Init",
.password = "dronebridge",
- .threshold.authmode = WIFI_AUTH_OPEN
+ .threshold.authmode = WIFI_AUTH_WEP
},
};
strncpy((char *)wifi_config.sta.ssid, (char *)DEFAULT_SSID, 32);