Skip to content

Commit

Permalink
Merge pull request #88 from DroneBridge/v2.0dev
Browse files Browse the repository at this point in the history
v2.0RC4
  • Loading branch information
seeul8er authored Oct 25, 2024
2 parents 27985af + e87214f commit 0e2810a
Show file tree
Hide file tree
Showing 16 changed files with 210 additions and 78 deletions.
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ A firmware for the popular ESP32 modules from Espressif Systems. Probably the ch
communicate with your drone, UAV, UAS, ground-based vehicle or whatever you may call them.

It also allows for a fully transparent serial to WiFi pass-through link with variable packet size
(Continuous stream of data required).
(As of release v2.0RC4 no continuous stream of data required anymore in MAVLink and transparent mode).

DroneBridge for ESP32 is a telemetry/low data rate-only solution. There is no support for cameras connected to the ESP32
since it does not support video encoding.
Expand All @@ -34,7 +34,7 @@ since it does not support video encoding.
- Fully configurable through an easy-to-use web interface
- Parsing of LTM & MSPv2 for more reliable connection and less packet loss
- Parsing of MAVLink with the injection of Radio Status packets for the display of RSSI in the GCS
- Fully transparent telemetry down-link option for continuous streams
- Fully transparent telemetry down-link option
- Reliable, low latency

<div align="center">
Expand Down
18 changes: 15 additions & 3 deletions frontend/dronebridge.js
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@ const ROOT_URL = window.location.href // for production code
let conn_status = 0; // connection status to the ESP32
let old_conn_status = 0; // connection status before last update of UI to know when it changed
let serial_via_JTAG = 0; // set to 1 if ESP32 is using the USB interface as serial interface for data and not using the UART. If 0 we set UART config to invisible for the user.
let last_byte_count = 0;
let last_timestamp_byte_count = 0;

function change_ap_ip_visibility(){
let ap_ip_div = document.getElementById("ap_ip_div");
Expand Down Expand Up @@ -176,12 +178,22 @@ function update_conn_status() {
function get_stats() {
get_json("api/system/stats").then(json_data => {
conn_status = 1
let d = new Date();
let bytes = parseInt(json_data["read_bytes"])
if (!isNaN(bytes) && bytes > 1000) {
document.getElementById("read_bytes").innerHTML = (bytes / 1000) + " kb"
let bytes_per_second = 0;
let current_time = d.getTime();
if (last_byte_count > 0 && last_timestamp_byte_count > 0 && !isNaN(bytes)) {
bytes_per_second = (bytes - last_byte_count) / ((current_time - last_timestamp_byte_count) / 1000);
}
last_timestamp_byte_count = current_time;
if (!isNaN(bytes) && bytes > 1000000) {
document.getElementById("read_bytes").innerHTML = (bytes / 1000000).toFixed(3) + " MB (" + ((bytes_per_second*8)/1000).toFixed(2) + " kbit/s)"
} else if (!isNaN(bytes) && bytes > 1000) {
document.getElementById("read_bytes").innerHTML = (bytes / 1000).toFixed(2) + " kB (" + ((bytes_per_second*8)/1000).toFixed(2) + " kbit/s)"
} else if (!isNaN(bytes)) {
document.getElementById("read_bytes").innerHTML = bytes + " bytes"
document.getElementById("read_bytes").innerHTML = bytes + " bytes (" + Math.round(bytes_per_second) + " byte/s)"
}
last_byte_count = bytes;

let tcp_clients = parseInt(json_data["tcp_connected"])
if (!isNaN(tcp_clients) && tcp_clients === 1) {
Expand Down
6 changes: 5 additions & 1 deletion frontend/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@ <h3>Serial</h3>
</div>
</div>
<div id="trans_pack_size_div" class="row">
<div class="twelve columns">
<div class="six columns">
<label for="trans_pack_size">Maximum packet size</label>
<select id="trans_pack_size" name="trans_pack_size" form="settings_form">
<option value="16">16</option>
Expand All @@ -177,6 +177,10 @@ <h3>Serial</h3>
<option value="768">768</option>
</select>
</div>
<div class="six columns">
<label for="serial_timeout">Serial read timeout [ms]</label>
<input type="number" id="serial_timeout" name="serial_timeout" min="1" max="65535" value="50">
</div>
</div>
<div class="row">
<div class="six columns" id="ap_ip_div">
Expand Down
61 changes: 47 additions & 14 deletions main/db_esp32_control.c
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ int db_open_int_telemetry_udp_socket() {
* @param data Buffer with the data to send
* @param data_length Length of the data in the buffer
*/
void send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *data, uint data_length) {
void db_send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *data, uint data_length) {
for (int i = 0; i < n_udp_conn_list->size; i++) { // send to all UDP clients
int sent = sendto(n_udp_conn_list->udp_socket, data, data_length, 0,
(struct sockaddr *) &n_udp_conn_list->db_udp_clients[i].udp_client,
Expand All @@ -206,30 +206,63 @@ void send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *da
}

/**
* Adds a payload to be sent via ESP-NOW to the ESP-NOW queue (where the esp-now task will pick it up, encrypt, package
* and finally send it over the air)
*
* @param data Pointer to the payload buffer
* @param data_length Length of the payload data. Must not be bigger than DB_ESPNOW_PAYLOAD_MAXSIZE - fails otherwise
*/
void db_send_to_all_espnow(uint8_t data[], const uint16_t *data_length) {
db_espnow_queue_event_t evt;
evt.data = malloc(*data_length);
memcpy(evt.data, data, *data_length);
evt.data_len = *data_length;
evt.packet_type = DB_ESP_NOW_PACKET_TYPE_DATA;
if (xQueueSend(db_espnow_send_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
ESP_LOGW(TAG, "Send to db_espnow_send_queue queue fail");
free(evt.data);
} else {
// all good
}
}

/**
* Main call for sending anything over the air.
* Send to all connected TCP & UDP clients or broadcast via ESP-NOW depending on the mode (DB_WIFI_MODE) we are currently in.
* Typically called by a function that read from UART.
*
* When in ESP-NOW mode the packets will be split if they are bigger than DB_ESPNOW_PAYLOAD_MAXSIZE.
*
* @param tcp_clients Array of socket IDs for the TCP clients
* @param udp_conn Structure handling the UDP connection
* @param data payload to send
* @param data_length Length of payload to send
*/
void send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint data_length) {
void db_send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint16_t data_length) {
if (DB_WIFI_MODE != DB_WIFI_MODE_ESPNOW_AIR && DB_WIFI_MODE != DB_WIFI_MODE_ESPNOW_GND) {
send_to_all_tcp_clients(tcp_clients, data, data_length);
send_to_all_udp_clients(n_udp_conn_list, data, data_length);
db_send_to_all_tcp_clients(tcp_clients, data, data_length);
db_send_to_all_udp_clients(n_udp_conn_list, data, data_length);
} else {
// ESP-NOW mode
db_espnow_queue_event_t evt;
evt.data = malloc(data_length);
memcpy(evt.data, data, data_length);
evt.data_len = data_length;
evt.packet_type = DB_ESP_NOW_PACKET_TYPE_DATA;
if (xQueueSend(db_espnow_send_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
ESP_LOGW(TAG, "Send to db_espnow_send_queue queue fail");
free(evt.data);
// Check if payload fits into one ESP-NOW packet
if (data_length > DB_ESPNOW_PAYLOAD_MAXSIZE) {
// data not properly sized (MAVLink implementation already sends properly sized chunks but MSP parser will not)
// split into multiple packets
uint16_t sent_bytes = 0;
uint16_t next_chunk_len = 0;
do {
next_chunk_len = data_length - sent_bytes;
if (next_chunk_len > DB_ESPNOW_PAYLOAD_MAXSIZE) {
next_chunk_len = DB_ESPNOW_PAYLOAD_MAXSIZE;
} else {
// do nothing - chunk will fit into the ESP-NOW payload field
}
db_send_to_all_espnow(&data[sent_bytes], &next_chunk_len);
sent_bytes += next_chunk_len;
} while (sent_bytes < data_length);
} else {
// all good
// packet is properly sized - send to ESP-NOW outbound queue
db_send_to_all_espnow(data, &data_length);
}
}
}
Expand Down Expand Up @@ -416,7 +449,7 @@ _Noreturn void control_module_esp_now(){
if (db_uart_write_queue != NULL && xQueueReceive(db_uart_write_queue, &db_espnow_uart_evt, 0) == pdTRUE) {
if (DB_SERIAL_PROTOCOL == DB_SERIAL_PROTOCOL_MAVLINK) {
// Parse, so we can listen in and react to certain messages - function will send parsed messages to serial link.
// We can not write to serial first since we might inject packets and do not know when to do so to not "destroy" an existign packet
// We can not write to serial first since we might inject packets and do not know when to do so to not "destroy" an existing packet
db_parse_mavlink_from_radio(NULL, NULL, db_espnow_uart_evt.data, db_espnow_uart_evt.data_len);
} else {
// no parsing with any other protocol - transparent here - just pass through
Expand Down
2 changes: 1 addition & 1 deletion main/db_esp32_control.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void control_module();
udp_conn_list_t *udp_client_list_create();
void udp_client_list_destroy(udp_conn_list_t *n_udp_conn_list);
bool add_to_known_udp_clients(udp_conn_list_t *n_udp_conn_list, struct db_udp_client_t new_db_udp_client, bool save_to_nvm);
void send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint data_length);
void db_send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint16_t data_length);
bool remove_from_known_udp_clients(udp_conn_list_t *n_udp_conn_list, struct db_udp_client_t new_db_udp_client);

#endif //DB_ESP32_DB_ESP32_CONTROL_H
2 changes: 1 addition & 1 deletion main/db_esp_now.c
Original file line number Diff line number Diff line change
Expand Up @@ -544,7 +544,7 @@ esp_err_t db_espnow_init() {
if (!esp_now_is_peer_exist(BROADCAST_MAC)) ESP_ERROR_CHECK(esp_now_add_peer(&peer));

/* Limit payload size to the max we can do */
if (DB_TRANS_BUF_SIZE > DB_ESPNOW_PAYLOAD_MAXSIZE) {
if (DB_TRANS_BUF_SIZE > DB_ESPNOW_PAYLOAD_MAXSIZE || DB_TRANS_BUF_SIZE < 1) {
DB_TRANS_BUF_SIZE = DB_ESPNOW_PAYLOAD_MAXSIZE;
} else {
// all good
Expand Down
22 changes: 18 additions & 4 deletions main/db_mavlink_msgs.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@

#define TAG "DB_MAV_MSGS"

uint16_t DB_MAV_PARAM_CNT = 11;
uint16_t DB_MAV_PARAM_CNT = 12; // Number of MAVLink parameters returned by ESP32 in the PARAM message. Needed by GCS.

/**
* Based on the system architecture and configured wifi mode the ESP32 may have a different role and system id.
Expand Down Expand Up @@ -129,6 +129,9 @@ MAV_TYPE db_mav_get_parameter_value(float_int_union *float_int, char *param_id,
} else if (strncmp(param_id, "SERIAL_RTS_THRES", 16) == 0 || param_index == 10) {
float_int->uint8 = DB_UART_RTS_THRESH;
type = MAV_PARAM_TYPE_UINT8;
} else if (strncmp(param_id, "SERIAL_T_OUT_MS", 16) == 0 || param_index == 11) {
float_int->uint16 = DB_SERIAL_READ_TIMEOUT_MS;
type = MAV_PARAM_TYPE_UINT16;
} else {
type = 0;
}
Expand Down Expand Up @@ -162,6 +165,13 @@ bool db_write_mavlink_parameter(fmav_param_set_t *param_set_payload) {
} else {
ESP_LOGE(TAG, "SERIAL_PACK_SIZE must be <1024 bytes");
}
} else if (strncmp(param_set_payload->param_id, "SERIAL_T_OUT_MS", 16) == 0) {
if (float_int.uint16 > 0) {
DB_SERIAL_READ_TIMEOUT_MS = float_int.uint16;
success = true;
} else {
ESP_LOGE(TAG, "SERIAL_T_OUT_MS must be >0 MS");
}
} else if (strncmp(param_set_payload->param_id, "SERIAL_BAUD", 16) == 0) {
DB_UART_BAUD_RATE = float_int.int32;
success = true;
Expand Down Expand Up @@ -350,7 +360,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
uint16_t len = fmav_msg_radio_status_encode_to_frame_buf(buff, db_get_mav_sys_id(),
db_get_mav_comp_id(), &payload_r,
fmav_status);
send_to_all_clients(tcp_clients, udp_conns, buff, len);
db_send_to_all_clients(tcp_clients, udp_conns, buff, len);
} else if (DB_WIFI_MODE == DB_WIFI_MODE_AP && wifi_sta_list.num > 0) {
// we assume ESP32 is not used in DB_WIFI_MODE_AP on the ground but only on the drone side
// ToDo: Only the RSSI of the first client is considered.
Expand All @@ -359,7 +369,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
uint16_t len = fmav_msg_radio_status_encode_to_frame_buf(buff, db_get_mav_sys_id(),
db_get_mav_comp_id(), &payload_r,
fmav_status);
send_to_all_clients(tcp_clients, udp_conns, buff, len);
db_send_to_all_clients(tcp_clients, udp_conns, buff, len);
} else {
// In AP LR mode the clients will send the info to the GCS
}
Expand All @@ -369,7 +379,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
// ToDo: Check if that is a good idea or push to extra thread
uint16_t length = db_create_heartbeat(buff, fmav_status);
// Send heartbeat to GND clients: Every ESP32 no matter its role or mode is emitting a heartbeat
send_to_all_clients(tcp_clients, udp_conns, buff, length);
db_send_to_all_clients(tcp_clients, udp_conns, buff, length);
} // do not react to heartbeats received via wireless interface - reaction to serial is sufficient
break;
case FASTMAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
Expand Down Expand Up @@ -419,6 +429,10 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
float_int.uint8 = DB_UART_RTS_THRESH;
len = db_get_mavmsg_param(buff, fmav_status, 10, &float_int, MAV_PARAM_TYPE_UINT8, "SERIAL_RTS_THRES");
db_route_mavlink_response(buff, len, origin, tcp_clients, udp_conns);

float_int.uint16 = DB_SERIAL_READ_TIMEOUT_MS;
len = db_get_mavmsg_param(buff, fmav_status, 11, &float_int, MAV_PARAM_TYPE_UINT16, "SERIAL_T_OUT_MS");
db_route_mavlink_response(buff, len, origin, tcp_clients, udp_conns);
}
break;
case FASTMAVLINK_MSG_ID_PARAM_REQUEST_READ: {
Expand Down
Loading

0 comments on commit 0e2810a

Please sign in to comment.