Skip to content

Commit 0e2810a

Browse files
authored
Merge pull request #88 from DroneBridge/v2.0dev
v2.0RC4
2 parents 27985af + e87214f commit 0e2810a

16 files changed

+210
-78
lines changed

README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ A firmware for the popular ESP32 modules from Espressif Systems. Probably the ch
1414
communicate with your drone, UAV, UAS, ground-based vehicle or whatever you may call them.
1515

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

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

4040
<div align="center">

frontend/dronebridge.js

+15-3
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,8 @@ const ROOT_URL = window.location.href // for production code
33
let conn_status = 0; // connection status to the ESP32
44
let old_conn_status = 0; // connection status before last update of UI to know when it changed
55
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.
6+
let last_byte_count = 0;
7+
let last_timestamp_byte_count = 0;
68

79
function change_ap_ip_visibility(){
810
let ap_ip_div = document.getElementById("ap_ip_div");
@@ -176,12 +178,22 @@ function update_conn_status() {
176178
function get_stats() {
177179
get_json("api/system/stats").then(json_data => {
178180
conn_status = 1
181+
let d = new Date();
179182
let bytes = parseInt(json_data["read_bytes"])
180-
if (!isNaN(bytes) && bytes > 1000) {
181-
document.getElementById("read_bytes").innerHTML = (bytes / 1000) + " kb"
183+
let bytes_per_second = 0;
184+
let current_time = d.getTime();
185+
if (last_byte_count > 0 && last_timestamp_byte_count > 0 && !isNaN(bytes)) {
186+
bytes_per_second = (bytes - last_byte_count) / ((current_time - last_timestamp_byte_count) / 1000);
187+
}
188+
last_timestamp_byte_count = current_time;
189+
if (!isNaN(bytes) && bytes > 1000000) {
190+
document.getElementById("read_bytes").innerHTML = (bytes / 1000000).toFixed(3) + " MB (" + ((bytes_per_second*8)/1000).toFixed(2) + " kbit/s)"
191+
} else if (!isNaN(bytes) && bytes > 1000) {
192+
document.getElementById("read_bytes").innerHTML = (bytes / 1000).toFixed(2) + " kB (" + ((bytes_per_second*8)/1000).toFixed(2) + " kbit/s)"
182193
} else if (!isNaN(bytes)) {
183-
document.getElementById("read_bytes").innerHTML = bytes + " bytes"
194+
document.getElementById("read_bytes").innerHTML = bytes + " bytes (" + Math.round(bytes_per_second) + " byte/s)"
184195
}
196+
last_byte_count = bytes;
185197

186198
let tcp_clients = parseInt(json_data["tcp_connected"])
187199
if (!isNaN(tcp_clients) && tcp_clients === 1) {

frontend/index.html

+5-1
Original file line numberDiff line numberDiff line change
@@ -165,7 +165,7 @@ <h3>Serial</h3>
165165
</div>
166166
</div>
167167
<div id="trans_pack_size_div" class="row">
168-
<div class="twelve columns">
168+
<div class="six columns">
169169
<label for="trans_pack_size">Maximum packet size</label>
170170
<select id="trans_pack_size" name="trans_pack_size" form="settings_form">
171171
<option value="16">16</option>
@@ -177,6 +177,10 @@ <h3>Serial</h3>
177177
<option value="768">768</option>
178178
</select>
179179
</div>
180+
<div class="six columns">
181+
<label for="serial_timeout">Serial read timeout [ms]</label>
182+
<input type="number" id="serial_timeout" name="serial_timeout" min="1" max="65535" value="50">
183+
</div>
180184
</div>
181185
<div class="row">
182186
<div class="six columns" id="ap_ip_div">

main/db_esp32_control.c

+47-14
Original file line numberDiff line numberDiff line change
@@ -193,7 +193,7 @@ int db_open_int_telemetry_udp_socket() {
193193
* @param data Buffer with the data to send
194194
* @param data_length Length of the data in the buffer
195195
*/
196-
void send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *data, uint data_length) {
196+
void db_send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *data, uint data_length) {
197197
for (int i = 0; i < n_udp_conn_list->size; i++) { // send to all UDP clients
198198
int sent = sendto(n_udp_conn_list->udp_socket, data, data_length, 0,
199199
(struct sockaddr *) &n_udp_conn_list->db_udp_clients[i].udp_client,
@@ -206,30 +206,63 @@ void send_to_all_udp_clients(udp_conn_list_t *n_udp_conn_list, const uint8_t *da
206206
}
207207

208208
/**
209+
* 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
210+
* and finally send it over the air)
211+
*
212+
* @param data Pointer to the payload buffer
213+
* @param data_length Length of the payload data. Must not be bigger than DB_ESPNOW_PAYLOAD_MAXSIZE - fails otherwise
214+
*/
215+
void db_send_to_all_espnow(uint8_t data[], const uint16_t *data_length) {
216+
db_espnow_queue_event_t evt;
217+
evt.data = malloc(*data_length);
218+
memcpy(evt.data, data, *data_length);
219+
evt.data_len = *data_length;
220+
evt.packet_type = DB_ESP_NOW_PACKET_TYPE_DATA;
221+
if (xQueueSend(db_espnow_send_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
222+
ESP_LOGW(TAG, "Send to db_espnow_send_queue queue fail");
223+
free(evt.data);
224+
} else {
225+
// all good
226+
}
227+
}
228+
229+
/**
230+
* Main call for sending anything over the air.
209231
* Send to all connected TCP & UDP clients or broadcast via ESP-NOW depending on the mode (DB_WIFI_MODE) we are currently in.
210232
* Typically called by a function that read from UART.
211233
*
234+
* When in ESP-NOW mode the packets will be split if they are bigger than DB_ESPNOW_PAYLOAD_MAXSIZE.
235+
*
212236
* @param tcp_clients Array of socket IDs for the TCP clients
213237
* @param udp_conn Structure handling the UDP connection
214238
* @param data payload to send
215239
* @param data_length Length of payload to send
216240
*/
217-
void send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint data_length) {
241+
void db_send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint16_t data_length) {
218242
if (DB_WIFI_MODE != DB_WIFI_MODE_ESPNOW_AIR && DB_WIFI_MODE != DB_WIFI_MODE_ESPNOW_GND) {
219-
send_to_all_tcp_clients(tcp_clients, data, data_length);
220-
send_to_all_udp_clients(n_udp_conn_list, data, data_length);
243+
db_send_to_all_tcp_clients(tcp_clients, data, data_length);
244+
db_send_to_all_udp_clients(n_udp_conn_list, data, data_length);
221245
} else {
222246
// ESP-NOW mode
223-
db_espnow_queue_event_t evt;
224-
evt.data = malloc(data_length);
225-
memcpy(evt.data, data, data_length);
226-
evt.data_len = data_length;
227-
evt.packet_type = DB_ESP_NOW_PACKET_TYPE_DATA;
228-
if (xQueueSend(db_espnow_send_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
229-
ESP_LOGW(TAG, "Send to db_espnow_send_queue queue fail");
230-
free(evt.data);
247+
// Check if payload fits into one ESP-NOW packet
248+
if (data_length > DB_ESPNOW_PAYLOAD_MAXSIZE) {
249+
// data not properly sized (MAVLink implementation already sends properly sized chunks but MSP parser will not)
250+
// split into multiple packets
251+
uint16_t sent_bytes = 0;
252+
uint16_t next_chunk_len = 0;
253+
do {
254+
next_chunk_len = data_length - sent_bytes;
255+
if (next_chunk_len > DB_ESPNOW_PAYLOAD_MAXSIZE) {
256+
next_chunk_len = DB_ESPNOW_PAYLOAD_MAXSIZE;
257+
} else {
258+
// do nothing - chunk will fit into the ESP-NOW payload field
259+
}
260+
db_send_to_all_espnow(&data[sent_bytes], &next_chunk_len);
261+
sent_bytes += next_chunk_len;
262+
} while (sent_bytes < data_length);
231263
} else {
232-
// all good
264+
// packet is properly sized - send to ESP-NOW outbound queue
265+
db_send_to_all_espnow(data, &data_length);
233266
}
234267
}
235268
}
@@ -416,7 +449,7 @@ _Noreturn void control_module_esp_now(){
416449
if (db_uart_write_queue != NULL && xQueueReceive(db_uart_write_queue, &db_espnow_uart_evt, 0) == pdTRUE) {
417450
if (DB_SERIAL_PROTOCOL == DB_SERIAL_PROTOCOL_MAVLINK) {
418451
// Parse, so we can listen in and react to certain messages - function will send parsed messages to serial link.
419-
// 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
452+
// 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
420453
db_parse_mavlink_from_radio(NULL, NULL, db_espnow_uart_evt.data, db_espnow_uart_evt.data_len);
421454
} else {
422455
// no parsing with any other protocol - transparent here - just pass through

main/db_esp32_control.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ void control_module();
5454
udp_conn_list_t *udp_client_list_create();
5555
void udp_client_list_destroy(udp_conn_list_t *n_udp_conn_list);
5656
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);
57-
void send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint data_length);
57+
void db_send_to_all_clients(int tcp_clients[], udp_conn_list_t *n_udp_conn_list, uint8_t data[], uint16_t data_length);
5858
bool remove_from_known_udp_clients(udp_conn_list_t *n_udp_conn_list, struct db_udp_client_t new_db_udp_client);
5959

6060
#endif //DB_ESP32_DB_ESP32_CONTROL_H

main/db_esp_now.c

+1-1
Original file line numberDiff line numberDiff line change
@@ -544,7 +544,7 @@ esp_err_t db_espnow_init() {
544544
if (!esp_now_is_peer_exist(BROADCAST_MAC)) ESP_ERROR_CHECK(esp_now_add_peer(&peer));
545545

546546
/* Limit payload size to the max we can do */
547-
if (DB_TRANS_BUF_SIZE > DB_ESPNOW_PAYLOAD_MAXSIZE) {
547+
if (DB_TRANS_BUF_SIZE > DB_ESPNOW_PAYLOAD_MAXSIZE || DB_TRANS_BUF_SIZE < 1) {
548548
DB_TRANS_BUF_SIZE = DB_ESPNOW_PAYLOAD_MAXSIZE;
549549
} else {
550550
// all good

main/db_mavlink_msgs.c

+18-4
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@
2828

2929
#define TAG "DB_MAV_MSGS"
3030

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

3333
/**
3434
* Based on the system architecture and configured wifi mode the ESP32 may have a different role and system id.
@@ -129,6 +129,9 @@ MAV_TYPE db_mav_get_parameter_value(float_int_union *float_int, char *param_id,
129129
} else if (strncmp(param_id, "SERIAL_RTS_THRES", 16) == 0 || param_index == 10) {
130130
float_int->uint8 = DB_UART_RTS_THRESH;
131131
type = MAV_PARAM_TYPE_UINT8;
132+
} else if (strncmp(param_id, "SERIAL_T_OUT_MS", 16) == 0 || param_index == 11) {
133+
float_int->uint16 = DB_SERIAL_READ_TIMEOUT_MS;
134+
type = MAV_PARAM_TYPE_UINT16;
132135
} else {
133136
type = 0;
134137
}
@@ -162,6 +165,13 @@ bool db_write_mavlink_parameter(fmav_param_set_t *param_set_payload) {
162165
} else {
163166
ESP_LOGE(TAG, "SERIAL_PACK_SIZE must be <1024 bytes");
164167
}
168+
} else if (strncmp(param_set_payload->param_id, "SERIAL_T_OUT_MS", 16) == 0) {
169+
if (float_int.uint16 > 0) {
170+
DB_SERIAL_READ_TIMEOUT_MS = float_int.uint16;
171+
success = true;
172+
} else {
173+
ESP_LOGE(TAG, "SERIAL_T_OUT_MS must be >0 MS");
174+
}
165175
} else if (strncmp(param_set_payload->param_id, "SERIAL_BAUD", 16) == 0) {
166176
DB_UART_BAUD_RATE = float_int.int32;
167177
success = true;
@@ -350,7 +360,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
350360
uint16_t len = fmav_msg_radio_status_encode_to_frame_buf(buff, db_get_mav_sys_id(),
351361
db_get_mav_comp_id(), &payload_r,
352362
fmav_status);
353-
send_to_all_clients(tcp_clients, udp_conns, buff, len);
363+
db_send_to_all_clients(tcp_clients, udp_conns, buff, len);
354364
} else if (DB_WIFI_MODE == DB_WIFI_MODE_AP && wifi_sta_list.num > 0) {
355365
// we assume ESP32 is not used in DB_WIFI_MODE_AP on the ground but only on the drone side
356366
// ToDo: Only the RSSI of the first client is considered.
@@ -359,7 +369,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
359369
uint16_t len = fmav_msg_radio_status_encode_to_frame_buf(buff, db_get_mav_sys_id(),
360370
db_get_mav_comp_id(), &payload_r,
361371
fmav_status);
362-
send_to_all_clients(tcp_clients, udp_conns, buff, len);
372+
db_send_to_all_clients(tcp_clients, udp_conns, buff, len);
363373
} else {
364374
// In AP LR mode the clients will send the info to the GCS
365375
}
@@ -369,7 +379,7 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
369379
// ToDo: Check if that is a good idea or push to extra thread
370380
uint16_t length = db_create_heartbeat(buff, fmav_status);
371381
// Send heartbeat to GND clients: Every ESP32 no matter its role or mode is emitting a heartbeat
372-
send_to_all_clients(tcp_clients, udp_conns, buff, length);
382+
db_send_to_all_clients(tcp_clients, udp_conns, buff, length);
373383
} // do not react to heartbeats received via wireless interface - reaction to serial is sufficient
374384
break;
375385
case FASTMAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
@@ -419,6 +429,10 @@ void handle_mavlink_message(fmav_message_t *new_msg, int *tcp_clients, udp_conn_
419429
float_int.uint8 = DB_UART_RTS_THRESH;
420430
len = db_get_mavmsg_param(buff, fmav_status, 10, &float_int, MAV_PARAM_TYPE_UINT8, "SERIAL_RTS_THRES");
421431
db_route_mavlink_response(buff, len, origin, tcp_clients, udp_conns);
432+
433+
float_int.uint16 = DB_SERIAL_READ_TIMEOUT_MS;
434+
len = db_get_mavmsg_param(buff, fmav_status, 11, &float_int, MAV_PARAM_TYPE_UINT16, "SERIAL_T_OUT_MS");
435+
db_route_mavlink_response(buff, len, origin, tcp_clients, udp_conns);
422436
}
423437
break;
424438
case FASTMAVLINK_MSG_ID_PARAM_REQUEST_READ: {

0 commit comments

Comments
 (0)