Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_HAL_ESP32: UART driver tweaks and making closer in shape to chibios #28717

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
61 changes: 47 additions & 14 deletions libraries/AP_HAL_ESP32/UARTDriver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,33 +13,67 @@
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include <AP_HAL_ESP32/UARTDriver.h>
#include <AP_HAL/AP_HAL.h>

#include <AP_Math/AP_Math.h>
#include "Semaphores.h"
#include "Scheduler.h"
#include "UARTDriver.h"

#include "esp_log.h"

extern const AP_HAL::HAL& hal;

namespace ESP32
{
#include "rom/ets_sys.h" //for ets_printf
extern int ets_printf(const char* format, ...); //for ets_printf in rom

using namespace ESP32;


UARTDesc uart_desc[] = {HAL_ESP32_UART_DEVICES};

// table to find UARTDrivers from serial number, used for event handling
UARTDriver *UARTDriver::serial_drivers[UART_MAX_DRIVERS];

UARTDriver::UARTDriver(uint8_t serial_num) :
AP_HAL::UARTDriver(),
_serial_num(serial_num)
{
_initialized = false;
if(_serial_num > UART_MAX_DRIVERS) {
// ets is very low level and can't print floats etc
ets_printf("too many UART drivers");
}
serial_drivers[_serial_num] = this;
//no printf allowed in static constructor, not allowed
}

void UARTDriver::vprintf(const char *fmt, va_list ap)
{
// the idea is that no other thread can printf to the console etc till the current one finishes its line/action/etc.
WITH_SEMAPHORE(_sem);

uart_port_t p = uart_desc[uart_num].port;
uart_port_t p = uart_desc[_serial_num].port;
if (p == 0) {
esp_log_writev(ESP_LOG_INFO, "", fmt, ap);
} else {
AP_HAL::UARTDriver::vprintf(fmt, ap);
}
//hal.scheduler->delay_microseconds(10000);// time for hw to flush while holding sem ? todo get rid of this?
}

// disable TX/RX pins for unusued uart
void UARTDriver::disable_rxtx(void) const
{
// nop on esp32. todo?
}

void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
if (uart_num < ARRAY_SIZE(uart_desc)) {
uart_port_t p = uart_desc[uart_num].port;
// hal.console->printf("%s:%d UART num:%d\n", __PRETTY_FUNCTION__, __LINE__,uart_desc[_serial_num].port);

if (_serial_num < ARRAY_SIZE(uart_desc)) {
uart_port_t p = uart_desc[_serial_num].port;
if (!_initialized) {

uart_config_t config = {
Expand All @@ -51,8 +85,8 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
};
uart_param_config(p, &config);
uart_set_pin(p,
uart_desc[uart_num].tx,
uart_desc[uart_num].rx,
uart_desc[_serial_num].tx,
uart_desc[_serial_num].rx,
UART_PIN_NO_CHANGE, UART_PIN_NO_CHANGE);
//uart_driver_install(p, 2*UART_FIFO_LEN, 0, 0, nullptr, 0);
uart_driver_install(p, 2*UART_HW_FIFO_LEN(p), 0, 0, nullptr, 0);
Expand All @@ -72,7 +106,7 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
void UARTDriver::_end()
{
if (_initialized) {
uart_driver_delete(uart_desc[uart_num].port);
uart_driver_delete(uart_desc[_serial_num].port);
_readbuf.set_size(0);
_writebuf.set_size(0);
}
Expand All @@ -81,7 +115,7 @@ void UARTDriver::_end()

void UARTDriver::_flush()
{
uart_port_t p = uart_desc[uart_num].port;
uart_port_t p = uart_desc[_serial_num].port;
uart_flush(p);
}

Expand Down Expand Up @@ -143,7 +177,7 @@ void IRAM_ATTR UARTDriver::_timer_tick(void)

void IRAM_ATTR UARTDriver::read_data()
{
uart_port_t p = uart_desc[uart_num].port;
uart_port_t p = uart_desc[_serial_num].port;
int count = 0;
do {
count = uart_read_bytes(p, _buffer, sizeof(_buffer), 0);
Expand All @@ -155,7 +189,7 @@ void IRAM_ATTR UARTDriver::read_data()

void IRAM_ATTR UARTDriver::write_data()
{
uart_port_t p = uart_desc[uart_num].port;
uart_port_t p = uart_desc[_serial_num].port;
int count = 0;
_write_mutex.take_blocking();
do {
Expand Down Expand Up @@ -184,7 +218,7 @@ size_t IRAM_ATTR UARTDriver::_write(const uint8_t *buffer, size_t size)

bool UARTDriver::_discard_input()
{
//uart_port_t p = uart_desc[uart_num].port;
//uart_port_t p = uart_desc[_serial_num].port;
//return uart_flush_input(p) == ESP_OK;
return false;
}
Expand Down Expand Up @@ -219,4 +253,3 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
return last_receive_us;
}

}
53 changes: 40 additions & 13 deletions libraries/AP_HAL_ESP32/UARTDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,33 +15,32 @@

#pragma once

#include "AP_HAL_ESP32.h"

#include <AP_HAL/UARTDriver.h>
#include <AP_HAL/utility/RingBuffer.h>
#include <AP_HAL_ESP32/AP_HAL_ESP32.h>
#include <AP_HAL_ESP32/Semaphores.h>
#include "Semaphores.h"

#include "driver/gpio.h"
#include "driver/uart.h"

namespace ESP32
{

struct UARTDesc {
uart_port_t port;
gpio_num_t rx;
gpio_num_t tx;
};
#define UART_MAX_DRIVERS 11


class UARTDriver : public AP_HAL::UARTDriver
class ESP32::UARTDriver : public AP_HAL::UARTDriver
{
public:

UARTDriver(uint8_t serial_num)
: AP_HAL::UARTDriver()
{
_initialized = false;
uart_num = serial_num;
}
UARTDriver(uint8_t serial_num);

/* Do not allow copies */
CLASS_NO_COPY(UARTDriver);

virtual ~UARTDriver() = default;

Expand All @@ -59,6 +58,25 @@ class UARTDriver : public AP_HAL::UARTDriver
return 10*1024;
}

// disable TX/RX pins for unusued uart?
void disable_rxtx(void) const override;

// unused stuff from chibios - do we want it in the future?
// struct SerialDef {
// void* serial;
// uint8_t instance;
// bool is_usb;
// uint8_t port;
// uint8_t rx;
// uint8_t tx;
// uint8_t rts_line;
// uint8_t cts_line;
// uint32_t _baudrate;
// uint8_t get_index(void) const {
// return uint8_t(this - &_serial_tab[0]);
// }
// };
//bool lock_port(uint32_t write_key, uint32_t read_key) override;
/*
return timestamp estimate in microseconds for when the start of
a nbytes packet arrived on the uart. This should be treated as a
Expand All @@ -85,7 +103,17 @@ class UARTDriver : public AP_HAL::UARTDriver
void read_data();
void write_data();

uint8_t uart_num;
HAL_Semaphore _sem;

// table to find UARTDrivers from serial number, used for event handling
static UARTDriver *serial_drivers[UART_MAX_DRIVERS];

// unused stuff from chibios - do we want it in the future?
//const SerialDef &sdef;
//static const SerialDef _serial_tab[];

// index into serial_drivers table
uint8_t _serial_num;

// timestamp for receiving data on the UART, avoiding a lock
uint64_t _receive_timestamp[2];
Expand All @@ -104,4 +132,3 @@ class UARTDriver : public AP_HAL::UARTDriver
bool _discard_input() override; // discard all bytes available for reading
};

}
Loading