implement suggested changes

- add internal buffering
- rtc initialization fix
This commit is contained in:
microDev 2021-02-25 00:48:36 +05:30
parent b12ccefbe6
commit 5d7fdafcde
No known key found for this signature in database
GPG Key ID: 2C0867BE60967730
7 changed files with 107 additions and 66 deletions

View File

@ -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

View File

@ -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"));
}

View File

@ -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"));
}

View File

@ -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;

View File

@ -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

View File

@ -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

View File

@ -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;