Skip to content

Commit

Permalink
Added WiFi client mode, more UART options and push to esp-idf 4.4.x
Browse files Browse the repository at this point in the history
ESP32 can now connect to existing WiFi instead of just creating its own.
UART speeds added.
UI improvements.
  • Loading branch information
seeul8er committed Oct 14, 2023
1 parent 43998fd commit ae86ec1
Show file tree
Hide file tree
Showing 11 changed files with 453 additions and 137 deletions.
4 changes: 2 additions & 2 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,5 @@ CMakeListsPrivate.txt
build/

cmake-build-debug/

cmake-build-release/
cmake-build-debug-43/
cmake-build-debug-44/
8 changes: 5 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,8 @@ Examples for boards that will work:
* [Adafruit AirLift – ESP32 WiFi Co-Processor Breakout Board](https://www.adafruit.com/product/4201) (requires FTDI adapter for flashing firmware)
* [Adafruit HUZZAH32](https://www.adafruit.com/product/4172) (requires FTDI adapter for flashing firmware)

DroneBridge for ESP32 is tested with an DOIT ESP32 development board.

DroneBridge for ESP32 is tested with an DOIT ESP32 development board.
**Other ESP boards like the ESP32-C3 etc. are very likely to work as well. I will be necessary to re-compile the code for the target.**

## Installation/Flashing using precompiled binaries

Expand Down Expand Up @@ -105,6 +105,7 @@ Defaults: UART2 (RX2, TX2 on GPIO 16, 17)
![DroneBridge for ESP32 web interface](wiki/dbesp32_webinterface.png)

**Configuration Options:**
- `ESP32 Mode`: ESP32 creates an access point or connects to an existing access point. Beware that the ESP32 will indefinitely search for the specified access point. You will need to re-flash the ESP32 to reset the settings!
- `Wifi SSID`: Up to 31 character long
- `Wifi password`: Up to 63 character long
- `UART baud rate`: Same as you configured on your flight controller
Expand All @@ -129,7 +130,7 @@ Most options require a restart/reset of ESP32 module
You will need the Espressif SDK: esp-idf + toolchain. Check out their website for more info and on how to set it up.
The code is written in pure C using the esp-idf (no arduino libs).

**This project uses the v4.3 branch of ESP-IDF**
**This project supports the v4.3 & v4.4 of ESP-IDF**

Compile and flash by running: `idf.py build`, `idf.py flash`

Expand All @@ -156,6 +157,7 @@ http://dronebridge.local/api/system/reboot
**Trigger a settings change:** Send a valid JSON
```json
{
"esp32_mode": 1,
"wifi_ssid": "DroneBridge ESP32",
"wifi_pass": "dronebridge",
"ap_channel": 6,
Expand Down
59 changes: 55 additions & 4 deletions frontend/db_settings.js
Original file line number Diff line number Diff line change
Expand Up @@ -2,17 +2,45 @@
const ROOT_URL = window.location.href // for production code
let conn_status = 0;

function change_ap_ip_visibility(){
var ap_ip_div = document.getElementById("ap_ip_div");
var ap_channel_div = document.getElementById("ap_channel_div");
if (document.getElementById("esp32_mode").value < 2) {
ap_ip_div.style.display = "block";
ap_channel_div.style.display = "block";
} else {
ap_ip_div.style.display = "none";
ap_channel_div.style.display = "none";
}
}

function change_msp_ltm_visibility(){
var msp_ltm_div = document.getElementById("msp_ltm_div");
var trans_pack_size_div = document.getElementById("trans_pack_size_div");
if (document.getElementById("telem_proto").value === "1") {
msp_ltm_div.style.display = "block";
trans_pack_size_div.style.display = "none";
} else {
msp_ltm_div.style.display = "none";
trans_pack_size_div.style.display = "block";
}
}

/**
* Convert a form into a JSON string
* @param form The HTML form to convert
* @returns {string} JSON formatted string
*/
function toJSONString(form) {
let obj = {}
let elements = form.querySelectorAll("input, select")
for (let i = 0; i < elements.length; ++i) {
let element = elements[i]
let name = element.name
let value = element.value;
let parsed = parseInt(value)
if (!isNaN(parsed) && name.localeCompare("ap_ip")) {
if (!isNaN(Number(value))) {
if (name) {
obj[name] = parsed
obj[name] = parseInt(value)
}
} else {
if (name) {
Expand All @@ -23,6 +51,11 @@ function toJSONString(form) {
return JSON.stringify(obj)
}

/**
* Request data from the ESP to display in the GUI
* @param api_path API path/request path
* @returns {Promise<any>}
*/
async function get_json(api_path) {
let req_url = ROOT_URL + api_path;

Expand All @@ -45,6 +78,12 @@ async function get_json(api_path) {
return await response.json();
}

/**
* Create a response with JSON data attached
* @param api_path API URL path
* @param json_data JSON body data to send
* @returns {Promise<any>}
*/
async function send_json(api_path, json_data) {
let post_url = ROOT_URL + api_path;
const response = await fetch(post_url, {
Expand Down Expand Up @@ -77,10 +116,15 @@ function get_system_info() {
function update_conn_status() {
if (conn_status)
document.getElementById("web_conn_status").innerHTML = "<span class=\"dot_green\"></span> connected to ESP32"
else
else {
document.getElementById("web_conn_status").innerHTML = "<span class=\"dot_red\"></span> disconnected from ESP32"
document.getElementById("current_client_ip").innerHTML = ""
}
}

/**
* Get connection status information and display it in the GUI
*/
function get_stats() {
get_json("api/system/stats").then(json_data => {
conn_status = 1
Expand All @@ -104,12 +148,17 @@ function get_stats() {
} else if (!isNaN(udp_clients)) {
document.getElementById("udp_connected").innerHTML = udp_clients + " client"
}

document.getElementById("current_client_ip").innerHTML = "IP Address: " + json_data["current_client_ip"]
}).catch(error => {
conn_status = 0
error.message;
});
}

/**
* Get settings from ESP and display them in the GUI. JSON objects have to match the element ids
*/
function get_settings() {
get_json("api/settings/request").then(json_data => {
console.log("Received settings: " + json_data)
Expand All @@ -124,6 +173,8 @@ function get_settings() {
conn_status = 0
error.message;
});
change_ap_ip_visibility();
change_msp_ltm_visibility();
}

function show_toast(msg) {
Expand Down
33 changes: 27 additions & 6 deletions frontend/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,10 @@ <h2>Statistics</h2>
<div style="font-size: 1.3rem" id="web_conn_status" class="six columns">
</div>
</div>
<div class="row">
<div style="font-size: 1.3rem" id="current_client_ip" class="six columns">
</div>
</div>
<div class="row">
<div class="four columns">
<label for="read_bytes">UART received bytes</label>
Expand All @@ -112,6 +116,15 @@ <h2>Statistics</h2>
</div>
<div>
<h2>Settings</h2>
<div class="row">
<div class="twelve columns">
<label for="esp32_mode">ESP32 Mode (requires save & reboot)</label>
<select id="esp32_mode" name="esp32_mode" form="settings_form" onchange="change_ap_ip_visibility()">
<option value="1">Access Point Mode</option>
<option value="2">WiFi Client Mode</option>
</select>
</div>
</div>
<div class="row">
<div class="six columns">
<label for="wifi_ssid">Wifi SSID</label>
Expand All @@ -123,7 +136,7 @@ <h2>Settings</h2>
</div>
</div>
<div class="row">
<div class="twelve columns">
<div id="ap_channel_div" class="twelve columns">
<label for="ap_channel">Wifi Channel</label>
<input type="text" name="ap_channel" value="" id="ap_channel">
</div>
Expand All @@ -141,7 +154,7 @@ <h2>Settings</h2>
<div class="row">
<div class="six columns">
<label for="telem_proto">UART serial protocol</label>
<select id="telem_proto" name="telem_proto" form="settings_form">
<select id="telem_proto" name="telem_proto" form="settings_form" onchange="change_msp_ltm_visibility()">
<option value="1">MSP/LTM</option>
<option value="4">Transparent/MAVLink</option>
</select>
Expand All @@ -153,17 +166,23 @@ <h2>Settings</h2>
<option value="1500000">1500000</option>
<option value="1000000">1000000</option>
<option value="500000">500000</option>
<option value="921600">921600</option>
<option value="576000">576000</option>
<option value="460800">460800</option>
<option value="230400">230400</option>
<option value="115200">115200</option>
<option value="76800">76800</option>
<option value="57600">57600</option>
<option value="38400">38400</option>
<option value="19200">19200</option>
<option value="9600">9600</option>
<option value="4800">4800</option>
<option value="2400">2400</option>
<option value="1200">1200</option>
</select>
</div>
</div>
<div class="row">
<div id="msp_ltm_div" class="row">
<div class="six columns">
<label for="msp_ltm_port">MSP & LTM to same port</label>
<select id="msp_ltm_port" name="msp_ltm_port" form="settings_form">
Expand All @@ -182,7 +201,7 @@ <h2>Settings</h2>
</select>
</div>
</div>
<div class="row">
<div id="trans_pack_size_div" class="row">
<div class="twelve columns">
<label for="trans_pack_size">Transparent packet size</label>
<select id="trans_pack_size" name="trans_pack_size" form="settings_form">
Expand All @@ -194,7 +213,7 @@ <h2>Settings</h2>
</select>
</div>
</div>
<div class="row">
<div id="ap_ip_div" class="row">
<div class="six columns">
<label for="ap_ip">Gateway IP address</label>
<input type="text" name="ap_ip" value="" id="ap_ip">
Expand All @@ -212,14 +231,16 @@ <h2>Settings</h2>
</div>
</div>
<div class="container">
<div id="about" style="margin-top: 1rem" class="row">DroneBridge for ESP32 - waiting for response from the ESP32
<div id="about" style="margin-top: 1rem" class="row">DroneBridge for ESP32 - waiting for a response from the ESP32
</div>
<div style="margin-bottom: 2rem" class="row">&copy; Wolfgang Christl 2018 - Apache 2.0 License</div>
</div>
<script>
// get settings once upon page load
get_system_info()
get_settings()
change_msp_ltm_visibility()
change_ap_ip_visibility()
// get stats every half a second
setInterval(get_stats, 500)
setInterval(update_conn_status, 500)
Expand Down
23 changes: 15 additions & 8 deletions main/db_esp32_control.c
Original file line number Diff line number Diff line change
Expand Up @@ -221,37 +221,44 @@ void handle_tcp_master(const int tcp_master_socket, int tcp_clients[]) {
}

/**
* Add a new client to the list of known UDP clients. Check if client is already known
* Add a new client to the list of known UDP clients. Checks if client is already known.
*
* @param connections Structure containing all UDP connection information
* @param new_client_addr Address of new client
* @param is_brdcst True if the client is to be added because he is connected to the local access point. He will receive
* telemetry even if he did not request it (broadcast)
*/
void
add_udp_to_known_clients(struct db_udp_connection_t *connections, struct sockaddr_in new_client_addr, bool is_brdcst) {
for (int i = 0; i < MAX_UDP_CLIENTS; i++) {
// Check if client is already listed
if (connections->udp_clients[i].sin_port == new_client_addr.sin_port && new_client_addr.sin_family == PF_INET &&
((struct sockaddr_in *) &connections->udp_clients[i])->sin_addr.s_addr ==
((struct sockaddr_in *) &new_client_addr)->sin_addr.s_addr) {
return;
} else if (connections->udp_clients[i].sin_len == 0) {
} else if (connections->udp_clients[i].sin_len == 0) { // check if we found an empty spot in the list
// (must be the end of the list then - kind of shady check I know but list gets cleared via
// update_udp_broadcast first)
connections->udp_clients[i] = new_client_addr;
char addr_str[128];
if (new_client_addr.sin_family == PF_INET) {
inet_ntoa_r(((struct sockaddr_in *) &new_client_addr)->sin_addr.s_addr, addr_str, sizeof(addr_str) - 1);
}
connections->is_broadcast[i] = is_brdcst;
if (!is_brdcst) {
// Only console out the clients that are not broadcast clients
ESP_LOGI(TAG, "UDP: New client connected: %s:%i", addr_str, new_client_addr.sin_port);
}
num_connected_udp_clients += 1;
return;
}
}
}

/**
* Get all connected clients to local AP and add to UDP connection list. List is updated every second
*
* @param pInt
* Get all connected clients to local AP and add to UDP connection list. These clients will receive telementry no
* matter if they requested. List is updated every second
* Only works in access point mode
*/
void update_udp_broadcast(int64_t *last_update, struct db_udp_connection_t *connections, const wifi_mode_t *wifi_mode) {
if (*wifi_mode == WIFI_MODE_AP && (esp_timer_get_time() - *last_update) >= 1000000) {
Expand Down Expand Up @@ -279,7 +286,6 @@ void update_udp_broadcast(int64_t *last_update, struct db_udp_connection_t *conn
new_client_addr.sin_addr.s_addr = station.ip.addr;
ESP_LOGD(TAG, "%i " IPSTR " " MACSTR "", netif_sta_list.num, IP2STR(&station.ip), MAC2STR(station.mac));
if (station.ip.addr != 0) { // DHCP bug. Assigns 0.0.0.0 to station when directly connected on startup
num_connected_udp_clients += 1;
add_udp_to_known_clients(connections, new_client_addr, true);
}
}
Expand All @@ -304,7 +310,7 @@ _Noreturn void control_module_tcp() {
tcp_clients[i] = -1;
}
if (tcp_master_socket == ESP_FAIL || uart_socket == ESP_FAIL) {
ESP_LOGE(TAG, "Can not start control module");
ESP_LOGE(TAG, "Can not start control module: tcp socket: %i UART socket: %i", tcp_master_socket, uart_socket);
}
fcntl(tcp_master_socket, F_SETFL, O_NONBLOCK);
uint read_transparent = 0;
Expand Down Expand Up @@ -343,7 +349,8 @@ _Noreturn void control_module_tcp() {
}
}
}
// handle incoming UDP data
// handle incoming UDP data - Read UDP and forward to flight controller
// all devices that send us UDP data will be added to the list of MAVLink UDP receivers
ssize_t recv_length = recvfrom(udp_conn.udp_socket, udp_buffer, UDP_BUF_SIZE, 0,
(struct sockaddr *) &udp_source_addr, &udp_socklen);
if (recv_length > 0) {
Expand Down
23 changes: 0 additions & 23 deletions main/db_esp32_settings.h

This file was deleted.

6 changes: 5 additions & 1 deletion main/globals.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,12 +25,14 @@
#define MAX_LTM_FRAMES_IN_BUFFER 5
#define BUILDVERSION 7
#define MAJOR_VERSION 1
#define MINOR_VERSION 0
#define MINOR_VERSION 2

// can be set by user
extern uint8_t DB_WIFI_MODE;
extern uint8_t DEFAULT_SSID[32];
extern uint8_t DEFAULT_PWD[64];
extern char DEFAULT_AP_IP[32];
extern char CURRENT_CLIENT_IP[32]; // IP address of the ESP32 when we are in client mode connected
extern uint8_t DEFAULT_CHANNEL;
extern uint8_t SERIAL_PROTOCOL; // 1=MSP, 3=MAVLink/transparent
extern uint8_t DB_UART_PIN_TX;
Expand All @@ -44,4 +46,6 @@ extern uint32_t uart_byte_count;
extern int8_t num_connected_tcp_clients;
extern int8_t num_connected_udp_clients;

extern int WIFI_ESP_MAXIMUM_RETRY;

#endif //DB_ESP32_GLOBALS_H
Loading

0 comments on commit ae86ec1

Please sign in to comment.