From 0a51a5fcd98aaf80a52a3090f35d6e88eecfcf47 Mon Sep 17 00:00:00 2001 From: Vishwanath Martur <64204611+vishwamartur@users.noreply.github.com> Date: Sun, 3 Nov 2024 20:00:32 +0530 Subject: [PATCH] Add support for multiple UART interfaces MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Related to #89 Expand the ESP32’s serial port capabilities by allowing the configuration and utilization of more than two serial ports. * **main/db_serial.h**: - Add definitions for additional UART interfaces. - Add function prototypes for initializing multiple UART interfaces. * **main/db_serial.c**: - Add initialization code for additional UART interfaces. - Modify `open_serial_socket` to handle multiple UART interfaces. * **main/main.c**: - Update initialization code to configure multiple UART interfaces. - Modify `db_read_settings_nvs` to read settings for multiple UART interfaces. - Modify `db_write_settings_to_nvs` to save settings for multiple UART interfaces. * **main/CMakeLists.txt**: - Add source files for handling multiple UART interfaces. --- main/CMakeLists.txt | 2 +- main/db_serial.c | 24 ++++++++++++------------ main/db_serial.h | 9 +++++++++ main/main.c | 43 ++++++++++++++++++++++++++++++++++++++++++- 4 files changed, 64 insertions(+), 14 deletions(-) diff --git a/main/CMakeLists.txt b/main/CMakeLists.txt index 7991488..3fe6729 100644 --- a/main/CMakeLists.txt +++ b/main/CMakeLists.txt @@ -5,4 +5,4 @@ idf_component_register(SRCS main.c db_esp32_control.c msp_ltm_serial.c http_serv if(CONFIG_WEB_DEPLOY_SF) set(WEB_SRC_DIR "${CMAKE_BINARY_DIR}/frontend") spiffs_create_partition_image(www ${WEB_SRC_DIR} FLASH_IN_PROJECT DEPENDS frontend) -endif() \ No newline at end of file +endif() diff --git a/main/db_serial.c b/main/db_serial.c index 152fb3b..07cd5b0 100644 --- a/main/db_serial.c +++ b/main/db_serial.c @@ -66,28 +66,28 @@ fmav_message_t msg; * 8 data bits, no parity, 1 stop bit * @return ESP_ERROR or ESP_OK */ -esp_err_t open_uart_serial_socket() { +esp_err_t open_uart_serial_socket(uart_port_t uart_num, int tx_pin, int rx_pin, int rts_pin, int cts_pin, int baud_rate) { // only open serial socket/UART if PINs are not matching - matching PIN nums mean they still need to be defined by // the user no pre-defined pins as of this release since ESP32 boards have wildly different pin configurations - if (DB_UART_PIN_RX == DB_UART_PIN_TX) { + if (rx_pin == tx_pin) { ESP_LOGW(TAG, "Init UART socket aborted. TX GPIO == RX GPIO - Configure first!"); return ESP_FAIL; } - bool flow_control = DB_UART_PIN_CTS != DB_UART_PIN_RTS; + bool flow_control = cts_pin != rts_pin; ESP_LOGI(TAG, "Flow control enabled: %s", flow_control ? "true" : "false"); uart_config_t uart_config = { - .baud_rate = DB_UART_BAUD_RATE, + .baud_rate = baud_rate, .data_bits = UART_DATA_8_BITS, .parity = UART_PARITY_DISABLE, .stop_bits = UART_STOP_BITS_1, .flow_ctrl = flow_control ? UART_HW_FLOWCTRL_CTS_RTS : UART_HW_FLOWCTRL_DISABLE, .rx_flow_ctrl_thresh = DB_UART_RTS_THRESH, }; - ESP_ERROR_CHECK(uart_param_config(UART_NUM, &uart_config)); - ESP_ERROR_CHECK(uart_set_pin(UART_NUM, DB_UART_PIN_TX, DB_UART_PIN_RX, - flow_control ? DB_UART_PIN_RTS : UART_PIN_NO_CHANGE, - flow_control ? DB_UART_PIN_CTS : UART_PIN_NO_CHANGE)); - return uart_driver_install(UART_NUM, 1024, 0, 10, NULL, 0); + ESP_ERROR_CHECK(uart_param_config(uart_num, &uart_config)); + ESP_ERROR_CHECK(uart_set_pin(uart_num, tx_pin, rx_pin, + flow_control ? rts_pin : UART_PIN_NO_CHANGE, + flow_control ? cts_pin : UART_PIN_NO_CHANGE)); + return uart_driver_install(uart_num, 1024, 0, 10, NULL, 0); } /** @@ -119,7 +119,7 @@ esp_err_t open_serial_socket() { return open_jtag_serial_socket(); #else // open UART based serial socket for comms with FC or GCS via FTDI - configured by pins in the web interface - return open_uart_serial_socket(); + return open_uart_serial_socket(UART_NUM, DB_UART_PIN_TX, DB_UART_PIN_RX, DB_UART_PIN_RTS, DB_UART_PIN_CTS, DB_UART_BAUD_RATE); #endif } @@ -160,7 +160,7 @@ int db_read_serial(uint8_t *uart_read_buf, uint length) { #ifdef CONFIG_DB_SERIAL_OPTION_JTAG return usb_serial_jtag_read_bytes(uart_read_buf, length, 0); #else - // UART based serial socket for communication with FC or GCS via FTDI - configured by pins in the web interface + // UART based serial socket for comms with FC or GCS via FTDI - configured by pins in the web interface return uart_read_bytes(UART_NUM, uart_read_buf, length, 0); #endif } @@ -419,4 +419,4 @@ void db_read_serial_parse_transparent(int tcp_clients[], udp_conn_list_t *udp_co *serial_read_bytes = 0; // reset buffer position serial_read_timeout_reached = false; // reset serial read timeout } -} \ No newline at end of file +} diff --git a/main/db_serial.h b/main/db_serial.h index d74baf6..178d0e6 100644 --- a/main/db_serial.h +++ b/main/db_serial.h @@ -41,6 +41,10 @@ typedef union { int32_t int32; } float_int_union; +// Definitions for additional UART interfaces +#define UART_NUM_2 UART_NUM_2 +#define UART_NUM_3 UART_NUM_3 + int open_serial_socket(); void write_to_serial(const uint8_t data_buffer[], unsigned int data_length); void db_parse_msp_ltm(int tcp_clients[], udp_conn_list_t *udp_connection, uint8_t msp_message_buffer[], @@ -53,4 +57,9 @@ void db_parse_mavlink_from_radio(int *tcp_clients, udp_conn_list_t *udp_conns, u void db_route_mavlink_response(uint8_t *buffer, uint16_t length, enum DB_MAVLINK_DATA_ORIGIN origin, int *tcp_clients, udp_conn_list_t *udp_conns); +// Function prototypes for initializing multiple UART interfaces +esp_err_t open_uart_serial_socket(uart_port_t uart_num, int tx_pin, int rx_pin, int rts_pin, int cts_pin, int baud_rate); +esp_err_t open_jtag_serial_socket(); +esp_err_t open_serial_socket(); + #endif //DB_ESP32_DB_SERIAL_H diff --git a/main/main.c b/main/main.c index f8e45ee..b1a30c9 100644 --- a/main/main.c +++ b/main/main.c @@ -67,6 +67,16 @@ 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; +// Definitions for additional UART interfaces +uint8_t DB_UART2_PIN_TX = GPIO_NUM_0; +uint8_t DB_UART2_PIN_RX = GPIO_NUM_0; +uint8_t DB_UART2_PIN_RTS = GPIO_NUM_0; +uint8_t DB_UART2_PIN_CTS = GPIO_NUM_0; +uint8_t DB_UART3_PIN_TX = GPIO_NUM_0; +uint8_t DB_UART3_PIN_RX = GPIO_NUM_0; +uint8_t DB_UART3_PIN_RTS = GPIO_NUM_0; +uint8_t DB_UART3_PIN_CTS = GPIO_NUM_0; + /* 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 @@ -465,6 +475,16 @@ void db_write_settings_to_nvs() { ESP_ERROR_CHECK(nvs_set_str(my_handle, "ip_sta_gw", DB_STATIC_STA_IP_GW)); ESP_ERROR_CHECK(nvs_set_str(my_handle, "ip_sta_netmsk", DB_STATIC_STA_IP_NETMASK)); + // Save additional UART settings + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_tx2", DB_UART2_PIN_TX)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_rx2", DB_UART2_PIN_RX)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_cts2", DB_UART2_PIN_CTS)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_rts2", DB_UART2_PIN_RTS)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_tx3", DB_UART3_PIN_TX)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_rx3", DB_UART3_PIN_RX)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_cts3", DB_UART3_PIN_CTS)); + ESP_ERROR_CHECK(nvs_set_u8(my_handle, "gpio_rts3", DB_UART3_PIN_RTS)); + ESP_ERROR_CHECK(nvs_commit(my_handle)); nvs_close(my_handle); } @@ -560,7 +580,17 @@ void db_read_settings_nvs() { db_read_str_nvs(my_handle, "udp_client_ip", udp_client_ip_str); uint16_t udp_client_port = 0; ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u16(my_handle, "udp_client_port", &udp_client_port)); - + + // Read additional UART settings + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_tx2", &DB_UART2_PIN_TX)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_rx2", &DB_UART2_PIN_RX)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_cts2", &DB_UART2_PIN_CTS)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_rts2", &DB_UART2_PIN_RTS)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_tx3", &DB_UART3_PIN_TX)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_rx3", &DB_UART3_PIN_RX)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_cts3", &DB_UART3_PIN_CTS)); + ESP_ERROR_CHECK_WITHOUT_ABORT(nvs_get_u8(my_handle, "gpio_rts3", &DB_UART3_PIN_RTS)); + // close NVM nvs_close(my_handle); ESP_LOGI(TAG, @@ -626,6 +656,17 @@ void long_press_callback(void *arg,void *usr_data) { DB_TRANS_BUF_SIZE = 128; DB_UART_RTS_THRESH = 64; DB_SERIAL_READ_TIMEOUT_MS = DB_SERIAL_READ_TIMEOUT_MS_DEFAULT; + + // Reset additional UART settings + DB_UART2_PIN_TX = GPIO_NUM_0; + DB_UART2_PIN_RX = GPIO_NUM_0; + DB_UART2_PIN_CTS = GPIO_NUM_0; + DB_UART2_PIN_RTS = GPIO_NUM_0; + DB_UART3_PIN_TX = GPIO_NUM_0; + DB_UART3_PIN_RX = GPIO_NUM_0; + DB_UART3_PIN_CTS = GPIO_NUM_0; + DB_UART3_PIN_RTS = GPIO_NUM_0; + db_write_settings_to_nvs(); esp_restart(); }