Skip to content

Commit

Permalink
Added reset button, broadcast ESPNOW seems to be working, to be tested
Browse files Browse the repository at this point in the history
  • Loading branch information
seeul8er committed Apr 21, 2024
1 parent 0b7ad16 commit 1ab7508
Show file tree
Hide file tree
Showing 8 changed files with 564 additions and 431 deletions.
2 changes: 1 addition & 1 deletion frontend/index.html
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ <h3>Wi-Fi</h3>
<option value="4">ESP-NOW LR Mode AIR</option>
<option value="5">ESP-NOW LR Mode GND</option>
</select>
<div id="esp-lr-ap-disclaimer" style="color: #ff881a; margin-bottom: 0.8rem">LR Mode makes the device invisible for non-LR enabled devices!</br>You will not be able to change the config!</br>Data rate is reduced to ~0.25Mbps. Range may be increase by a factor of ~2.</br>You will have to manually erase the flash memory of the ESP32 and re-flash DroneBridge for ESP32 to get back into normal Wi-Fi Mode!</div>
<div id="esp-lr-ap-disclaimer" style="color: #ff881a; margin-bottom: 0.8rem">LR Mode makes the device invisible for non-LR enabled devices!</br>You will not be able to change the config!</br>Data rate is reduced to ~0.25Mbps. Range may be increase by a factor of ~2.</br>Press boot button (short press for AP-Mode with password "dronebridge" or long press for reset to defaults) or erase the flash memory of the ESP32 and re-flash DroneBridge for ESP32 to get back into normal Wi-Fi Mode!</div>
</div>
</div>
<div class="row">
Expand Down
3 changes: 2 additions & 1 deletion main/db_esp32_control.c
Original file line number Diff line number Diff line change
Expand Up @@ -279,10 +279,11 @@ _Noreturn void control_module_esp_now(){
while (1) {
read_process_uart(NULL, &transparent_buff_pos, &msp_ltm_buff_pos, msp_message_buffer, serial_buffer,
&db_msp_ltm_port);
if (xQueueReceive(db_uart_write_queue, &db_uart_evt, 0) == pdTRUE) {
if (db_uart_write_queue != NULL && xQueueReceive(db_uart_write_queue, &db_uart_evt, 0) == pdTRUE) {
write_to_uart(db_uart_evt.data, db_uart_evt.data_len);
free(db_uart_evt.data);
} else {
if (db_uart_write_queue == NULL) ESP_LOGE(TAG, "db_uart_write_queue is NULL!");
// no new data available do nothing
}
if (delay_timer_cnt == 5000) {
Expand Down
76 changes: 48 additions & 28 deletions main/db_esp_now.c
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,26 @@ void generate_pkcs5_key(const char* password, unsigned char* key, size_t keylen)
mbedtls_md_free(&mdctx);
}

/**
* NOT USED for now!
* Adds a ESPNOW peer for an encrypted point to point connection. The other esp32 has to add this device as peer as well
* Call only after ESPNOW was inited.
* @param mac The peers MAC address
* @param lmk The local 16 byte master key for encrypting the point to point connection. LMKs must match on both ESP32 devices.
*/
void db_add_espnow_peer(uint8_t *mac, uint8_t *lmk){
esp_now_peer_info_t peer;
memset(&peer, 0, sizeof(esp_now_peer_info_t));
memcpy(peer.peer_addr, mac, ESP_NOW_ETH_ALEN);
memcpy(peer.lmk, lmk, ESP_NOW_KEY_LEN);
peer.encrypt = true;
if (!esp_now_is_peer_exist(mac)) {
ESP_ERROR_CHECK(esp_now_add_peer(&peer));
} else {
ESP_LOGW(TAG, "Peer already exists. Not adding to list");
}
}

/**
* Encrypts and authenticates a DroneBridge for ESP32 ESP-NOW packet with its payload using AES-GCM 256
* Beware we are using the same key for both communication directions.
Expand Down Expand Up @@ -146,7 +166,7 @@ int db_encrypt_payload(db_esp_now_packet_t* db_esp_now_packet, uint8_t encrypt_p
* @param len_encrypted_data length of the buffer (db_esp_now_packet_protected_data)
* @return returns result of mbedtls_gcm_auth_decrypt e.g. 0 on success and valid data
*/
int db_decrypt_payload(db_esp_now_packet_t* db_esp_now_packet, db_esp_now_packet_protected_data_t* decrypt_out_buffer,
int db_decrypt_payload(db_esp_now_packet_t* db_esp_now_packet, uint8_t* decrypt_out_buffer,
uint8_t len_encrypted_data) {
int ret_decrypt = mbedtls_gcm_auth_decrypt(
&aes,
Expand All @@ -155,7 +175,7 @@ int db_decrypt_payload(db_esp_now_packet_t* db_esp_now_packet, db_esp_now_packet
(uint8_t*) &db_esp_now_packet->db_esp_now_packet_header, size_packet_header,
db_esp_now_packet->tag, DB_ESPNOW_AES_TAG_LEN,
(uint8_t*) &db_esp_now_packet->db_esp_now_packet_protected_data,
(uint8_t*) decrypt_out_buffer
decrypt_out_buffer
);
switch (ret_decrypt) {
case 0:
Expand Down Expand Up @@ -183,7 +203,7 @@ bool db_read_uart_queue_and_send() {
.db_esp_now_packet_header.seq_num = 0,
.db_esp_now_packet_header.packet_type = 0
}; // make static so it is gets instanced only once
if (xQueueReceive(db_espnow_send_queue, &evt, 0) == pdTRUE) {
if (db_espnow_send_queue != NULL && xQueueReceive(db_espnow_send_queue, &evt, 0) == pdTRUE) {
if (DB_WIFI_MODE == DB_WIFI_MODE_ESPNOW_GND) {
db_esp_now_packet.db_esp_now_packet_header.origin = DB_ESPNOW_ORIGIN_GND;
} else {
Expand Down Expand Up @@ -215,7 +235,12 @@ bool db_read_uart_queue_and_send() {
return false;
}
} else {
// nothing to do - Queue is empty
if (db_espnow_send_queue == NULL) {
ESP_LOGE(TAG, "db_espnow_send_queue is NULL!");
} else {
// nothing to do - Queue is empty
}

}
return false;
}
Expand All @@ -235,19 +260,23 @@ bool db_read_uart_queue_and_send() {
void db_espnow_process_rcv_data(uint8_t *data, uint16_t data_len, uint8_t *src_addr) {
db_esp_now_packet_t *db_esp_now_packet = (db_esp_now_packet_t *) data;
static uint32_t last_seq_num = 0;
uint8_t len_payload = data_len - DB_ESPNOW_AES_TAG_LEN - size_packet_header;
uint8_t db_decrypted_data[len_payload];

static db_espnow_UART_event_t db_uart_evt;
db_uart_evt.data = malloc(DB_ESPNOW_PAYLOAD_MAXSIZE);
// cast from db_espnow_UART_event_t to db_esp_now_packet_protected_data_t possible because byte equal!
if (db_decrypt_payload(db_esp_now_packet, (db_esp_now_packet_protected_data_t *) &db_uart_evt, data_len) == 0) {
if (db_decrypt_payload(db_esp_now_packet, db_decrypted_data, len_payload) == 0) {
if (last_seq_num < db_esp_now_packet->db_esp_now_packet_header.seq_num) {
// all good and as expected
} else {
ESP_LOGW(TAG, "Sequence number lower than expected. Sender did reset or packet may be part of a replay attack.");
// accept packet anyway for now to make for a more robust link
}
last_seq_num = db_esp_now_packet->db_esp_now_packet_header.seq_num;

// Pass data to UART queue
db_espnow_UART_event_t db_uart_evt;
db_uart_evt.data = malloc(len_payload - 1);
// For some reason it seems we cannot directly decrypt to db_espnow_UART_event_t -> Queues get set to NULL
memcpy(db_uart_evt.data, db_decrypted_data, len_payload - 1);
if (xQueueSend(db_uart_write_queue, &db_uart_evt, ESPNOW_MAXDELAY) != pdTRUE) {
ESP_LOGW(TAG, "Send to db_uart_write_queue failed");
free(db_uart_evt.data);
Expand Down Expand Up @@ -329,22 +358,22 @@ static void db_esp_now_receive_callback(const esp_now_recv_info_t *recv_info, co
}
memcpy(recv_cb->data, data, len);
recv_cb->data_len = len;
if (xQueueSend(db_espnow_send_recv_callback_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
if (db_espnow_send_recv_callback_queue != NULL && xQueueSend(db_espnow_send_recv_callback_queue, &evt, ESPNOW_MAXDELAY) != pdTRUE) {
ESP_LOGW(TAG, "Send to receive queue fail");
free(recv_cb->data);
}
}

/**
* Init mbedtls aes gcm mode and set encryption key based on the WiFi password specified by the user
* @param aes_key buffer for saving the generated aes key of len AES_256_KEY_BYTES
* @return result of mbedtls_gcm_setkey
*/
int init_gcm_encryption_module() {
int init_gcm_encryption_module(uint8_t *aes_key) {
mbedtls_gcm_init(&aes);
uint8_t aes_key[AES_256_KEY_BYTES];
generate_pkcs5_key((const char*) DB_WIFI_PWD, aes_key, AES_256_KEY_BYTES);
ESP_LOGI(TAG, "Derived AES Key:");
for (int i = 0; i < sizeof(aes_key); ++i) {
for (int i = 0; i < AES_256_KEY_BYTES; ++i) {
printf("%02x", aes_key[i]);
}
printf("\n");
Expand All @@ -353,6 +382,7 @@ int init_gcm_encryption_module() {
}

void deinit_espnow_all(){
ESP_LOGW(TAG, "De init ESPNOW incl. Queues & AES");
mbedtls_gcm_free(&aes);
vSemaphoreDelete(db_espnow_send_recv_callback_queue);
vSemaphoreDelete(db_espnow_send_queue); // ToDo: Check if that is a good idea since control task might be using it
Expand Down Expand Up @@ -396,20 +426,6 @@ esp_err_t db_espnow_init() {
memcpy(peer.peer_addr, BROADCAST_MAC, 6);
if (!esp_now_is_peer_exist(BROADCAST_MAC)) ESP_ERROR_CHECK(esp_now_add_peer(&peer));

// esp_now_peer_info_t *peer = malloc(sizeof(esp_now_peer_info_t));
// if (peer == NULL) {
// ESP_LOGE(TAG, "Malloc peer information fail");
// deinit_espnow_all();
// return ESP_FAIL;
// }
// memset(peer, 0, sizeof(esp_now_peer_info_t));
// peer->channel = DB_WIFI_CHANNEL;
// peer->ifidx = WIFI_IF_STA;
// peer->encrypt = false;
// memcpy(peer->peer_addr, BROADCAST_MAC, ESP_NOW_ETH_ALEN);
// ESP_ERROR_CHECK(esp_now_add_peer(peer));
// free(peer);

/* Limit payload size to the max we can do */
if (DB_TRANS_BUF_SIZE > DB_ESPNOW_PAYLOAD_MAXSIZE) {
DB_TRANS_BUF_SIZE = DB_ESPNOW_PAYLOAD_MAXSIZE;
Expand All @@ -418,12 +434,15 @@ esp_err_t db_espnow_init() {
}

/* Init AES GCM encryption module */
int ret = init_gcm_encryption_module();
uint8_t aes_key[AES_256_KEY_BYTES];
int ret = init_gcm_encryption_module(aes_key);
if (ret != 0) {
ESP_LOGE(TAG, "mbedtls_gcm_setkey returned an error: %i", ret);
deinit_espnow_all();
return ESP_FAIL;
}
ESP_ERROR_CHECK(esp_now_set_pmk(aes_key)); // only first 16 bytes will be used

ESP_LOGI(TAG, "ESP-NOW for DroneBridge init done");
return ESP_OK;
}
Expand All @@ -445,7 +464,8 @@ _Noreturn void process_espnow_data() {
bool ready_to_send = true; // initially true
int delay_timer_cnt = 0;
while(1) {
if(xQueueReceive(db_espnow_send_recv_callback_queue, &evt, 0) == pdTRUE) {
if (db_espnow_send_recv_callback_queue == NULL) ESP_LOGE(TAG, "db_espnow_send_recv_callback_queue is NULL!");
if(db_espnow_send_recv_callback_queue != NULL && xQueueReceive(db_espnow_send_recv_callback_queue, &evt, 0) == pdTRUE) {
switch (evt.id) {
case DB_ESPNOW_SEND_CB: {
db_espnow_event_send_cb_t *send_cb = &evt.info.send_cb;
Expand Down
8 changes: 6 additions & 2 deletions main/db_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -84,10 +84,14 @@ esp_err_t open_serial_socket() {
*/
void write_to_uart(const uint8_t data_buffer[], const unsigned int data_length) {
int written = uart_write_bytes(UART_NUM, data_buffer, data_length);
if (written > 0)
if (written > 0) {
ESP_LOGD(TAG, "Wrote %i bytes to UART", written);
else
} else if (written == 0) {
ESP_LOGW(TAG, "Wrote 0 bytes to UART (%s) - Check if UART is connected.", esp_err_to_name(errno));
} else {
ESP_LOGE(TAG, "Error writing to UART %s", esp_err_to_name(errno));
}

}

/**
Expand Down
1 change: 1 addition & 0 deletions main/idf_component.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
## IDF Component Manager Manifest File
dependencies:
espressif/button: "^3.2.0"
espressif/esp-now: "^2.5.1"
espressif/mdns: "^1.2.2"
## Required IDF version
Expand Down
97 changes: 68 additions & 29 deletions main/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include "main.h"
#include "mdns.h"
#include "db_esp_now.h"
#include "iot_button.h"

#define NVS_NAMESPACE "settings"

Expand All @@ -60,7 +61,19 @@ uint8_t DB_UART_PIN_RX = GPIO_NUM_0;
uint8_t DB_UART_PIN_RTS = GPIO_NUM_0;
uint8_t DB_UART_PIN_CTS = GPIO_NUM_0;
uint8_t DB_UART_RTS_THRESH = 64;
uint8_t DB_RESET_PIN = GPIO_NUM_0; // used to reset ESP to defaults and force restart

/* used to reset ESP to defaults and force restart or to reset the mode to access point mode */
#ifdef CONFIG_IDF_TARGET_ESP32C3
#define DB_RESET_PIN GPIO_NUM_9
#elif CONFIG_IDF_TARGET_ESP32S2
#define DB_RESET_PIN GPIO_NUM_0
#elif CONFIG_IDF_TARGET_ESP32S3
#define DB_RESET_PIN GPIO_NUM_0
#elif CONFIG_IDF_TARGET_ESP32
#define DB_RESET_PIN GPIO_NUM_0
#else
#define DB_RESET_PIN GPIO_NUM_0
#endif

int32_t DB_UART_BAUD_RATE = 57600;
uint16_t DB_TRANS_BUF_SIZE = 64;
Expand Down Expand Up @@ -333,7 +346,10 @@ int init_wifi_clientmode() {
}

/**
* Initialize WiFi for ESP-NOW mode
* Initialize WiFi for ESP-NOW mode.
* If someone uses ESP-NOW over WiFi it is because he wants range over everything else.
* LR mode makes it very inconvenient to change settings but gives the most range. No AP mode since AP will not be
* visible.
*/
void init_wifi_espnow() {
ESP_LOGI(TAG, "Setting up Wi-Fi for ESP-NOW");
Expand Down Expand Up @@ -436,45 +452,68 @@ void read_settings_nvs() {
}

/**
* Interrupt trigger called when RESET button is pressed. Will reset the config to DroneBridge for ESP32 defaults.
* Callback for a short press (<CONFIG_BUTTON_SHORT_PRESS_TIME_MS) of the reset/boot button.
* Sets mode to WiFi access point mode with default password "dronebridge" so user can check/change the config
* @param arg
*/
static void IRAM_ATTR gpio_isr_handler(void* arg)
{
uint32_t gpio_num = (uint32_t) arg;
if (gpio_num == DB_RESET_PIN) {
ESP_LOGW(TAG, "Reset triggered via GPIO %i. Resetting settings and rebooting", DB_RESET_PIN);
DB_WIFI_MODE = DB_WIFI_MODE_AP;
strncpy((char *) DB_WIFI_SSID, "DroneBridge for ESP32", sizeof(DB_WIFI_SSID) - 1);
strncpy((char *) DB_WIFI_PWD, "dronebridge", sizeof(DB_WIFI_PWD) - 1);
strncpy(DEFAULT_AP_IP, "192.168.2.1", sizeof(DEFAULT_AP_IP) - 1);
DB_WIFI_CHANNEL = 6;
DB_UART_PIN_TX = GPIO_NUM_0;
DB_UART_PIN_RX = GPIO_NUM_0;
DB_UART_PIN_CTS = GPIO_NUM_0;
DB_UART_PIN_RTS = GPIO_NUM_0;
DB_SERIAL_PROTOCOL = 4;
DB_TRANS_BUF_SIZE = 64;
DB_UART_RTS_THRESH = 64;
esp_restart();
}
void short_press_callback(void *arg,void *usr_data) {
ESP_LOGW(TAG, "Short press detected setting wifi mode to access point with password: dronebridge");
DB_WIFI_MODE = DB_WIFI_MODE_AP;
strncpy((char *) DB_WIFI_PWD, "dronebridge", sizeof(DB_WIFI_PWD) - 1);
write_settings_to_nvs();
esp_restart();
}

/**
* Callback for a long press (>CONFIG_BUTTON_LONG_PRESS_TIME_MS) of the reset/boot button
* @param arg
*/
void long_press_callback(void *arg,void *usr_data) {
ESP_LOGW(TAG, "Reset triggered via GPIO %i. Resetting settings and rebooting", DB_RESET_PIN);
DB_WIFI_MODE = DB_WIFI_MODE_AP;
strncpy((char *) DB_WIFI_SSID, "DroneBridge for ESP32", sizeof(DB_WIFI_SSID) - 1);
strncpy((char *) DB_WIFI_PWD, "dronebridge", sizeof(DB_WIFI_PWD) - 1);
strncpy(DEFAULT_AP_IP, "192.168.2.1", sizeof(DEFAULT_AP_IP) - 1);
DB_WIFI_CHANNEL = 6;
DB_UART_PIN_TX = GPIO_NUM_0;
DB_UART_PIN_RX = GPIO_NUM_0;
DB_UART_PIN_CTS = GPIO_NUM_0;
DB_UART_PIN_RTS = GPIO_NUM_0;
DB_SERIAL_PROTOCOL = 4;
DB_TRANS_BUF_SIZE = 64;
DB_UART_RTS_THRESH = 64;
write_settings_to_nvs();
esp_restart();
}

/**
* Setup boot button GPIO to reset entire ESP32 settings and to force a reboot of the system
*/
void set_reset_trigger() {
// ToDo: Setup boot button GPIO to reset entire ESP32 settings and to force a reboot of the system
// gpio_set_intr_type(DB_RESET_PIN, GPIO_INTR_ANYEDGE);
// ESP_ERROR_CHECK(gpio_install_isr_service(ESP_INTR_FLAG_DEFAULT));
// ESP_ERROR_CHECK(gpio_isr_handler_add(DB_RESET_PIN, gpio_isr_handler, (void *) DB_RESET_PIN));
button_config_t gpio_btn_cfg = {
.type = BUTTON_TYPE_GPIO,
.long_press_time = CONFIG_BUTTON_LONG_PRESS_TIME_MS,
.short_press_time = CONFIG_BUTTON_SHORT_PRESS_TIME_MS,
.gpio_button_config = {
.gpio_num = DB_RESET_PIN,
.active_level = 0,
},
};
button_handle_t gpio_btn = iot_button_create(&gpio_btn_cfg);
if(NULL == gpio_btn) {
ESP_LOGE(TAG, "Creating reset button failed");
} else {
iot_button_register_cb(gpio_btn, BUTTON_SINGLE_CLICK, short_press_callback,NULL);
iot_button_register_cb(gpio_btn, BUTTON_LONG_PRESS_UP, long_press_callback,NULL);
}
}

/**
* Main entry point.
* Client Mode: ESP32 connects to a known access point.
* If the ESP32 could not connect to the specified access point using WIFI_ESP_MAXIMUM_RETRY retries, the
* ESP32 will switch temporarily to access point mode to allow the user to check the configuration. On reboot of the
* ESP32 the WiFi client mode will be re-enabled if not changed otherwise by the user.
* If the ESP32 could not connect to the specified access point using WIFI_ESP_MAXIMUM_RETRY retries, the
* ESP32 will switch temporarily to access point mode to allow the user to check the configuration. On reboot of the
* ESP32 the WiFi client mode will be re-enabled if not changed otherwise by the user.
*
* AP-Mode: ESP32 creates an WiFi access point of its own where the ground control stations can connect
*/
Expand Down
Loading

0 comments on commit 1ab7508

Please sign in to comment.