From b12ccefbe6afd2c8b1743ce7759880ef3b01e9ed Mon Sep 17 00:00:00 2001 From: microDev <70126934+microDev1@users.noreply.github.com> Date: Fri, 19 Feb 2021 18:36:00 +0530 Subject: [PATCH 1/5] uart implementation for rp2040 --- locale/circuitpython.pot | 15 +- ports/raspberrypi/common-hal/busio/UART.c | 464 +++++++--------------- ports/raspberrypi/common-hal/busio/UART.h | 18 +- shared-bindings/busio/UART.c | 8 +- 4 files changed, 175 insertions(+), 330 deletions(-) diff --git a/locale/circuitpython.pot b/locale/circuitpython.pot index 0a79520b88e2..bffc3005cbf9 100644 --- a/locale/circuitpython.pot +++ b/locale/circuitpython.pot @@ -335,6 +335,10 @@ msgstr "" msgid "All UART peripherals are in use" msgstr "" +#: ports/raspberrypi/common-hal/busio/UART.c +msgid "All UART peripherals in use" +msgstr "" + #: ports/atmel-samd/common-hal/audioio/AudioOut.c msgid "All event channels in use" msgstr "" @@ -1277,6 +1281,7 @@ msgstr "" #: ports/mimxrt10xx/common-hal/busio/UART.c ports/nrf/common-hal/busio/I2C.c #: ports/raspberrypi/common-hal/busio/I2C.c #: ports/raspberrypi/common-hal/busio/SPI.c +#: ports/raspberrypi/common-hal/busio/UART.c msgid "Invalid pins" msgstr "" @@ -1824,6 +1829,10 @@ msgstr "" msgid "RS485 inversion specified when not in RS485 mode" msgstr "" +#: ports/raspberrypi/common-hal/busio/UART.c +msgid "RS485 is not supported on this board" +msgstr "" + #: ports/cxd56/common-hal/rtc/RTC.c ports/esp32s2/common-hal/rtc/RTC.c #: ports/mimxrt10xx/common-hal/rtc/RTC.c ports/nrf/common-hal/rtc/RTC.c #: ports/raspberrypi/common-hal/rtc/RTC.c @@ -2124,10 +2133,6 @@ msgstr "" msgid "UART Re-init error" msgstr "" -#: ports/raspberrypi/common-hal/busio/UART.c -msgid "UART not yet supported" -msgstr "" - #: ports/stm/common-hal/busio/UART.c msgid "UART write error" msgstr "" @@ -2455,7 +2460,7 @@ msgid "binary op %q not implemented" msgstr "" #: shared-bindings/busio/UART.c -msgid "bits must be 7, 8 or 9" +msgid "bits must be between 5 and 8" msgstr "" #: shared-bindings/audiomixer/Mixer.c diff --git a/ports/raspberrypi/common-hal/busio/UART.c b/ports/raspberrypi/common-hal/busio/UART.c index f9a75b499688..660a473ae6a0 100644 --- a/ports/raspberrypi/common-hal/busio/UART.c +++ b/ports/raspberrypi/common-hal/busio/UART.c @@ -3,7 +3,7 @@ * * The MIT License (MIT) * - * Copyright (c) 2021 Scott Shawcroft for Adafruit Industries + * Copyright (c) 2021 microDev * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -24,238 +24,135 @@ * THE SOFTWARE. */ -#include "shared-bindings/microcontroller/__init__.h" #include "shared-bindings/busio/UART.h" -#include "mpconfigport.h" -#include "lib/utils/interrupt_char.h" -#include "py/gc.h" +#include "py/stream.h" #include "py/mperrno.h" #include "py/runtime.h" -#include "py/stream.h" -#include "supervisor/shared/translate.h" #include "supervisor/shared/tick.h" +#include "lib/utils/interrupt_char.h" -#define UART_DEBUG(...) (void)0 -// #define UART_DEBUG(...) mp_printf(&mp_plat_print __VA_OPT__(,) __VA_ARGS__) - -// Do-nothing callback needed so that usart_async code will enable rx interrupts. -// See comment below re usart_async_register_callback() -// static void usart_async_rxc_callback(const struct usart_async_descriptor *const descr) { -// // Nothing needs to be done by us. -// } +#include "src/rp2_common/hardware_gpio/include/hardware/gpio.h" #define NO_PIN 0xff +#define UART_INST(uart) (((uart) ? uart1 : uart0)) + +#define TX 0 +#define RX 1 +#define CTS 2 +#define RTS 3 + +typedef enum { + STATUS_FREE = 0, + STATUS_IN_USE, + STATUS_NEVER_RESET +} uart_status_t; + +static uart_status_t uart_status[2]; + +void uart_reset(void) { + for (uint8_t num = 0; num < 2; num++) { + if (uart_status[num] == STATUS_IN_USE) { + uart_status[num] = STATUS_FREE; + uart_deinit(UART_INST(num)); + } + } +} + +void never_reset_uart(uint8_t num) { + uart_status[num] = STATUS_NEVER_RESET; +} + +static uint8_t get_free_uart() { + uint8_t num; + for (num = 0; num < 2; num++) { + if (uart_status[num] == STATUS_FREE) { + break; + } + if (num) { + mp_raise_RuntimeError(translate("All UART peripherals in use")); + } + } + return num; +} + +static uint8_t pin_init(const uint8_t uart, const mcu_pin_obj_t * pin, const uint8_t pin_type) { + if (pin == NULL) { + return NO_PIN; + } + if (!(((pin->number & 3) == pin_type) && ((((pin->number + 4) & 8) >> 3) == uart))) { + mp_raise_ValueError(translate("Invalid pins")); + } + gpio_set_function(pin->number, GPIO_FUNC_UART); + return pin->number; +} + void common_hal_busio_uart_construct(busio_uart_obj_t *self, - const mcu_pin_obj_t * tx, const mcu_pin_obj_t * rx, - const mcu_pin_obj_t * rts, const mcu_pin_obj_t * cts, - const mcu_pin_obj_t * rs485_dir, bool rs485_invert, - uint32_t baudrate, uint8_t bits, busio_uart_parity_t parity, uint8_t stop, - mp_float_t timeout, uint16_t receiver_buffer_size, byte* receiver_buffer, - bool sigint_enabled) { - mp_raise_NotImplementedError(translate("UART not yet supported")); - -// Sercom* sercom = NULL; -// uint8_t sercom_index = 255; // Unset index -// uint32_t rx_pinmux = 0; -// uint8_t rx_pad = 255; // Unset pad -// uint32_t tx_pinmux = 0; -// uint8_t tx_pad = 255; // Unset pad - -// if ((rts != NULL) || (cts != NULL) || (rs485_dir != NULL) || (rs485_invert)) { -// mp_raise_ValueError(translate("RTS/CTS/RS485 Not yet supported on this device")); -// } - -// if (bits > 8) { -// mp_raise_NotImplementedError(translate("bytes > 8 bits not supported")); -// } - -// bool have_tx = tx != NULL; -// bool have_rx = rx != NULL; -// if (!have_tx && !have_rx) { -// mp_raise_ValueError(translate("tx and rx cannot both be None")); -// } - -// self->baudrate = baudrate; -// self->character_bits = bits; -// self->timeout_ms = timeout * 1000; - -// // This assignment is only here because the usart_async routines take a *const argument. -// struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - -// for (int i = 0; i < NUM_SERCOMS_PER_PIN; i++) { -// Sercom* potential_sercom = NULL; -// if (have_tx) { -// sercom_index = tx->sercom[i].index; -// if (sercom_index >= SERCOM_INST_NUM) { -// continue; -// } -// potential_sercom = sercom_insts[sercom_index]; -// #ifdef SAMD21 -// if (potential_sercom->USART.CTRLA.bit.ENABLE != 0 || -// !(tx->sercom[i].pad == 0 || -// tx->sercom[i].pad == 2)) { -// continue; -// } -// #endif -// #ifdef SAM_D5X_E5X -// if (potential_sercom->USART.CTRLA.bit.ENABLE != 0 || -// !(tx->sercom[i].pad == 0)) { -// continue; -// } -// #endif -// tx_pinmux = PINMUX(tx->number, (i == 0) ? MUX_C : MUX_D); -// tx_pad = tx->sercom[i].pad; -// if (rx == NULL) { -// sercom = potential_sercom; -// break; -// } -// } -// for (int j = 0; j < NUM_SERCOMS_PER_PIN; j++) { -// if (((!have_tx && rx->sercom[j].index < SERCOM_INST_NUM && -// sercom_insts[rx->sercom[j].index]->USART.CTRLA.bit.ENABLE == 0) || -// sercom_index == rx->sercom[j].index) && -// rx->sercom[j].pad != tx_pad) { -// rx_pinmux = PINMUX(rx->number, (j == 0) ? MUX_C : MUX_D); -// rx_pad = rx->sercom[j].pad; -// sercom = sercom_insts[rx->sercom[j].index]; -// sercom_index = rx->sercom[j].index; -// break; -// } -// } -// if (sercom != NULL) { -// break; -// } -// } -// if (sercom == NULL) { -// mp_raise_ValueError(translate("Invalid pins")); -// } -// if (!have_tx) { -// tx_pad = 0; -// if (rx_pad == 0) { -// tx_pad = 2; -// } -// } -// if (!have_rx) { -// rx_pad = (tx_pad + 1) % 4; -// } - -// // Set up clocks on SERCOM. -// samd_peripherals_sercom_clock_init(sercom, sercom_index); - -// if (rx && receiver_buffer_size > 0) { -// self->buffer_length = receiver_buffer_size; -// // Initially allocate the UART's buffer in the long-lived part of the -// // heap. UARTs are generally long-lived objects, but the "make long- -// // lived" machinery is incapable of moving internal pointers like -// // self->buffer, so do it manually. (However, as long as internal -// // pointers like this are NOT moved, allocating the buffer -// // in the long-lived pool is not strictly necessary) -// self->buffer = (uint8_t *) gc_alloc(self->buffer_length * sizeof(uint8_t), false, true); -// if (self->buffer == NULL) { -// common_hal_busio_uart_deinit(self); -// mp_raise_msg_varg(&mp_type_MemoryError, translate("Failed to allocate RX buffer of %d bytes"), self->buffer_length * sizeof(uint8_t)); -// } -// } else { -// self->buffer_length = 0; -// self->buffer = NULL; -// } - -// if (usart_async_init(usart_desc_p, sercom, self->buffer, self->buffer_length, NULL) != ERR_NONE) { -// mp_raise_ValueError(translate("Could not initialize UART")); -// } - -// // usart_async_init() sets a number of defaults based on a prototypical SERCOM -// // which don't necessarily match what we need. After calling it, set the values -// // specific to this instantiation of UART. - -// // Set pads computed for this SERCOM. -// // TXPO: -// // 0x0: TX pad 0; no RTS/CTS -// // 0x1: TX pad 2; no RTS/CTS -// // 0x2: TX pad 0; RTS: pad 2, CTS: pad 3 (not used by us right now) -// // So divide by 2 to map pad to value. -// // RXPO: -// // 0x0: RX pad 0 -// // 0x1: RX pad 1 -// // 0x2: RX pad 2 -// // 0x3: RX pad 3 - -// // Doing a group mask and set of the registers saves 60 bytes over setting the bitfields individually. - -// sercom->USART.CTRLA.reg &= ~(SERCOM_USART_CTRLA_TXPO_Msk | -// SERCOM_USART_CTRLA_RXPO_Msk | -// SERCOM_USART_CTRLA_FORM_Msk); -// sercom->USART.CTRLA.reg |= SERCOM_USART_CTRLA_TXPO(tx_pad / 2) | -// SERCOM_USART_CTRLA_RXPO(rx_pad) | -// (parity == BUSIO_UART_PARITY_NONE ? 0 : SERCOM_USART_CTRLA_FORM(1)); - -// // Enable tx and/or rx based on whether the pins were specified. -// // CHSIZE is 0 for 8 bits, 5, 6, 7 for 5, 6, 7 bits. 1 for 9 bits, but we don't support that. -// sercom->USART.CTRLB.reg &= ~(SERCOM_USART_CTRLB_TXEN | -// SERCOM_USART_CTRLB_RXEN | -// SERCOM_USART_CTRLB_PMODE | -// SERCOM_USART_CTRLB_SBMODE | -// SERCOM_USART_CTRLB_CHSIZE_Msk); -// sercom->USART.CTRLB.reg |= (have_tx ? SERCOM_USART_CTRLB_TXEN : 0) | -// (have_rx ? SERCOM_USART_CTRLB_RXEN : 0) | -// (parity == BUSIO_UART_PARITY_ODD ? SERCOM_USART_CTRLB_PMODE : 0) | -// (stop > 1 ? SERCOM_USART_CTRLB_SBMODE : 0) | -// SERCOM_USART_CTRLB_CHSIZE(bits % 8); - -// // Set baud rate -// common_hal_busio_uart_set_baudrate(self, baudrate); - -// // Turn on rx interrupt handling. The UART async driver has its own set of internal callbacks, -// // which are set up by uart_async_init(). These in turn can call user-specified callbacks. -// // In fact, the actual interrupts are not enabled unless we set up a user-specified callback. -// // This is confusing. It's explained in the Atmel START User Guide -> Implementation Description -> -// // Different read function behavior in some asynchronous drivers. As of this writing: -// // http://start.atmel.com/static/help/index.html?GUID-79201A5A-226F-4FBB-B0B8-AB0BE0554836 -// // Look at the ASFv4 code example for async USART. -// usart_async_register_callback(usart_desc_p, USART_ASYNC_RXC_CB, usart_async_rxc_callback); - - -// if (have_tx) { -// gpio_set_pin_direction(tx->number, GPIO_DIRECTION_OUT); -// gpio_set_pin_pull_mode(tx->number, GPIO_PULL_OFF); -// gpio_set_pin_function(tx->number, tx_pinmux); -// self->tx_pin = tx->number; -// claim_pin(tx); -// } else { -// self->tx_pin = NO_PIN; -// } - -// if (have_rx) { -// gpio_set_pin_direction(rx->number, GPIO_DIRECTION_IN); -// gpio_set_pin_pull_mode(rx->number, GPIO_PULL_OFF); -// gpio_set_pin_function(rx->number, rx_pinmux); -// self->rx_pin = rx->number; -// claim_pin(rx); -// } else { -// self->rx_pin = NO_PIN; -// } - -// usart_async_enable(usart_desc_p); + const mcu_pin_obj_t * tx, const mcu_pin_obj_t * rx, + const mcu_pin_obj_t * rts, const mcu_pin_obj_t * cts, + const mcu_pin_obj_t * rs485_dir, bool rs485_invert, + uint32_t baudrate, uint8_t bits, busio_uart_parity_t parity, uint8_t stop, + mp_float_t timeout, uint16_t receiver_buffer_size, byte* receiver_buffer, + bool sigint_enabled) { + + if ((rs485_dir != NULL) || (rs485_invert)) { + mp_raise_NotImplementedError(translate("RS485 is not supported on this board")); + } + + uint8_t uart_id = get_free_uart(); + + self->tx_pin = pin_init(uart_id, tx, TX); + self->rx_pin = pin_init(uart_id, rx, RX); + self->cts_pin = pin_init(uart_id, cts, CTS); + self->rts_pin = pin_init(uart_id, rts, RTS); + + self->uart = UART_INST(uart_id); + self->baudrate = baudrate; + self->timeout_ms = timeout * 1000; + + uart_init(self->uart, self->baudrate); + uart_set_fifo_enabled(self->uart, true); + uart_set_format(self->uart, bits, stop, parity); + uart_set_hw_flow(self->uart, (cts != NULL), (rts != NULL)); } bool common_hal_busio_uart_deinited(busio_uart_obj_t *self) { - return self->rx_pin == NO_PIN && self->tx_pin == NO_PIN; + return self->tx_pin == NO_PIN && self->rx_pin == NO_PIN; } void common_hal_busio_uart_deinit(busio_uart_obj_t *self) { if (common_hal_busio_uart_deinited(self)) { return; } - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - // usart_async_disable(usart_desc_p); - // usart_async_deinit(usart_desc_p); - reset_pin_number(self->rx_pin); + uart_deinit(self->uart); reset_pin_number(self->tx_pin); - self->rx_pin = NO_PIN; + reset_pin_number(self->rx_pin); + reset_pin_number(self->cts_pin); + reset_pin_number(self->rts_pin); self->tx_pin = NO_PIN; + self->rx_pin = NO_PIN; + self->cts_pin = NO_PIN; + self->rts_pin = NO_PIN; +} + +// Write characters. +size_t common_hal_busio_uart_write(busio_uart_obj_t *self, const uint8_t *data, size_t len, int *errcode) { + if (self->tx_pin == NO_PIN) { + mp_raise_ValueError(translate("No TX pin")); + } + + while (len > 0) { + if (uart_is_writable(self->uart)) { + // Write and advance. + uart_get_hw(self->uart)->dr = *data++; + // Decrease how many chars left to write. + len--; + } + RUN_BACKGROUND_TASKS; + } + + return len; } // Read characters. @@ -264,87 +161,53 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t mp_raise_ValueError(translate("No RX pin")); } - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - if (len == 0) { // Nothing to read. return 0; } - // struct io_descriptor *io; - // usart_async_get_io_descriptor(usart_desc_p, &io); - size_t total_read = 0; - // uint64_t start_ticks = supervisor_ticks_ms64(); - - // // Busy-wait until timeout or until we've read enough chars. - // while (supervisor_ticks_ms64() - start_ticks <= self->timeout_ms) { - // // Read as many chars as we can right now, up to len. - // size_t num_read = io_read(io, data, len); - - // // Advance pointer in data buffer, and decrease how many chars left to read. - // data += num_read; - // len -= num_read; - // total_read += num_read; - // if (len == 0) { - // // Don't need to read any more: data buf is full. - // break; - // } - // if (num_read > 0) { - // // Reset the timeout on every character read. - // start_ticks = supervisor_ticks_ms64(); - // } - // RUN_BACKGROUND_TASKS; - // // Allow user to break out of a timeout with a KeyboardInterrupt. - // if (mp_hal_is_interrupted()) { - // break; - // } - // // If we are zero timeout, make sure we don't loop again (in the event - // // we read in under 1ms) - // if (self->timeout_ms == 0) { - // break; - // } - // } - - // if (total_read == 0) { - // *errcode = EAGAIN; - // return MP_STREAM_ERROR; - // } - - return total_read; -} - -// Write characters. -size_t common_hal_busio_uart_write(busio_uart_obj_t *self, const uint8_t *data, size_t len, int *errcode) { - if (self->tx_pin == NO_PIN) { - mp_raise_ValueError(translate("No TX pin")); + uint64_t start_ticks = supervisor_ticks_ms64(); + + // Busy-wait until timeout or until we've read enough chars. + while (supervisor_ticks_ms64() - start_ticks <= self->timeout_ms) { + if (uart_is_readable(self->uart)) { + // Read and advance. + *data++ = uart_get_hw(self->uart)->dr; + + // Decrease how many chars left to read. + len--; + total_read++; + + // Reset the timeout on every character read. + start_ticks = supervisor_ticks_ms64(); + } + + RUN_BACKGROUND_TASKS; + + // Allow user to break out of a timeout with a KeyboardInterrupt. + if (mp_hal_is_interrupted()) { + break; + } + + // Don't need to read any more: data buf is full. + if (len == 0) { + break; + } + + // If we are zero timeout, make sure we don't loop again (in the event + // we read in under 1ms) + if (self->timeout_ms == 0) { + break; + } } - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - - // struct io_descriptor *io; - // usart_async_get_io_descriptor(usart_desc_p, &io); - - // // Start writing characters. This is non-blocking and will - // // return immediately after setting up the write. - // if (io_write(io, data, len) < 0) { - // *errcode = MP_EAGAIN; - // return MP_STREAM_ERROR; - // } - - // // Busy-wait until all characters transmitted. - // struct usart_async_status async_status; - // while (true) { - // usart_async_get_status(usart_desc_p, &async_status); - // if (async_status.txcnt >= len) { - // break; - // } - // RUN_BACKGROUND_TASKS; - // } + if (total_read == 0) { + *errcode = EAGAIN; + return MP_STREAM_ERROR; + } - return len; + return total_read; } uint32_t common_hal_busio_uart_get_baudrate(busio_uart_obj_t *self) { @@ -352,18 +215,8 @@ uint32_t common_hal_busio_uart_get_baudrate(busio_uart_obj_t *self) { } void common_hal_busio_uart_set_baudrate(busio_uart_obj_t *self, uint32_t baudrate) { - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - // usart_async_set_baud_rate(usart_desc_p, - // // Samples and ARITHMETIC vs FRACTIONAL must correspond to USART_SAMPR in - // // hpl_sercom_config.h. - // _usart_async_calculate_baud_rate(baudrate, // e.g. 9600 baud - // PROTOTYPE_SERCOM_USART_ASYNC_CLOCK_FREQUENCY, - // 16, // samples - // USART_BAUDRATE_ASYNCH_ARITHMETIC, - // 0 // fraction - not used for ARITHMETIC - // )); self->baudrate = baudrate; + uart_set_baudrate(self->uart, baudrate); } mp_float_t common_hal_busio_uart_get_timeout(busio_uart_obj_t *self) { @@ -375,30 +228,15 @@ void common_hal_busio_uart_set_timeout(busio_uart_obj_t *self, mp_float_t timeou } uint32_t common_hal_busio_uart_rx_characters_available(busio_uart_obj_t *self) { - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - // struct usart_async_status async_status; - // usart_async_get_status(usart_desc_p, &async_status); - // return async_status.rxcnt; - return 0; + return uart_is_readable(self->uart); } -void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) { - // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - // usart_async_flush_rx_buffer(usart_desc_p); - -} +void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) {} // True if there are no characters still to be written. bool common_hal_busio_uart_ready_to_tx(busio_uart_obj_t *self) { if (self->tx_pin == NO_PIN) { return false; } - return false; - // // This assignment is only here because the usart_async routines take a *const argument. - // struct usart_async_descriptor * const usart_desc_p = (struct usart_async_descriptor * const) &self->usart_desc; - // struct usart_async_status async_status; - // usart_async_get_status(usart_desc_p, &async_status); - // return !(async_status.flags & USART_ASYNC_STATUS_BUSY); + return uart_is_writable(self->uart); } diff --git a/ports/raspberrypi/common-hal/busio/UART.h b/ports/raspberrypi/common-hal/busio/UART.h index 43ed9bee014c..03613daeb78f 100644 --- a/ports/raspberrypi/common-hal/busio/UART.h +++ b/ports/raspberrypi/common-hal/busio/UART.h @@ -3,7 +3,7 @@ * * The MIT License (MIT) * - * Copyright (c) 2021 Scott Shawcroft for Adafruit Industries + * Copyright (c) 2021 microDev * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to deal @@ -27,21 +27,23 @@ #ifndef MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_BUSIO_UART_H #define MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_BUSIO_UART_H +#include "py/obj.h" #include "common-hal/microcontroller/Pin.h" -#include "py/obj.h" +#include "src/rp2_common/hardware_uart/include/hardware/uart.h" typedef struct { mp_obj_base_t base; - // struct usart_async_descriptor usart_desc; - uint8_t rx_pin; uint8_t tx_pin; - uint8_t character_bits; - bool rx_error; + uint8_t rx_pin; + uint8_t cts_pin; + uint8_t rts_pin; uint32_t baudrate; uint32_t timeout_ms; - uint32_t buffer_length; - uint8_t* buffer; + uart_inst_t * uart; } busio_uart_obj_t; +extern void uart_reset(void); +extern void never_reset_uart(uint8_t num); + #endif // MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_BUSIO_UART_H diff --git a/shared-bindings/busio/UART.c b/shared-bindings/busio/UART.c index bf0b7e721d05..151081d31320 100644 --- a/shared-bindings/busio/UART.c +++ b/shared-bindings/busio/UART.c @@ -55,7 +55,7 @@ //| :param ~microcontroller.Pin rs485_dir: the output pin for rs485 direction setting, or ``None`` if rs485 not in use. //| :param bool rs485_invert: rs485_dir pin active high when set. Active low otherwise. //| :param int baudrate: the transmit and receive speed. -//| :param int bits: the number of bits per byte, 7, 8 or 9. +//| :param int bits: the number of bits per byte, 5 to 8. //| :param Parity parity: the parity used for error checking. //| :param int stop: the number of stop bits, 1 or 2. //| :param float timeout: the timeout in seconds to wait for the first character and between subsequent characters when reading. Raises ``ValueError`` if timeout >100 seconds. @@ -110,10 +110,10 @@ STATIC mp_obj_t busio_uart_make_new(const mp_obj_type_t *type, size_t n_args, co mp_raise_ValueError(translate("tx and rx cannot both be None")); } - uint8_t bits = args[ARG_bits].u_int; - if (bits < 7 || bits > 9) { - mp_raise_ValueError(translate("bits must be 7, 8 or 9")); + if (args[ARG_bits].u_int < 5 || args[ARG_bits].u_int > 8) { + mp_raise_ValueError(translate("bits must be between 5 and 8")); } + uint8_t bits = args[ARG_bits].u_int; busio_uart_parity_t parity = BUSIO_UART_PARITY_NONE; if (args[ARG_parity].u_obj == &busio_uart_parity_even_obj) { From 5d7fdafcdec126f4f552689df25cecf30b39265d Mon Sep 17 00:00:00 2001 From: microDev <70126934+microDev1@users.noreply.github.com> Date: Thu, 25 Feb 2021 00:48:36 +0530 Subject: [PATCH 2/5] implement suggested changes - add internal buffering - rtc initialization fix --- locale/circuitpython.pot | 23 ++--- ports/mimxrt10xx/common-hal/busio/UART.c | 8 +- ports/nrf/common-hal/busio/UART.c | 8 +- ports/raspberrypi/common-hal/busio/UART.c | 115 ++++++++++++++-------- ports/raspberrypi/common-hal/busio/UART.h | 6 +- ports/raspberrypi/supervisor/port.c | 7 ++ shared-bindings/busio/UART.c | 6 +- 7 files changed, 107 insertions(+), 66 deletions(-) diff --git a/locale/circuitpython.pot b/locale/circuitpython.pot index bffc3005cbf9..6a009f63d123 100644 --- a/locale/circuitpython.pot +++ b/locale/circuitpython.pot @@ -332,11 +332,8 @@ msgid "All SPI peripherals are in use" msgstr "" #: ports/esp32s2/common-hal/busio/UART.c ports/nrf/common-hal/busio/UART.c -msgid "All UART peripherals are in use" -msgstr "" - #: ports/raspberrypi/common-hal/busio/UART.c -msgid "All UART peripherals in use" +msgid "All UART peripherals are in use" msgstr "" #: ports/atmel-samd/common-hal/audioio/AudioOut.c @@ -947,6 +944,7 @@ msgid "Failed to acquire mutex, err 0x%04x" msgstr "" #: ports/mimxrt10xx/common-hal/busio/UART.c ports/nrf/common-hal/busio/UART.c +#: ports/raspberrypi/common-hal/busio/UART.c msgid "Failed to allocate RX buffer" msgstr "" @@ -1202,7 +1200,8 @@ msgstr "" msgid "Invalid bits per value" msgstr "" -#: ports/nrf/common-hal/busio/UART.c ports/stm/common-hal/busio/UART.c +#: ports/nrf/common-hal/busio/UART.c ports/raspberrypi/common-hal/busio/UART.c +#: ports/stm/common-hal/busio/UART.c msgid "Invalid buffer size" msgstr "" @@ -1277,8 +1276,7 @@ msgstr "" #: ports/esp32s2/common-hal/busio/I2C.c ports/esp32s2/common-hal/busio/SPI.c #: ports/esp32s2/common-hal/busio/UART.c ports/esp32s2/common-hal/canio/CAN.c #: ports/mimxrt10xx/common-hal/busio/I2C.c -#: ports/mimxrt10xx/common-hal/busio/SPI.c -#: ports/mimxrt10xx/common-hal/busio/UART.c ports/nrf/common-hal/busio/I2C.c +#: ports/mimxrt10xx/common-hal/busio/SPI.c ports/nrf/common-hal/busio/I2C.c #: ports/raspberrypi/common-hal/busio/I2C.c #: ports/raspberrypi/common-hal/busio/SPI.c #: ports/raspberrypi/common-hal/busio/UART.c @@ -1330,7 +1328,8 @@ msgstr "" msgid "Invalid wave file" msgstr "" -#: ports/stm/common-hal/busio/UART.c +#: ports/mimxrt10xx/common-hal/busio/UART.c ports/nrf/common-hal/busio/UART.c +#: ports/raspberrypi/common-hal/busio/UART.c ports/stm/common-hal/busio/UART.c msgid "Invalid word/bit length" msgstr "" @@ -1820,7 +1819,7 @@ msgstr "" msgid "RNG Init Error" msgstr "" -#: ports/nrf/common-hal/busio/UART.c +#: ports/nrf/common-hal/busio/UART.c ports/raspberrypi/common-hal/busio/UART.c msgid "RS485 Not yet supported on this device" msgstr "" @@ -1829,10 +1828,6 @@ msgstr "" msgid "RS485 inversion specified when not in RS485 mode" msgstr "" -#: ports/raspberrypi/common-hal/busio/UART.c -msgid "RS485 is not supported on this board" -msgstr "" - #: ports/cxd56/common-hal/rtc/RTC.c ports/esp32s2/common-hal/rtc/RTC.c #: ports/mimxrt10xx/common-hal/rtc/RTC.c ports/nrf/common-hal/rtc/RTC.c #: ports/raspberrypi/common-hal/rtc/RTC.c @@ -2460,7 +2455,7 @@ msgid "binary op %q not implemented" msgstr "" #: shared-bindings/busio/UART.c -msgid "bits must be between 5 and 8" +msgid "bits must be in range 5 to 9" msgstr "" #: shared-bindings/audiomixer/Mixer.c diff --git a/ports/mimxrt10xx/common-hal/busio/UART.c b/ports/mimxrt10xx/common-hal/busio/UART.c index 03a6e8f3efb1..503da14c2615 100644 --- a/ports/mimxrt10xx/common-hal/busio/UART.c +++ b/ports/mimxrt10xx/common-hal/busio/UART.c @@ -93,6 +93,10 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, self->character_bits = bits; self->timeout_ms = timeout * 1000; + if (self->character_bits != 7 && self->character_bits != 8) { + mp_raise_ValueError(translate("Invalid word/bit length")); + } + // We are transmitting one direction if one pin is NULL and the other isn't. bool is_onedirection = (rx == NULL) != (tx == NULL); bool uart_taken = false; @@ -154,10 +158,6 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, mp_raise_ValueError(translate("Hardware in use, try alternative pins")); } - if(self->rx == NULL && self->tx == NULL) { - mp_raise_ValueError(translate("Invalid pins")); - } - if (is_onedirection && ((rts != NULL) || (cts != NULL))) { mp_raise_ValueError(translate("Both RX and TX required for flow control")); } diff --git a/ports/nrf/common-hal/busio/UART.c b/ports/nrf/common-hal/busio/UART.c index 6ecf7e0ba3db..491e360e4df5 100644 --- a/ports/nrf/common-hal/busio/UART.c +++ b/ports/nrf/common-hal/busio/UART.c @@ -70,9 +70,9 @@ static uint32_t get_nrf_baud (uint32_t baudrate) { { 14400, NRF_UARTE_BAUDRATE_14400 }, { 19200, NRF_UARTE_BAUDRATE_19200 }, { 28800, NRF_UARTE_BAUDRATE_28800 }, - { 31250, NRF_UARTE_BAUDRATE_31250 }, + { 31250, NRF_UARTE_BAUDRATE_31250 }, { 38400, NRF_UARTE_BAUDRATE_38400 }, - { 56000, NRF_UARTE_BAUDRATE_56000 }, + { 56000, NRF_UARTE_BAUDRATE_56000 }, { 57600, NRF_UARTE_BAUDRATE_57600 }, { 76800, NRF_UARTE_BAUDRATE_76800 }, { 115200, NRF_UARTE_BAUDRATE_115200 }, @@ -144,6 +144,10 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, mp_float_t timeout, uint16_t receiver_buffer_size, byte* receiver_buffer, bool sigint_enabled) { + if (bits != 8) { + mp_raise_ValueError(translate("Invalid word/bit length")); + } + if ((rs485_dir != NULL) || (rs485_invert)) { mp_raise_ValueError(translate("RS485 Not yet supported on this device")); } diff --git a/ports/raspberrypi/common-hal/busio/UART.c b/ports/raspberrypi/common-hal/busio/UART.c index 660a473ae6a0..e319b4ccf23a 100644 --- a/ports/raspberrypi/common-hal/busio/UART.c +++ b/ports/raspberrypi/common-hal/busio/UART.c @@ -31,18 +31,15 @@ #include "py/runtime.h" #include "supervisor/shared/tick.h" #include "lib/utils/interrupt_char.h" +#include "common-hal/microcontroller/Pin.h" +#include "src/rp2_common/hardware_irq/include/hardware/irq.h" #include "src/rp2_common/hardware_gpio/include/hardware/gpio.h" #define NO_PIN 0xff #define UART_INST(uart) (((uart) ? uart1 : uart0)) -#define TX 0 -#define RX 1 -#define CTS 2 -#define RTS 3 - typedef enum { STATUS_FREE = 0, STATUS_IN_USE, @@ -51,7 +48,7 @@ typedef enum { static uart_status_t uart_status[2]; -void uart_reset(void) { +void reset_uart(void) { for (uint8_t num = 0; num < 2; num++) { if (uart_status[num] == STATUS_IN_USE) { uart_status[num] = STATUS_FREE; @@ -71,7 +68,7 @@ static uint8_t get_free_uart() { break; } if (num) { - mp_raise_RuntimeError(translate("All UART peripherals in use")); + mp_raise_RuntimeError(translate("All UART peripherals are in use")); } } return num; @@ -84,10 +81,21 @@ static uint8_t pin_init(const uint8_t uart, const mcu_pin_obj_t * pin, const uin if (!(((pin->number & 3) == pin_type) && ((((pin->number + 4) & 8) >> 3) == uart))) { mp_raise_ValueError(translate("Invalid pins")); } + claim_pin(pin); gpio_set_function(pin->number, GPIO_FUNC_UART); return pin->number; } +static ringbuf_t ringbuf[2]; + +static void uart0_callback(void) { + while (uart_is_readable(uart0) && !ringbuf_put(&ringbuf[0], (uint8_t)uart_get_hw(uart0)->dr)) {} +} + +static void uart1_callback(void) { + while (uart_is_readable(uart1) && !ringbuf_put(&ringbuf[1], (uint8_t)uart_get_hw(uart1)->dr)) {} +} + void common_hal_busio_uart_construct(busio_uart_obj_t *self, const mcu_pin_obj_t * tx, const mcu_pin_obj_t * rx, const mcu_pin_obj_t * rts, const mcu_pin_obj_t * cts, @@ -96,25 +104,56 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, mp_float_t timeout, uint16_t receiver_buffer_size, byte* receiver_buffer, bool sigint_enabled) { + if (bits > 8) { + mp_raise_ValueError(translate("Invalid word/bit length")); + } + + if (receiver_buffer_size == 0) { + mp_raise_ValueError(translate("Invalid buffer size")); + } + if ((rs485_dir != NULL) || (rs485_invert)) { - mp_raise_NotImplementedError(translate("RS485 is not supported on this board")); + mp_raise_NotImplementedError(translate("RS485 Not yet supported on this device")); } uint8_t uart_id = get_free_uart(); - self->tx_pin = pin_init(uart_id, tx, TX); - self->rx_pin = pin_init(uart_id, rx, RX); - self->cts_pin = pin_init(uart_id, cts, CTS); - self->rts_pin = pin_init(uart_id, rts, RTS); + self->tx_pin = pin_init(uart_id, tx, 0); + self->rx_pin = pin_init(uart_id, rx, 1); + self->cts_pin = pin_init(uart_id, cts, 2); + self->rts_pin = pin_init(uart_id, rts, 3); self->uart = UART_INST(uart_id); + self->uart_id = uart_id; self->baudrate = baudrate; self->timeout_ms = timeout * 1000; uart_init(self->uart, self->baudrate); - uart_set_fifo_enabled(self->uart, true); + uart_set_fifo_enabled(self->uart, false); uart_set_format(self->uart, bits, stop, parity); uart_set_hw_flow(self->uart, (cts != NULL), (rts != NULL)); + + if (rx != NULL) { + // Initially allocate the UART's buffer in the long-lived part of the + // heap. UARTs are generally long-lived objects, but the "make long- + // lived" machinery is incapable of moving internal pointers like + // self->buffer, so do it manually. (However, as long as internal + // pointers like this are NOT moved, allocating the buffer + // in the long-lived pool is not strictly necessary) + // (This is a macro.) + if (!ringbuf_alloc(&ringbuf[uart_id], receiver_buffer_size, true)) { + mp_raise_msg(&mp_type_MemoryError, translate("Failed to allocate RX buffer")); + } + if (uart_id) { + self->uart_irq_id = UART1_IRQ; + irq_set_exclusive_handler(self->uart_irq_id, uart1_callback); + } else { + self->uart_irq_id = UART0_IRQ; + irq_set_exclusive_handler(self->uart_irq_id, uart0_callback); + } + irq_set_enabled(self->uart_irq_id, true); + uart_set_irq_enables(self->uart, true, false); + } } bool common_hal_busio_uart_deinited(busio_uart_obj_t *self) { @@ -126,6 +165,7 @@ void common_hal_busio_uart_deinit(busio_uart_obj_t *self) { return; } uart_deinit(self->uart); + ringbuf_free(&ringbuf[self->uart_id]); reset_pin_number(self->tx_pin); reset_pin_number(self->rx_pin); reset_pin_number(self->cts_pin); @@ -169,36 +209,25 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t size_t total_read = 0; uint64_t start_ticks = supervisor_ticks_ms64(); - // Busy-wait until timeout or until we've read enough chars. - while (supervisor_ticks_ms64() - start_ticks <= self->timeout_ms) { - if (uart_is_readable(self->uart)) { - // Read and advance. - *data++ = uart_get_hw(self->uart)->dr; - - // Decrease how many chars left to read. - len--; - total_read++; - - // Reset the timeout on every character read. + // Busy-wait for all bytes received or timeout + while (len > 0 && (supervisor_ticks_ms64() - start_ticks < self->timeout_ms)) { + // Reset the timeout on every character read. + if (ringbuf_num_filled(&ringbuf[self->uart_id])) { + // Prevent conflict with uart irq. + irq_set_enabled(self->uart_irq_id, false); + // Copy as much received data as available, up to len bytes. + size_t num_read = ringbuf_get_n(&ringbuf[self->uart_id], data, len); + // Re-enable irq. + irq_set_enabled(self->uart_irq_id, true); + len-=num_read; + data+=num_read; + total_read+=num_read; start_ticks = supervisor_ticks_ms64(); } - RUN_BACKGROUND_TASKS; - // Allow user to break out of a timeout with a KeyboardInterrupt. if (mp_hal_is_interrupted()) { - break; - } - - // Don't need to read any more: data buf is full. - if (len == 0) { - break; - } - - // If we are zero timeout, make sure we don't loop again (in the event - // we read in under 1ms) - if (self->timeout_ms == 0) { - break; + return 0; } } @@ -228,12 +257,16 @@ void common_hal_busio_uart_set_timeout(busio_uart_obj_t *self, mp_float_t timeou } uint32_t common_hal_busio_uart_rx_characters_available(busio_uart_obj_t *self) { - return uart_is_readable(self->uart); + return ringbuf_num_filled(&ringbuf[self->uart_id]); } -void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) {} +void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) { + // Prevent conflict with uart irq. + irq_set_enabled(self->uart_irq_id, false); + ringbuf_clear(&ringbuf[self->uart_id]); + irq_set_enabled(self->uart_irq_id, true); +} -// True if there are no characters still to be written. bool common_hal_busio_uart_ready_to_tx(busio_uart_obj_t *self) { if (self->tx_pin == NO_PIN) { return false; diff --git a/ports/raspberrypi/common-hal/busio/UART.h b/ports/raspberrypi/common-hal/busio/UART.h index 03613daeb78f..da6170596b10 100644 --- a/ports/raspberrypi/common-hal/busio/UART.h +++ b/ports/raspberrypi/common-hal/busio/UART.h @@ -28,7 +28,7 @@ #define MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_BUSIO_UART_H #include "py/obj.h" -#include "common-hal/microcontroller/Pin.h" +#include "py/ringbuf.h" #include "src/rp2_common/hardware_uart/include/hardware/uart.h" @@ -38,12 +38,14 @@ typedef struct { uint8_t rx_pin; uint8_t cts_pin; uint8_t rts_pin; + uint8_t uart_id; + uint8_t uart_irq_id; uint32_t baudrate; uint32_t timeout_ms; uart_inst_t * uart; } busio_uart_obj_t; -extern void uart_reset(void); +extern void reset_uart(void); extern void never_reset_uart(uint8_t num); #endif // MICROPY_INCLUDED_RASPBERRYPI_COMMON_HAL_BUSIO_UART_H diff --git a/ports/raspberrypi/supervisor/port.c b/ports/raspberrypi/supervisor/port.c index 36d2e8275c47..3b8790ea08ef 100644 --- a/ports/raspberrypi/supervisor/port.c +++ b/ports/raspberrypi/supervisor/port.c @@ -39,6 +39,9 @@ #include "shared-bindings/rtc/__init__.h" #include "shared-bindings/pwmio/PWMOut.h" +#include "common-hal/rtc/RTC.h" +#include "common-hal/busio/UART.h" + #include "supervisor/shared/safe_mode.h" #include "supervisor/shared/stack.h" #include "supervisor/shared/tick.h" @@ -78,6 +81,9 @@ safe_mode_t port_init(void) { // Reset everything into a known state before board_init. reset_port(); + // Initialize RTC + common_hal_rtc_init(); + // For the tick. hardware_alarm_claim(0); hardware_alarm_set_callback(0, _tick_callback); @@ -95,6 +101,7 @@ void reset_port(void) { #if CIRCUITPY_BUSIO reset_i2c(); reset_spi(); + reset_uart(); #endif #if CIRCUITPY_PWMIO diff --git a/shared-bindings/busio/UART.c b/shared-bindings/busio/UART.c index 151081d31320..50d233f2b9a8 100644 --- a/shared-bindings/busio/UART.c +++ b/shared-bindings/busio/UART.c @@ -55,7 +55,7 @@ //| :param ~microcontroller.Pin rs485_dir: the output pin for rs485 direction setting, or ``None`` if rs485 not in use. //| :param bool rs485_invert: rs485_dir pin active high when set. Active low otherwise. //| :param int baudrate: the transmit and receive speed. -//| :param int bits: the number of bits per byte, 5 to 8. +//| :param int bits: the number of bits per byte, 5 to 9. //| :param Parity parity: the parity used for error checking. //| :param int stop: the number of stop bits, 1 or 2. //| :param float timeout: the timeout in seconds to wait for the first character and between subsequent characters when reading. Raises ``ValueError`` if timeout >100 seconds. @@ -110,8 +110,8 @@ STATIC mp_obj_t busio_uart_make_new(const mp_obj_type_t *type, size_t n_args, co mp_raise_ValueError(translate("tx and rx cannot both be None")); } - if (args[ARG_bits].u_int < 5 || args[ARG_bits].u_int > 8) { - mp_raise_ValueError(translate("bits must be between 5 and 8")); + if (args[ARG_bits].u_int < 5 || args[ARG_bits].u_int > 9) { + mp_raise_ValueError(translate("bits must be in range 5 to 9")); } uint8_t bits = args[ARG_bits].u_int; From 8170e26a869b1f00e2dc7aade84cb459155bf920 Mon Sep 17 00:00:00 2001 From: microDev <70126934+microDev1@users.noreply.github.com> Date: Thu, 25 Feb 2021 23:46:00 +0530 Subject: [PATCH 3/5] more uart improvements - address suggested changes - refine uart instance availibility checks - improve pin validation and rx buffer handling --- ports/raspberrypi/common-hal/busio/UART.c | 101 ++++++++++++---------- 1 file changed, 54 insertions(+), 47 deletions(-) diff --git a/ports/raspberrypi/common-hal/busio/UART.c b/ports/raspberrypi/common-hal/busio/UART.c index e319b4ccf23a..1f0f4e2f6f04 100644 --- a/ports/raspberrypi/common-hal/busio/UART.c +++ b/ports/raspberrypi/common-hal/busio/UART.c @@ -42,15 +42,15 @@ typedef enum { STATUS_FREE = 0, - STATUS_IN_USE, + STATUS_BUSY, STATUS_NEVER_RESET } uart_status_t; -static uart_status_t uart_status[2]; +static uart_status_t uart_status[NUM_UARTS]; void reset_uart(void) { - for (uint8_t num = 0; num < 2; num++) { - if (uart_status[num] == STATUS_IN_USE) { + for (uint8_t num = 0; num < NUM_UARTS; num++) { + if (uart_status[num] == STATUS_BUSY) { uart_status[num] = STATUS_FREE; uart_deinit(UART_INST(num)); } @@ -61,24 +61,11 @@ void never_reset_uart(uint8_t num) { uart_status[num] = STATUS_NEVER_RESET; } -static uint8_t get_free_uart() { - uint8_t num; - for (num = 0; num < 2; num++) { - if (uart_status[num] == STATUS_FREE) { - break; - } - if (num) { - mp_raise_RuntimeError(translate("All UART peripherals are in use")); - } - } - return num; -} - static uint8_t pin_init(const uint8_t uart, const mcu_pin_obj_t * pin, const uint8_t pin_type) { if (pin == NULL) { return NO_PIN; } - if (!(((pin->number & 3) == pin_type) && ((((pin->number + 4) & 8) >> 3) == uart))) { + if (!(((pin->number % 4) == pin_type) && ((((pin->number + 4) / 8) % NUM_UARTS) == uart))) { mp_raise_ValueError(translate("Invalid pins")); } claim_pin(pin); @@ -86,14 +73,18 @@ static uint8_t pin_init(const uint8_t uart, const mcu_pin_obj_t * pin, const uin return pin->number; } -static ringbuf_t ringbuf[2]; +static ringbuf_t ringbuf[NUM_UARTS]; static void uart0_callback(void) { - while (uart_is_readable(uart0) && !ringbuf_put(&ringbuf[0], (uint8_t)uart_get_hw(uart0)->dr)) {} + while (uart_is_readable(uart0) && ringbuf_num_empty(&ringbuf[0]) > 0) { + ringbuf_put(&ringbuf[0], (uint8_t)uart_get_hw(uart0)->dr); + } } static void uart1_callback(void) { - while (uart_is_readable(uart1) && !ringbuf_put(&ringbuf[1], (uint8_t)uart_get_hw(uart1)->dr)) {} + while (uart_is_readable(uart1) && ringbuf_num_empty(&ringbuf[1]) > 0) { + ringbuf_put(&ringbuf[1], (uint8_t)uart_get_hw(uart1)->dr); + } } void common_hal_busio_uart_construct(busio_uart_obj_t *self, @@ -116,7 +107,13 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, mp_raise_NotImplementedError(translate("RS485 Not yet supported on this device")); } - uint8_t uart_id = get_free_uart(); + uint8_t uart_id = ((((tx != NULL) ? tx->number : rx->number) + 4) / 8) % NUM_UARTS; + + if (uart_status[uart_id] != STATUS_FREE) { + mp_raise_RuntimeError(translate("All UART peripherals are in use")); + } else { + uart_status[uart_id] = STATUS_BUSY; + } self->tx_pin = pin_init(uart_id, tx, 0); self->rx_pin = pin_init(uart_id, rx, 1); @@ -129,7 +126,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, self->timeout_ms = timeout * 1000; uart_init(self->uart, self->baudrate); - uart_set_fifo_enabled(self->uart, false); + uart_set_fifo_enabled(self->uart, true); uart_set_format(self->uart, bits, stop, parity); uart_set_hw_flow(self->uart, (cts != NULL), (rts != NULL)); @@ -144,7 +141,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, if (!ringbuf_alloc(&ringbuf[uart_id], receiver_buffer_size, true)) { mp_raise_msg(&mp_type_MemoryError, translate("Failed to allocate RX buffer")); } - if (uart_id) { + if (uart_id == 1) { self->uart_irq_id = UART1_IRQ; irq_set_exclusive_handler(self->uart_irq_id, uart1_callback); } else { @@ -166,6 +163,7 @@ void common_hal_busio_uart_deinit(busio_uart_obj_t *self) { } uart_deinit(self->uart); ringbuf_free(&ringbuf[self->uart_id]); + uart_status[self->uart_id] = STATUS_FREE; reset_pin_number(self->tx_pin); reset_pin_number(self->rx_pin); reset_pin_number(self->cts_pin); @@ -183,7 +181,7 @@ size_t common_hal_busio_uart_write(busio_uart_obj_t *self, const uint8_t *data, } while (len > 0) { - if (uart_is_writable(self->uart)) { + while (uart_is_writable(self->uart) && len > 0) { // Write and advance. uart_get_hw(self->uart)->dr = *data++; // Decrease how many chars left to write. @@ -206,31 +204,40 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t return 0; } - size_t total_read = 0; - uint64_t start_ticks = supervisor_ticks_ms64(); - - // Busy-wait for all bytes received or timeout - while (len > 0 && (supervisor_ticks_ms64() - start_ticks < self->timeout_ms)) { - // Reset the timeout on every character read. - if (ringbuf_num_filled(&ringbuf[self->uart_id])) { - // Prevent conflict with uart irq. - irq_set_enabled(self->uart_irq_id, false); - // Copy as much received data as available, up to len bytes. - size_t num_read = ringbuf_get_n(&ringbuf[self->uart_id], data, len); - // Re-enable irq. - irq_set_enabled(self->uart_irq_id, true); - len-=num_read; - data+=num_read; - total_read+=num_read; - start_ticks = supervisor_ticks_ms64(); - } - RUN_BACKGROUND_TASKS; - // Allow user to break out of a timeout with a KeyboardInterrupt. - if (mp_hal_is_interrupted()) { - return 0; + // Prevent conflict with uart irq. + irq_set_enabled(self->uart_irq_id, false); + + // Copy as much received data as available, up to len bytes. + size_t total_read = ringbuf_get_n(&ringbuf[self->uart_id], data, len); + + // Check if we still need to read more data. + if (len > total_read) { + len-=total_read; + uint64_t start_ticks = supervisor_ticks_ms64(); + // Busy-wait until timeout or until we've read enough chars. + while (len > 0 && (supervisor_ticks_ms64() - start_ticks < self->timeout_ms)) { + if (uart_is_readable(self->uart)) { + // Read and advance. + *data++ = uart_get_hw(self->uart)->dr; + + // Adjust the counters. + len--; + total_read++; + + // Reset the timeout on every character read. + start_ticks = supervisor_ticks_ms64(); + } + RUN_BACKGROUND_TASKS; + // Allow user to break out of a timeout with a KeyboardInterrupt. + if (mp_hal_is_interrupted()) { + return 0; + } } } + // Re-enable irq. + irq_set_enabled(self->uart_irq_id, true); + if (total_read == 0) { *errcode = EAGAIN; return MP_STREAM_ERROR; From 52bc935fa7aa9e5c94f75fec8b2fa746c83f0be7 Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Thu, 25 Feb 2021 16:50:57 -0800 Subject: [PATCH 4/5] A few minor fixes for corner cases * Always clear the peripheral interrupt so we don't hang when full * Store the ringbuf in the object so it gets collected when we're alive * Make UART objects have a finaliser so they are deinit when their memory is freed * Copy bytes into the ringbuf from the FIFO after we read to ensure the interrupt is enabled ASAP * Copy bytes into the ringbuf from the FIFO before measuring our rx available because the interrupt is based on a threshold (not > 0). For example, a single byte won't trigger an interrupt. --- ports/raspberrypi/common-hal/busio/UART.c | 57 +++++++++++++++++------ ports/raspberrypi/common-hal/busio/UART.h | 1 + py/gc.c | 2 +- py/malloc.c | 6 +-- py/misc.h | 8 ++-- shared-bindings/busio/UART.c | 3 +- tests/manual/busio/uart_echo.py | 18 +++++++ 7 files changed, 72 insertions(+), 23 deletions(-) create mode 100644 tests/manual/busio/uart_echo.py diff --git a/ports/raspberrypi/common-hal/busio/UART.c b/ports/raspberrypi/common-hal/busio/UART.c index 1f0f4e2f6f04..1bc12117773e 100644 --- a/ports/raspberrypi/common-hal/busio/UART.c +++ b/ports/raspberrypi/common-hal/busio/UART.c @@ -73,18 +73,27 @@ static uint8_t pin_init(const uint8_t uart, const mcu_pin_obj_t * pin, const uin return pin->number; } -static ringbuf_t ringbuf[NUM_UARTS]; +static busio_uart_obj_t* active_uarts[NUM_UARTS]; -static void uart0_callback(void) { - while (uart_is_readable(uart0) && ringbuf_num_empty(&ringbuf[0]) > 0) { - ringbuf_put(&ringbuf[0], (uint8_t)uart_get_hw(uart0)->dr); +static void _copy_into_ringbuf(ringbuf_t* r, uart_inst_t* uart) { + while (uart_is_readable(uart) && ringbuf_num_empty(r) > 0) { + ringbuf_put(r, (uint8_t) uart_get_hw(uart)->dr); } } +static void shared_callback(busio_uart_obj_t *self) { + _copy_into_ringbuf(&self->ringbuf, self->uart); + // We always clear the interrupt so it doesn't continue to fire because we + // may not have read everything available. + uart_get_hw(self->uart)->icr = UART_UARTICR_RXIC_BITS; +} + +static void uart0_callback(void) { + shared_callback(active_uarts[0]); +} + static void uart1_callback(void) { - while (uart_is_readable(uart1) && ringbuf_num_empty(&ringbuf[1]) > 0) { - ringbuf_put(&ringbuf[1], (uint8_t)uart_get_hw(uart1)->dr); - } + shared_callback(active_uarts[1]); } void common_hal_busio_uart_construct(busio_uart_obj_t *self, @@ -138,9 +147,10 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, // pointers like this are NOT moved, allocating the buffer // in the long-lived pool is not strictly necessary) // (This is a macro.) - if (!ringbuf_alloc(&ringbuf[uart_id], receiver_buffer_size, true)) { + if (!ringbuf_alloc(&self->ringbuf, receiver_buffer_size, true)) { mp_raise_msg(&mp_type_MemoryError, translate("Failed to allocate RX buffer")); } + active_uarts[uart_id] = self; if (uart_id == 1) { self->uart_irq_id = UART1_IRQ; irq_set_exclusive_handler(self->uart_irq_id, uart1_callback); @@ -149,7 +159,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self, irq_set_exclusive_handler(self->uart_irq_id, uart0_callback); } irq_set_enabled(self->uart_irq_id, true); - uart_set_irq_enables(self->uart, true, false); + uart_set_irq_enables(self->uart, true /* rx has data */, false /* tx needs data */); } } @@ -162,7 +172,8 @@ void common_hal_busio_uart_deinit(busio_uart_obj_t *self) { return; } uart_deinit(self->uart); - ringbuf_free(&ringbuf[self->uart_id]); + ringbuf_free(&self->ringbuf); + active_uarts[self->uart_id] = NULL; uart_status[self->uart_id] = STATUS_FREE; reset_pin_number(self->tx_pin); reset_pin_number(self->rx_pin); @@ -208,7 +219,7 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t irq_set_enabled(self->uart_irq_id, false); // Copy as much received data as available, up to len bytes. - size_t total_read = ringbuf_get_n(&ringbuf[self->uart_id], data, len); + size_t total_read = ringbuf_get_n(&self->ringbuf, data, len); // Check if we still need to read more data. if (len > total_read) { @@ -218,7 +229,7 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t while (len > 0 && (supervisor_ticks_ms64() - start_ticks < self->timeout_ms)) { if (uart_is_readable(self->uart)) { // Read and advance. - *data++ = uart_get_hw(self->uart)->dr; + data[total_read] = uart_get_hw(self->uart)->dr; // Adjust the counters. len--; @@ -230,11 +241,16 @@ size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t RUN_BACKGROUND_TASKS; // Allow user to break out of a timeout with a KeyboardInterrupt. if (mp_hal_is_interrupted()) { - return 0; + break; } } } + // Now that we've emptied the ringbuf some, fill it up with anything in the + // FIFO. This ensures that we'll empty the FIFO as much as possible and + // reset the interrupt when we catch up. + _copy_into_ringbuf(&self->ringbuf, self->uart); + // Re-enable irq. irq_set_enabled(self->uart_irq_id, true); @@ -264,13 +280,24 @@ void common_hal_busio_uart_set_timeout(busio_uart_obj_t *self, mp_float_t timeou } uint32_t common_hal_busio_uart_rx_characters_available(busio_uart_obj_t *self) { - return ringbuf_num_filled(&ringbuf[self->uart_id]); + // Prevent conflict with uart irq. + irq_set_enabled(self->uart_irq_id, false); + // The UART only interrupts after a threshold so make sure to copy anything + // out of its FIFO before measuring how many bytes we've received. + _copy_into_ringbuf(&self->ringbuf, self->uart); + irq_set_enabled(self->uart_irq_id, false); + return ringbuf_num_filled(&self->ringbuf); } void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) { // Prevent conflict with uart irq. irq_set_enabled(self->uart_irq_id, false); - ringbuf_clear(&ringbuf[self->uart_id]); + ringbuf_clear(&self->ringbuf); + + // Throw away the FIFO contents too. + while (uart_is_readable(self->uart)) { + (void) uart_get_hw(self->uart)->dr; + } irq_set_enabled(self->uart_irq_id, true); } diff --git a/ports/raspberrypi/common-hal/busio/UART.h b/ports/raspberrypi/common-hal/busio/UART.h index da6170596b10..4c07de240b34 100644 --- a/ports/raspberrypi/common-hal/busio/UART.h +++ b/ports/raspberrypi/common-hal/busio/UART.h @@ -43,6 +43,7 @@ typedef struct { uint32_t baudrate; uint32_t timeout_ms; uart_inst_t * uart; + ringbuf_t ringbuf; } busio_uart_obj_t; extern void reset_uart(void); diff --git a/py/gc.c b/py/gc.c index 69327060f74c..2aa2668dc4ea 100755 --- a/py/gc.c +++ b/py/gc.c @@ -192,7 +192,7 @@ void gc_init(void *start, void *end) { } void gc_deinit(void) { - // Run any finalizers before we stop using the heap. + // Run any finalisers before we stop using the heap. gc_sweep_all(); MP_STATE_MEM(gc_pool_start) = 0; diff --git a/py/malloc.c b/py/malloc.c index 8d5141ee0463..c923e89a65f5 100644 --- a/py/malloc.c +++ b/py/malloc.c @@ -57,7 +57,7 @@ #undef free #undef realloc #define malloc_ll(b, ll) gc_alloc((b), false, (ll)) -#define malloc_with_finaliser(b) gc_alloc((b), true, false) +#define malloc_with_finaliser(b, ll) gc_alloc((b), true, (ll)) #define free gc_free #define realloc(ptr, n) gc_realloc(ptr, n, true) #define realloc_ext(ptr, n, mv) gc_realloc(ptr, n, mv) @@ -103,8 +103,8 @@ void *m_malloc_maybe(size_t num_bytes, bool long_lived) { } #if MICROPY_ENABLE_FINALISER -void *m_malloc_with_finaliser(size_t num_bytes) { - void *ptr = malloc_with_finaliser(num_bytes); +void *m_malloc_with_finaliser(size_t num_bytes, bool long_lived) { + void *ptr = malloc_with_finaliser(num_bytes, long_lived); if (ptr == NULL && num_bytes != 0) { m_malloc_fail(num_bytes); } diff --git a/py/misc.h b/py/misc.h index 6ed256e705f5..0fef7e249e26 100644 --- a/py/misc.h +++ b/py/misc.h @@ -72,11 +72,13 @@ typedef unsigned int uint; #define m_new_obj_var_maybe(obj_type, var_type, var_num) ((obj_type*)m_malloc_maybe(sizeof(obj_type) + sizeof(var_type) * (var_num), false)) #define m_new_ll_obj_var_maybe(obj_type, var_type, var_num) ((obj_type*)m_malloc_maybe(sizeof(obj_type) + sizeof(var_type) * (var_num), true)) #if MICROPY_ENABLE_FINALISER -#define m_new_obj_with_finaliser(type) ((type*)(m_malloc_with_finaliser(sizeof(type)))) -#define m_new_obj_var_with_finaliser(type, var_type, var_num) ((type*)m_malloc_with_finaliser(sizeof(type) + sizeof(var_type) * (var_num))) +#define m_new_obj_with_finaliser(type) ((type*)(m_malloc_with_finaliser(sizeof(type), false))) +#define m_new_obj_var_with_finaliser(type, var_type, var_num) ((type*)m_malloc_with_finaliser(sizeof(type) + sizeof(var_type) * (var_num), false)) +#define m_new_ll_obj_with_finaliser(type) ((type*)(m_malloc_with_finaliser(sizeof(type), true))) #else #define m_new_obj_with_finaliser(type) m_new_obj(type) #define m_new_obj_var_with_finaliser(type, var_type, var_num) m_new_obj_var(type, var_type, var_num) +#define m_new_ll_obj_with_finaliser(type) m_new_ll_obj(type) #endif #if MICROPY_MALLOC_USES_ALLOCATED_SIZE #define m_renew(type, ptr, old_num, new_num) ((type*)(m_realloc((ptr), sizeof(type) * (old_num), sizeof(type) * (new_num)))) @@ -93,7 +95,7 @@ typedef unsigned int uint; void *m_malloc(size_t num_bytes, bool long_lived); void *m_malloc_maybe(size_t num_bytes, bool long_lived); -void *m_malloc_with_finaliser(size_t num_bytes); +void *m_malloc_with_finaliser(size_t num_bytes, bool long_lived); void *m_malloc0(size_t num_bytes, bool long_lived); #if MICROPY_MALLOC_USES_ALLOCATED_SIZE void *m_realloc(void *ptr, size_t old_num_bytes, size_t new_num_bytes); diff --git a/shared-bindings/busio/UART.c b/shared-bindings/busio/UART.c index 50d233f2b9a8..2f8fc9c322f8 100644 --- a/shared-bindings/busio/UART.c +++ b/shared-bindings/busio/UART.c @@ -82,7 +82,7 @@ STATIC mp_obj_t busio_uart_make_new(const mp_obj_type_t *type, size_t n_args, co // This is needed to avoid crashes with certain UART implementations which // cannot accomodate being moved after creation. (See // https://github.com/adafruit/circuitpython/issues/1056) - busio_uart_obj_t *self = m_new_ll_obj(busio_uart_obj_t); + busio_uart_obj_t *self = m_new_ll_obj_with_finaliser(busio_uart_obj_t); self->base.type = &busio_uart_type; enum { ARG_tx, ARG_rx, ARG_baudrate, ARG_bits, ARG_parity, ARG_stop, ARG_timeout, ARG_receiver_buffer_size, ARG_rts, ARG_cts, ARG_rs485_dir,ARG_rs485_invert}; @@ -387,6 +387,7 @@ const mp_obj_type_t busio_uart_parity_type = { }; STATIC const mp_rom_map_elem_t busio_uart_locals_dict_table[] = { + { MP_ROM_QSTR(MP_QSTR___del__), MP_ROM_PTR(&busio_uart_deinit_obj) }, { MP_ROM_QSTR(MP_QSTR_deinit), MP_ROM_PTR(&busio_uart_deinit_obj) }, { MP_ROM_QSTR(MP_QSTR___enter__), MP_ROM_PTR(&default___enter___obj) }, { MP_ROM_QSTR(MP_QSTR___exit__), MP_ROM_PTR(&busio_uart___exit___obj) }, diff --git a/tests/manual/busio/uart_echo.py b/tests/manual/busio/uart_echo.py new file mode 100644 index 000000000000..f55d4db9ec29 --- /dev/null +++ b/tests/manual/busio/uart_echo.py @@ -0,0 +1,18 @@ +import busio +import board +import time + +i = 0 + +u = busio.UART(tx=board.TX, rx=board.RX) + +while True: + u.write(str(i).encode("utf-8")) + time.sleep(0.1) + print(i, u.in_waiting) # should be the number of digits + time.sleep(0.1) + print(i, u.in_waiting) # should be the number of digits + r = u.read(64 + 10) + print(i, u.in_waiting) # should be 0 + print(len(r), r) + i += 1 From 7562b0cbb8018b288cbaaebd0412371a4ed2ddcf Mon Sep 17 00:00:00 2001 From: Scott Shawcroft Date: Fri, 26 Feb 2021 12:00:01 -0800 Subject: [PATCH 5/5] Turn off GC opt on catwan_usbstick --- ports/atmel-samd/boards/catwan_usbstick/mpconfigboard.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ports/atmel-samd/boards/catwan_usbstick/mpconfigboard.mk b/ports/atmel-samd/boards/catwan_usbstick/mpconfigboard.mk index 892a5371ef29..b1306f54b6d7 100644 --- a/ports/atmel-samd/boards/catwan_usbstick/mpconfigboard.mk +++ b/ports/atmel-samd/boards/catwan_usbstick/mpconfigboard.mk @@ -11,3 +11,5 @@ LONGINT_IMPL = NONE CIRCUITPY_FULL_BUILD = 0 CIRCUITPY_COUNTIO = 0 CIRCUITPY_ROTARYIO = 0 + +SUPEROPT_GC = 0