Merge pull request #3083 from tannewt/esp32s2_busio

Add busio support for the ESP32-S2
This commit is contained in:
Jeff Epler 2020-07-01 21:02:08 -05:00 committed by GitHub
commit fcddfd0f39
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
52 changed files with 1589 additions and 142 deletions

View File

@ -370,6 +370,7 @@ jobs:
board:
- "espressif_saola_1_wroom"
- "espressif_saola_1_wrover"
- "unexpectedmaker_feathers2"
steps:
- name: Set up Python 3.8

View File

@ -243,3 +243,49 @@ stubs:
update-frozen-libraries:
@echo "Updating all frozen libraries to latest tagged version."
cd frozen; for library in *; do cd $$library; ../../tools/git-checkout-latest-tag.sh; cd ..; done
one-of-each: samd21 samd51 esp32s2 litex mimxrt10xx nrf stm
samd21:
$(MAKE) -C ports/atmel-samd BOARD=trinket_m0
samd51:
$(MAKE) -C ports/atmel-samd BOARD=feather_m4_express
esp32s2:
$(MAKE) -C ports/esp32s2 BOARD=espressif_saola_1_wroom
litex:
$(MAKE) -C ports/litex BOARD=fomu
mimxrt10xx:
$(MAKE) -C ports/mimxrt10xx BOARD=feather_mimxrt1011
nrf:
$(MAKE) -C ports/nrf BOARD=feather_nrf52840_express
stm:
$(MAKE) -C ports/stm BOARD=feather_stm32f405_express
clean-one-of-each: clean-samd21 clean-samd51 clean-esp32s2 clean-litex clean-mimxrt10xx clean-nrf clean-stm
clean-samd21:
$(MAKE) -C ports/atmel-samd BOARD=trinket_m0 clean
clean-samd51:
$(MAKE) -C ports/atmel-samd BOARD=feather_m4_express clean
clean-esp32s2:
$(MAKE) -C ports/esp32s2 BOARD=espressif_saola_1_wroom clean
clean-litex:
$(MAKE) -C ports/litex BOARD=fomu clean
clean-mimxrt10xx:
$(MAKE) -C ports/mimxrt10xx BOARD=feather_mimxrt1011 clean
clean-nrf:
$(MAKE) -C ports/nrf BOARD=feather_nrf52840_express clean
clean-stm:
$(MAKE) -C ports/stm BOARD=feather_stm32f405_express clean

View File

@ -341,7 +341,7 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self,
return status >= 0; // Status is number of chars read or an error code < 0.
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uint8_t *data_in, size_t len) {
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len) {
if (len == 0) {
return true;
}
@ -350,7 +350,7 @@ bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uin
status = sercom_dma_transfer(self->spi_desc.dev.prvt, data_out, data_in, len);
} else {
struct spi_xfer xfer;
xfer.txbuf = data_out;
xfer.txbuf = (uint8_t*) data_out;
xfer.rxbuf = data_in;
xfer.size = len;
status = spi_m_sync_transfer(&self->spi_desc, &xfer);

View File

@ -58,7 +58,7 @@ 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, uart_parity_t parity, uint8_t stop,
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) {
@ -195,7 +195,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
SERCOM_USART_CTRLA_FORM_Msk);
sercom->USART.CTRLA.reg |= SERCOM_USART_CTRLA_TXPO(tx_pad / 2) |
SERCOM_USART_CTRLA_RXPO(rx_pad) |
(parity == PARITY_NONE ? 0 : SERCOM_USART_CTRLA_FORM(1));
(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.
@ -206,7 +206,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
SERCOM_USART_CTRLB_CHSIZE_Msk);
sercom->USART.CTRLB.reg |= (have_tx ? SERCOM_USART_CTRLB_TXEN : 0) |
(have_rx ? SERCOM_USART_CTRLB_RXEN : 0) |
(parity == PARITY_ODD ? SERCOM_USART_CTRLB_PMODE : 0) |
(parity == BUSIO_UART_PARITY_ODD ? SERCOM_USART_CTRLB_PMODE : 0) |
(stop > 1 ? SERCOM_USART_CTRLB_SBMODE : 0) |
SERCOM_USART_CTRLB_CHSIZE(bits % 8);

View File

@ -130,7 +130,7 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self, uint8_t *data, size_t len,
return true;
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uint8_t *data_in, size_t len) {
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len) {
SPI_EXCHANGE(self->spi_dev, data_out, data_in, len);
return true;

View File

@ -56,7 +56,7 @@ 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, uart_parity_t parity, uint8_t stop,
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) {
struct termios tio;
@ -69,7 +69,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
mp_raise_ValueError(translate("Could not initialize UART"));
}
if (parity != PARITY_NONE) {
if (parity != BUSIO_UART_PARITY_NONE) {
mp_raise_ValueError(translate("Could not initialize UART"));
}

View File

@ -78,6 +78,7 @@ INC += -Iesp-idf/components/freertos/xtensa/include
INC += -Iesp-idf/components/esp32s2/include
INC += -Iesp-idf/components/xtensa/esp32s2/include
INC += -Iesp-idf/components/esp_common/include
INC += -Iesp-idf/components/esp_ringbuf/include
INC += -Iesp-idf/components/esp_rom/include
INC += -Iesp-idf/components/xtensa/include
INC += -Iesp-idf/components/esp_timer/include
@ -257,7 +258,7 @@ ESP_AUTOGEN_LD = $(BUILD)/esp-idf/esp-idf/esp32s2/esp32s2_out.ld $(BUILD)/esp-id
FLASH_FLAGS = --flash_mode $(CIRCUITPY_ESP_FLASH_MODE) --flash_freq $(CIRCUITPY_ESP_FLASH_FREQ) --flash_size $(CIRCUITPY_ESP_FLASH_SIZE)
all: $(BUILD)/firmware.bin
all: $(BUILD)/firmware.bin $(BUILD)/firmware.uf2
$(BUILD)/firmware.elf: $(OBJ) | $(ESP_IDF_COMPONENTS_EXPANDED) $(ESP_AUTOGEN_LD)
$(STEPECHO) "LINK $@"
@ -273,8 +274,15 @@ $(BUILD)/circuitpython-firmware.bin: $(BUILD)/firmware.elf
$(BUILD)/firmware.bin: $(BUILD)/esp-idf/partition_table/partition-table.bin $(BUILD)/esp-idf/bootloader/bootloader.bin $(BUILD)/circuitpython-firmware.bin
$(Q)$(PYTHON) ../../tools/join_bins.py $@ 0x1000 $(BUILD)/esp-idf/bootloader/bootloader.bin 0x8000 $(BUILD)/esp-idf/partition_table/partition-table.bin 0x10000 $(BUILD)/circuitpython-firmware.bin
$(BUILD)/firmware.uf2: $(BUILD)/circuitpython-firmware.bin
$(STEPECHO) "Create $@"
$(Q)$(PYTHON3) $(TOP)/tools/uf2/utils/uf2conv.py -f 0xbfdd4eee -b 0x0000 -c -o $@ $^
flash: $(BUILD)/firmware.bin
esptool.py --chip esp32s2 -p $(PORT) -b 460800 --before=default_reset --after=hard_reset write_flash $(FLASH_FLAGS) 0x0000 $^
esptool.py --chip esp32s2 -p $(PORT) --no-stub -b 460800 --before=default_reset --after=hard_reset write_flash $(FLASH_FLAGS) 0x0000 $^
flash-circuitpython-only: $(BUILD)/circuitpython-firmware.bin
esptool.py --chip esp32s2 -p $(PORT) --no-stub -b 460800 --before=default_reset --after=hard_reset write_flash $(FLASH_FLAGS) 0x10000 $^
include $(TOP)/py/mkrules.mk

View File

@ -47,16 +47,14 @@ void run_background_tasks(void) {
return;
}
// Delay for 1 tick so that we don't starve the idle task.
// TODO: 1 tick is 10ms which is a long time! Can we delegate to idle for a minimal amount of
// time?
vTaskDelay(1);
// Zero delay in case FreeRTOS wants to switch to something else.
vTaskDelay(0);
running_background_tasks = true;
filesystem_background();
// #if CIRCUITPY_DISPLAYIO
// displayio_background();
// #endif
#if CIRCUITPY_DISPLAYIO
displayio_background();
#endif
running_background_tasks = false;
assert_heap_ok();

View File

@ -30,12 +30,12 @@
void board_init(void) {
// USB
never_reset_pin(&pin_GPIO19);
never_reset_pin(&pin_GPIO20);
common_hal_never_reset_pin(&pin_GPIO19);
common_hal_never_reset_pin(&pin_GPIO20);
// Debug UART
never_reset_pin(&pin_GPIO43);
never_reset_pin(&pin_GPIO44);
common_hal_never_reset_pin(&pin_GPIO43);
common_hal_never_reset_pin(&pin_GPIO44);
}
bool board_requests_safe_mode(void) {

View File

@ -11,8 +11,6 @@ LONGINT_IMPL = MPZ
CFLAGS += -DCFG_TUD_TASK_QUEUE_SZ=32
CIRCUITPY_NEOPIXEL_WRITE = 0
CIRCUITPY_DIGITALIO = 0
CIRCUITPY_MICROCONTROLLER = 0
CIRCUITPY_ESP_FLASH_MODE=dio
CIRCUITPY_ESP_FLASH_FREQ=40m

View File

@ -30,12 +30,12 @@
void board_init(void) {
// USB
never_reset_pin(&pin_GPIO19);
never_reset_pin(&pin_GPIO20);
common_hal_never_reset_pin(&pin_GPIO19);
common_hal_never_reset_pin(&pin_GPIO20);
// Debug UART
never_reset_pin(&pin_GPIO43);
never_reset_pin(&pin_GPIO44);
common_hal_never_reset_pin(&pin_GPIO43);
common_hal_never_reset_pin(&pin_GPIO44);
}
bool board_requests_safe_mode(void) {

View File

@ -11,8 +11,6 @@ LONGINT_IMPL = MPZ
CFLAGS += -DCFG_TUD_TASK_QUEUE_SZ=32
CIRCUITPY_NEOPIXEL_WRITE = 0
CIRCUITPY_DIGITALIO = 0
CIRCUITPY_MICROCONTROLLER = 0
CIRCUITPY_ESP_FLASH_MODE=dio
CIRCUITPY_ESP_FLASH_FREQ=40m

View File

@ -0,0 +1,56 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "boards/board.h"
#include "mpconfigboard.h"
#include "shared-bindings/microcontroller/Pin.h"
void board_init(void) {
// USB
common_hal_never_reset_pin(&pin_GPIO19);
common_hal_never_reset_pin(&pin_GPIO20);
// Debug UART
common_hal_never_reset_pin(&pin_GPIO43);
common_hal_never_reset_pin(&pin_GPIO44);
// SPI Flash and RAM
common_hal_never_reset_pin(&pin_GPIO26);
common_hal_never_reset_pin(&pin_GPIO27);
common_hal_never_reset_pin(&pin_GPIO28);
common_hal_never_reset_pin(&pin_GPIO29);
common_hal_never_reset_pin(&pin_GPIO30);
common_hal_never_reset_pin(&pin_GPIO31);
common_hal_never_reset_pin(&pin_GPIO32);
}
bool board_requests_safe_mode(void) {
return false;
}
void reset_board(void) {
}

View File

@ -0,0 +1,36 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Scott Shawcroft for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
//Micropython setup
#define MICROPY_HW_BOARD_NAME "FeatherS2"
#define MICROPY_HW_MCU_NAME "ESP32S2"
#define AUTORESET_DELAY_MS 500
// Doesn't work with this on.
// #define MICROPY_HW_APA102_MOSI (&pin_GPIO44)
// #define MICROPY_HW_APA102_SCK (&pin_GPIO45)

View File

@ -0,0 +1,21 @@
USB_VID = 0x239A
USB_PID = 0x80AC
USB_PRODUCT = "FeatherS2"
USB_MANUFACTURER = "UnexpectedMaker"
USB_DEVICES = "CDC,MSC,HID"
INTERNAL_FLASH_FILESYSTEM = 1
LONGINT_IMPL = MPZ
# The default queue depth of 16 overflows on release builds,
# so increase it to 32.
CFLAGS += -DCFG_TUD_TASK_QUEUE_SZ=32
CIRCUITPY_NEOPIXEL_WRITE = 0
CIRCUITPY_ESP_FLASH_MODE=qio
CIRCUITPY_ESP_FLASH_FREQ=40m
CIRCUITPY_ESP_FLASH_SIZE=16MB
CIRCUITPY_BITBANG_APA102 = 1

View File

@ -0,0 +1,57 @@
#include "shared-bindings/board/__init__.h"
STATIC const mp_rom_map_elem_t board_global_dict_table[] = {
{ MP_ROM_QSTR(MP_QSTR_A0), MP_ROM_PTR(&pin_GPIO17) },
{ MP_ROM_QSTR(MP_QSTR_D14), MP_ROM_PTR(&pin_GPIO17) },
{ MP_ROM_QSTR(MP_QSTR_A1), MP_ROM_PTR(&pin_GPIO18) },
{ MP_ROM_QSTR(MP_QSTR_D15), MP_ROM_PTR(&pin_GPIO18) },
{ MP_ROM_QSTR(MP_QSTR_A2), MP_ROM_PTR(&pin_GPIO14) },
{ MP_ROM_QSTR(MP_QSTR_D16), MP_ROM_PTR(&pin_GPIO14) },
{ MP_ROM_QSTR(MP_QSTR_A3), MP_ROM_PTR(&pin_GPIO12) },
{ MP_ROM_QSTR(MP_QSTR_D17), MP_ROM_PTR(&pin_GPIO12) },
{ MP_ROM_QSTR(MP_QSTR_A4), MP_ROM_PTR(&pin_GPIO6) },
{ MP_ROM_QSTR(MP_QSTR_D18), MP_ROM_PTR(&pin_GPIO6) },
{ MP_ROM_QSTR(MP_QSTR_A5), MP_ROM_PTR(&pin_GPIO5) },
{ MP_ROM_QSTR(MP_QSTR_D19), MP_ROM_PTR(&pin_GPIO5) },
{ MP_ROM_QSTR(MP_QSTR_SCK), MP_ROM_PTR(&pin_GPIO36) },
{ MP_ROM_QSTR(MP_QSTR_D25), MP_ROM_PTR(&pin_GPIO36) },
{ MP_ROM_QSTR(MP_QSTR_MOSI), MP_ROM_PTR(&pin_GPIO35) },
{ MP_ROM_QSTR(MP_QSTR_D24), MP_ROM_PTR(&pin_GPIO35) },
{ MP_ROM_QSTR(MP_QSTR_MISO), MP_ROM_PTR(&pin_GPIO37) },
{ MP_ROM_QSTR(MP_QSTR_D23), MP_ROM_PTR(&pin_GPIO37) },
{ MP_ROM_QSTR(MP_QSTR_D0), MP_ROM_PTR(&pin_GPIO44) },
{ MP_ROM_QSTR(MP_QSTR_RX), MP_ROM_PTR(&pin_GPIO44) },
{ MP_ROM_QSTR(MP_QSTR_D1), MP_ROM_PTR(&pin_GPIO43) },
{ MP_ROM_QSTR(MP_QSTR_TX), MP_ROM_PTR(&pin_GPIO43) },
// Moving to 9 and 8
{ MP_ROM_QSTR(MP_QSTR_SDA), MP_ROM_PTR(&pin_GPIO38) },
{ MP_ROM_QSTR(MP_QSTR_SCL), MP_ROM_PTR(&pin_GPIO33) },
{ MP_ROM_QSTR(MP_QSTR_D5), MP_ROM_PTR(&pin_GPIO1) },
{ MP_ROM_QSTR(MP_QSTR_D6), MP_ROM_PTR(&pin_GPIO3) },
{ MP_ROM_QSTR(MP_QSTR_D9), MP_ROM_PTR(&pin_GPIO7) },
{ MP_ROM_QSTR(MP_QSTR_D10), MP_ROM_PTR(&pin_GPIO8) },
{ MP_ROM_QSTR(MP_QSTR_D11), MP_ROM_PTR(&pin_GPIO9) },
{ MP_ROM_QSTR(MP_QSTR_D12), MP_ROM_PTR(&pin_GPIO10) },
{ MP_ROM_QSTR(MP_QSTR_D13), MP_ROM_PTR(&pin_GPIO11) },
{ MP_ROM_QSTR(MP_QSTR_APA102_MOSI), MP_ROM_PTR(&pin_GPIO44) }, // MTDO
{ MP_ROM_QSTR(MP_QSTR_APA102_SCK), MP_ROM_PTR(&pin_GPIO45) },
{ MP_ROM_QSTR(MP_QSTR_LED), MP_ROM_PTR(&pin_GPIO13) },
{ MP_ROM_QSTR(MP_QSTR_I2C), MP_ROM_PTR(&board_i2c_obj) },
{ MP_ROM_QSTR(MP_QSTR_SPI), MP_ROM_PTR(&board_spi_obj) },
{ MP_ROM_QSTR(MP_QSTR_UART), MP_ROM_PTR(&board_uart_obj) },
};
MP_DEFINE_CONST_DICT(board_module_globals, board_global_dict_table);

View File

@ -0,0 +1,228 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Scott Shawcroft for Adafruit Industries LLC
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "shared-bindings/busio/I2C.h"
#include "py/mperrno.h"
#include "py/runtime.h"
#include "driver/i2c.h"
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/microcontroller/Pin.h"
#include "supervisor/shared/translate.h"
typedef enum {
STATUS_FREE = 0,
STATUS_IN_USE,
STATUS_NEVER_RESET
} i2c_status_t;
static i2c_status_t i2c_status[I2C_NUM_MAX];
void never_reset_i2c(i2c_port_t num) {
i2c_status[num] = STATUS_NEVER_RESET;
}
void i2c_reset(void) {
for (i2c_port_t num = 0; num < I2C_NUM_MAX; num++) {
if (i2c_status[num] == STATUS_IN_USE) {
i2c_driver_delete(num);
i2c_status[num] = STATUS_FREE;
}
}
}
void common_hal_busio_i2c_construct(busio_i2c_obj_t *self,
const mcu_pin_obj_t* scl, const mcu_pin_obj_t* sda, uint32_t frequency, uint32_t timeout) {
// Pins 45 and 46 are "strapping" pins that impact start up behavior. They usually need to
// be pulled-down so pulling them up for I2C is a bad idea. To make this hard, we don't
// support I2C on these pins.
//
// 46 is also input-only so it'll never work.
if (scl->number == 45 || scl->number == 46 || sda->number == 45 || sda->number == 46) {
mp_raise_ValueError(translate("Invalid pins"));
}
#if CIRCUITPY_REQUIRE_I2C_PULLUPS
// Test that the pins are in a high state. (Hopefully indicating they are pulled up.)
gpio_set_direction(sda->number, GPIO_MODE_DEF_INPUT);
gpio_set_direction(scl->number, GPIO_MODE_DEF_INPUT);
gpio_pulldown_en(sda->number);
gpio_pulldown_en(scl->number);
common_hal_mcu_delay_us(10);
gpio_pulldown_dis(sda->number);
gpio_pulldown_dis(scl->number);
// We must pull up within 3us to achieve 400khz.
common_hal_mcu_delay_us(3);
if (gpio_get_level(sda->number) == 0 || gpio_get_level(scl->number) == 0) {
reset_pin_number(sda->number);
reset_pin_number(scl->number);
mp_raise_RuntimeError(translate("SDA or SCL needs a pull up"));
}
#endif
if (xSemaphoreCreateBinaryStatic(&self->semaphore) != &self->semaphore) {
mp_raise_RuntimeError(translate("Unable to create lock"));
}
xSemaphoreGive(&self->semaphore);
self->sda_pin = sda;
self->scl_pin = scl;
self->i2c_num = I2C_NUM_MAX;
for (i2c_port_t num = 0; num < I2C_NUM_MAX; num++) {
if (i2c_status[num] == STATUS_FREE) {
self->i2c_num = num;
}
}
if (self->i2c_num == I2C_NUM_MAX) {
mp_raise_ValueError(translate("All I2C peripherals are in use"));
}
i2c_status[self->i2c_num] = STATUS_IN_USE;
i2c_config_t i2c_conf = {
.mode = I2C_MODE_MASTER,
.sda_io_num = self->sda_pin->number,
.scl_io_num = self->scl_pin->number,
.sda_pullup_en = GPIO_PULLUP_DISABLE, /*!< Internal GPIO pull mode for I2C sda signal*/
.scl_pullup_en = GPIO_PULLUP_DISABLE, /*!< Internal GPIO pull mode for I2C scl signal*/
.master = {
.clk_speed = frequency,
}
};
esp_err_t result = i2c_param_config(self->i2c_num, &i2c_conf);
if (result != ESP_OK) {
mp_raise_ValueError(translate("Invalid pins"));
}
result = i2c_driver_install(self->i2c_num,
I2C_MODE_MASTER,
0,
0,
0);
if (result != ESP_OK) {
mp_raise_OSError(MP_EIO);
}
claim_pin(sda);
claim_pin(scl);
}
bool common_hal_busio_i2c_deinited(busio_i2c_obj_t *self) {
return self->sda_pin == NULL;
}
void common_hal_busio_i2c_deinit(busio_i2c_obj_t *self) {
if (common_hal_busio_i2c_deinited(self)) {
return;
}
i2c_driver_delete(self->i2c_num);
i2c_status[self->i2c_num] = STATUS_FREE;
common_hal_reset_pin(self->sda_pin);
common_hal_reset_pin(self->scl_pin);
self->sda_pin = NULL;
self->scl_pin = NULL;
}
bool common_hal_busio_i2c_probe(busio_i2c_obj_t *self, uint8_t addr) {
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, addr << 1, true);
i2c_master_stop(cmd);
esp_err_t result = i2c_master_cmd_begin(self->i2c_num, cmd, 10);
i2c_cmd_link_delete(cmd);
return result == ESP_OK;
}
bool common_hal_busio_i2c_try_lock(busio_i2c_obj_t *self) {
if (self->has_lock) {
return false;
}
self->has_lock = xSemaphoreTake(&self->semaphore, 0) == pdTRUE;
return self->has_lock;
}
bool common_hal_busio_i2c_has_lock(busio_i2c_obj_t *self) {
return self->has_lock;
}
void common_hal_busio_i2c_unlock(busio_i2c_obj_t *self) {
xSemaphoreGive(&self->semaphore);
self->has_lock = false;
}
uint8_t common_hal_busio_i2c_write(busio_i2c_obj_t *self, uint16_t addr,
const uint8_t *data, size_t len, bool transmit_stop_bit) {
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, addr << 1, true);
i2c_master_write(cmd, (uint8_t*) data, len, true);
if (transmit_stop_bit) {
i2c_master_stop(cmd);
}
esp_err_t result = i2c_master_cmd_begin(self->i2c_num, cmd, 100 /* wait in ticks */);
i2c_cmd_link_delete(cmd);
if (result == ESP_OK) {
return 0;
} else if (result == ESP_FAIL) {
return MP_ENODEV;
}
return MP_EIO;
}
uint8_t common_hal_busio_i2c_read(busio_i2c_obj_t *self, uint16_t addr,
uint8_t *data, size_t len) {
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, addr << 1 | 1, true); // | 1 to indicate read
if (len > 1) {
i2c_master_read(cmd, data, len - 1, 0);
}
i2c_master_read_byte(cmd, data + len - 1, 1);
i2c_master_stop(cmd);
esp_err_t result = i2c_master_cmd_begin(self->i2c_num, cmd, 100 /* wait in ticks */);
i2c_cmd_link_delete(cmd);
if (result == ESP_OK) {
return 0;
} else if (result == ESP_FAIL) {
return MP_ENODEV;
}
return MP_EIO;
}
void common_hal_busio_i2c_never_reset(busio_i2c_obj_t *self) {
never_reset_i2c(self->i2c_num);
common_hal_never_reset_pin(self->scl_pin);
common_hal_never_reset_pin(self->sda_pin);
}

View File

@ -0,0 +1,48 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_I2C_H
#define MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_I2C_H
#include "common-hal/microcontroller/Pin.h"
#include "esp-idf/components/soc/include/hal/i2c_types.h"
#include "FreeRTOS.h"
#include "freertos/semphr.h"
#include "py/obj.h"
typedef struct {
mp_obj_base_t base;
const mcu_pin_obj_t* scl_pin;
const mcu_pin_obj_t* sda_pin;
i2c_port_t i2c_num;
StaticSemaphore_t semaphore;
bool has_lock;
} busio_i2c_obj_t;
void i2c_reset(void);
#endif // MICROPY_INCLUDED_ATMEL_SAMD_COMMON_HAL_BUSIO_I2C_H

View File

@ -0,0 +1,33 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Scott Shawcroft
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_ONEWIRE_H
#define MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_ONEWIRE_H
// Use bitbangio.
#include "shared-module/busio/OneWire.h"
#endif // MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_ONEWIRE_H

View File

@ -0,0 +1,358 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "shared-bindings/busio/SPI.h"
#include "py/mperrno.h"
#include "py/runtime.h"
#include "boards/board.h"
#include "shared-bindings/microcontroller/Pin.h"
#include "supervisor/shared/rgb_led_status.h"
static bool spi_never_reset[SOC_SPI_PERIPH_NUM];
// Store one lock handle per device so that we can free it.
static spi_bus_lock_dev_handle_t lock_dev_handle[SOC_SPI_PERIPH_NUM];
static intr_handle_t intr_handle[SOC_SPI_PERIPH_NUM];
void spi_reset(void) {
for (spi_host_device_t host_id = SPI2_HOST; host_id < SOC_SPI_PERIPH_NUM; host_id++) {
if (spi_never_reset[host_id]) {
continue;
}
bool in_use = false;
if (lock_dev_handle[host_id] != NULL) {
spi_bus_lock_unregister_dev(lock_dev_handle[host_id]);
lock_dev_handle[host_id] = NULL;
in_use = true;
}
if (intr_handle[host_id] != NULL) {
esp_intr_free(intr_handle[host_id]);
intr_handle[host_id] = NULL;
in_use = true;
}
if (in_use) {
spi_bus_free(host_id);
}
}
}
// This is copied in from the ESP-IDF because it is static.
// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
static bool bus_uses_iomux_pins(spi_host_device_t host, const spi_bus_config_t* bus_config)
{
if (bus_config->sclk_io_num>=0 &&
bus_config->sclk_io_num != spi_periph_signal[host].spiclk_iomux_pin) return false;
if (bus_config->quadwp_io_num>=0 &&
bus_config->quadwp_io_num != spi_periph_signal[host].spiwp_iomux_pin) return false;
if (bus_config->quadhd_io_num>=0 &&
bus_config->quadhd_io_num != spi_periph_signal[host].spihd_iomux_pin) return false;
if (bus_config->mosi_io_num >= 0 &&
bus_config->mosi_io_num != spi_periph_signal[host].spid_iomux_pin) return false;
if (bus_config->miso_io_num>=0 &&
bus_config->miso_io_num != spi_periph_signal[host].spiq_iomux_pin) return false;
return true;
}
// End copied code.
static bool spi_bus_is_free(spi_host_device_t host_id) {
return spi_bus_get_attr(host_id) == NULL;
}
static void spi_interrupt_handler(void *arg) {
// busio_spi_obj_t *self = arg;
}
// The interrupt may get invoked by the bus lock.
static void spi_bus_intr_enable(void *self)
{
esp_intr_enable(((busio_spi_obj_t *)self)->interrupt);
}
// The interrupt is always disabled by the ISR itself, not exposed
static void spi_bus_intr_disable(void *self)
{
esp_intr_disable(((busio_spi_obj_t *)self)->interrupt);
}
void common_hal_busio_spi_construct(busio_spi_obj_t *self,
const mcu_pin_obj_t * clock, const mcu_pin_obj_t * mosi,
const mcu_pin_obj_t * miso) {
spi_bus_config_t bus_config;
bus_config.mosi_io_num = mosi != NULL ? mosi->number : -1;
bus_config.miso_io_num = miso != NULL ? miso->number : -1;
bus_config.sclk_io_num = clock != NULL ? clock->number : -1;
bus_config.quadwp_io_num = -1;
bus_config.quadhd_io_num = -1;
bus_config.max_transfer_sz = 0; // Uses the default
bus_config.flags = SPICOMMON_BUSFLAG_MASTER | SPICOMMON_BUSFLAG_SCLK |
(mosi != NULL ? SPICOMMON_BUSFLAG_MOSI : 0) |
(miso != NULL ? SPICOMMON_BUSFLAG_MISO : 0);
bus_config.intr_flags = 0;
// RAM and Flash is often on SPI1 and is unsupported by the IDF so use it as
// a flag value.
spi_host_device_t host_id = SPI1_HOST;
self->connected_through_gpio = true;
// Try and save SPI2 for pins that are on the IOMUX
if (bus_uses_iomux_pins(SPI2_HOST, &bus_config) && spi_bus_is_free(SPI2_HOST)) {
host_id = SPI2_HOST;
self->connected_through_gpio = false;
} else if (spi_bus_is_free(SPI3_HOST)) {
host_id = SPI3_HOST;
} else if (spi_bus_is_free(SPI2_HOST)) {
host_id = SPI2_HOST;
}
if (host_id == SPI1_HOST) {
mp_raise_ValueError(translate("All SPI peripherals are in use"));
}
esp_err_t result = spi_bus_initialize(host_id, &bus_config, host_id /* dma channel */);
if (result == ESP_ERR_NO_MEM) {
mp_raise_msg(&mp_type_MemoryError, translate("ESP-IDF memory allocation failed"));
} else if (result == ESP_ERR_INVALID_ARG) {
mp_raise_ValueError(translate("Invalid pins"));
}
// After this point, we need to deinit to free IDF memory so fill out self's pins.
self->clock_pin = clock;
self->MOSI_pin = mosi;
self->MISO_pin = miso;
self->host_id = host_id;
spi_bus_lock_dev_config_t config = { .flags = 0 };
// The returned lock is stored in the bus lock but must be freed separately with
// spi_bus_lock_unregister_dev.
result = spi_bus_lock_register_dev(spi_bus_get_attr(host_id)->lock,
&config,
&self->lock);
if (result == ESP_ERR_NO_MEM) {
common_hal_busio_spi_deinit(self);
mp_raise_msg(&mp_type_MemoryError, translate("ESP-IDF memory allocation failed"));
}
lock_dev_handle[host_id] = self->lock;
result = esp_intr_alloc(spicommon_irqsource_for_host(host_id),
bus_config.intr_flags | ESP_INTR_FLAG_INTRDISABLED,
spi_interrupt_handler, self, &self->interrupt);
if (result == ESP_ERR_NO_MEM) {
common_hal_busio_spi_deinit(self);
mp_raise_msg(&mp_type_MemoryError, translate("ESP-IDF memory allocation failed"));
}
intr_handle[host_id] = self->interrupt;
spi_bus_lock_set_bg_control(spi_bus_get_attr(host_id)->lock, spi_bus_intr_enable, spi_bus_intr_disable, self);
spi_hal_context_t* hal = &self->hal_context;
// spi_hal_init clears the given hal context so set everything after.
spi_hal_init(hal, host_id);
hal->dmadesc_tx = &self->tx_dma;
hal->dmadesc_rx = &self->rx_dma;
hal->dmadesc_n = 1;
// We don't use native CS.
// hal->cs_setup = 0;
// hal->cs_hold = 0;
// hal->cs_pin_id = 0;
hal->sio = 0;
hal->half_duplex = 0;
// hal->tx_lsbfirst = 0;
// hal->rx_lsbfirst = 0;
hal->dma_enabled = 1;
hal->no_compensate = 1;
// Ignore CS bits
// We don't use cmd, addr or dummy bits.
// hal->cmd = 0;
// hal->cmd_bits = 0;
// hal->addr_bits = 0;
// hal->dummy_bits = 0;
// hal->addr = 0;
hal->io_mode = SPI_LL_IO_MODE_NORMAL;
common_hal_busio_spi_configure(self, 250000, 0, 0, 8);
}
void common_hal_busio_spi_never_reset(busio_spi_obj_t *self) {
spi_never_reset[self->host_id] = true;
common_hal_never_reset_pin(self->clock_pin);
common_hal_never_reset_pin(self->MOSI_pin);
common_hal_never_reset_pin(self->MISO_pin);
}
bool common_hal_busio_spi_deinited(busio_spi_obj_t *self) {
return self->clock_pin == NULL;
}
void common_hal_busio_spi_deinit(busio_spi_obj_t *self) {
if (common_hal_busio_spi_deinited(self)) {
return;
}
spi_never_reset[self->host_id] = false;
if (self->lock != NULL) {
spi_bus_lock_unregister_dev(self->lock);
lock_dev_handle[self->host_id] = NULL;
}
if (self->interrupt != NULL) {
esp_intr_free(self->interrupt);
intr_handle[self->host_id] = NULL;
}
spi_bus_free(self->host_id);
common_hal_reset_pin(self->clock_pin);
common_hal_reset_pin(self->MOSI_pin);
common_hal_reset_pin(self->MISO_pin);
self->clock_pin = NULL;
}
bool common_hal_busio_spi_configure(busio_spi_obj_t *self,
uint32_t baudrate, uint8_t polarity, uint8_t phase, uint8_t bits) {
if (baudrate == self->target_frequency &&
polarity == self->polarity &&
phase == self->phase &&
bits == self->bits) {
return true;
}
self->hal_context.mode = polarity << 1 | phase;
self->polarity = polarity;
self->phase = phase;
self->bits = bits;
self->target_frequency = baudrate;
self->hal_context.timing_conf = &self->timing_conf;
esp_err_t result = spi_hal_get_clock_conf(&self->hal_context,
self->target_frequency,
128 /* duty_cycle */,
self->connected_through_gpio,
0 /* input_delay_ns */,
&self->real_frequency,
&self->timing_conf);
if (result != ESP_OK) {
return false;
}
spi_hal_setup_device(&self->hal_context);
return true;
}
bool common_hal_busio_spi_try_lock(busio_spi_obj_t *self) {
// If our lock has already been taken then return false because someone else
// may already grabbed it in our call stack.
if (self->has_lock) {
return false;
}
// Wait to grab the lock from another task.
esp_err_t result = spi_bus_lock_acquire_start(self->lock, portMAX_DELAY);
self->has_lock = result == ESP_OK;
return self->has_lock;
}
bool common_hal_busio_spi_has_lock(busio_spi_obj_t *self) {
return self->has_lock;
}
void common_hal_busio_spi_unlock(busio_spi_obj_t *self) {
spi_bus_lock_acquire_end(self->lock);
self->has_lock = false;
}
bool common_hal_busio_spi_write(busio_spi_obj_t *self,
const uint8_t *data, size_t len) {
return common_hal_busio_spi_transfer(self, data, NULL, len);
}
bool common_hal_busio_spi_read(busio_spi_obj_t *self,
uint8_t *data, size_t len, uint8_t write_value) {
return common_hal_busio_spi_transfer(self, NULL, data, len);
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len) {
if (len == 0) {
return true;
}
spi_hal_context_t* hal = &self->hal_context;
hal->send_buffer = NULL;
hal->rcv_buffer = NULL;
// Reset timing_conf in case we've moved since the last time we used it.
hal->timing_conf = &self->timing_conf;
// This rounds up.
size_t dma_count = (len + LLDESC_MAX_NUM_PER_DESC - 1) / LLDESC_MAX_NUM_PER_DESC;
for (size_t i = 0; i < dma_count; i++) {
size_t offset = LLDESC_MAX_NUM_PER_DESC * i;
size_t dma_len = len - offset;
if (dma_len > LLDESC_MAX_NUM_PER_DESC) {
dma_len = LLDESC_MAX_NUM_PER_DESC;
}
hal->tx_bitlen = dma_len * self->bits;
hal->rx_bitlen = dma_len * self->bits;
if (data_out != NULL) {
hal->send_buffer = (uint8_t*) data_out + offset;
}
if (data_in != NULL) {
hal->rcv_buffer = data_in + offset;
}
spi_hal_setup_trans(hal);
spi_hal_prepare_data(hal);
spi_hal_user_start(hal);
// TODO: Switch to waiting on a lock that is given by an interrupt.
while (!spi_hal_usr_is_done(hal)) {
RUN_BACKGROUND_TASKS;
}
spi_hal_fetch_result(hal);
}
return true;
}
uint32_t common_hal_busio_spi_get_frequency(busio_spi_obj_t* self) {
return self->real_frequency;
}
uint8_t common_hal_busio_spi_get_phase(busio_spi_obj_t* self) {
return self->phase;
}
uint8_t common_hal_busio_spi_get_polarity(busio_spi_obj_t* self) {
return self->polarity;
}

View File

@ -0,0 +1,62 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_SPI_H
#define MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_SPI_H
#include "common-hal/microcontroller/Pin.h"
#include "esp-idf/components/driver/include/driver/spi_common_internal.h"
#include "esp-idf/components/soc/include/hal/spi_hal.h"
#include "esp-idf/components/soc/include/hal/spi_types.h"
#include "py/obj.h"
typedef struct {
mp_obj_base_t base;
const mcu_pin_obj_t* clock_pin;
const mcu_pin_obj_t* MOSI_pin;
const mcu_pin_obj_t* MISO_pin;
spi_host_device_t host_id;
spi_bus_lock_dev_handle_t lock;
spi_hal_context_t hal_context;
spi_hal_timing_conf_t timing_conf;
intr_handle_t interrupt;
// IDF allocates these in DMA accessible memory so they may need to move when
// we use external RAM for CircuitPython.
lldesc_t tx_dma;
lldesc_t rx_dma;
uint32_t target_frequency;
int32_t real_frequency;
uint8_t polarity;
uint8_t phase;
uint8_t bits;
bool has_lock;
bool connected_through_gpio;
} busio_spi_obj_t;
void spi_reset(void);
#endif // MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_SPI_H

View File

@ -0,0 +1,348 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2020 Scott Shawcroft for Adafruit Industries LLC
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "shared-bindings/microcontroller/__init__.h"
#include "shared-bindings/busio/UART.h"
#include "driver/uart.h"
#include "mpconfigport.h"
#include "lib/utils/interrupt_char.h"
#include "py/gc.h"
#include "py/mperrno.h"
#include "py/runtime.h"
#include "py/stream.h"
#include "supervisor/shared/translate.h"
#include "supervisor/shared/tick.h"
void uart_reset(void) {
for (uart_port_t num = 0; num < UART_NUM_MAX; num++) {
// Ignore the UART used by the IDF.
#ifdef CONFIG_CONSOLE_UART_NUM
if (num == CONFIG_CONSOLE_UART_NUM) {
continue;
}
#endif
if (uart_is_driver_installed(num)) {
uart_driver_delete(num);
}
}
}
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) {
if (bits > 8) {
mp_raise_NotImplementedError(translate("bytes > 8 bits not supported"));
}
bool have_tx = tx != NULL;
bool have_rx = rx != NULL;
bool have_rts = rts != NULL;
bool have_cts = cts != NULL;
bool have_rs485_dir = rs485_dir != NULL;
if (!have_tx && !have_rx) {
mp_raise_ValueError(translate("tx and rx cannot both be None"));
}
// Filter for sane settings for RS485
if (have_rs485_dir) {
if (have_rts || have_cts) {
mp_raise_ValueError(translate("Cannot specify RTS or CTS in RS485 mode"));
}
} else if (rs485_invert) {
mp_raise_ValueError(translate("RS485 inversion specified when not in RS485 mode"));
}
self->timeout_ms = timeout * 1000;
self->uart_num = UART_NUM_MAX;
for (uart_port_t num = 0; num < UART_NUM_MAX; num++) {
if (!uart_is_driver_installed(num)) {
self->uart_num = num;
}
}
if (self->uart_num == UART_NUM_MAX) {
mp_raise_ValueError(translate("All UART peripherals are in use"));
}
uart_mode_t mode = UART_MODE_UART;
uart_hw_flowcontrol_t flow_control = UART_HW_FLOWCTRL_DISABLE;
if (have_rs485_dir) {
mode = UART_MODE_RS485_HALF_DUPLEX;
if (!rs485_invert) {
uart_set_line_inverse(self->uart_num, UART_SIGNAL_DTR_INV);
}
} else if (have_rts && have_cts) {
flow_control = UART_HW_FLOWCTRL_CTS_RTS;
} else if (have_rts) {
flow_control = UART_HW_FLOWCTRL_RTS;
} else if (have_rts) {
flow_control = UART_HW_FLOWCTRL_CTS;
}
if (receiver_buffer_size <= UART_FIFO_LEN) {
receiver_buffer_size = UART_FIFO_LEN + 8;
}
uint8_t rx_threshold = UART_FIFO_LEN - 8;
// Install the driver before we change the settings.
if (uart_driver_install(self->uart_num, receiver_buffer_size, 0, 0, NULL, 0) != ESP_OK ||
uart_set_mode(self->uart_num, mode) != ESP_OK) {
mp_raise_ValueError(translate("Could not initialize UART"));
}
uart_set_hw_flow_ctrl(self->uart_num, flow_control, rx_threshold);
// Set baud rate
common_hal_busio_uart_set_baudrate(self, baudrate);
uart_word_length_t word_length = UART_DATA_8_BITS;
switch (bits) {
// Shared bindings prevents data < 7 bits.
// case 5:
// word_length = UART_DATA_5_BITS;
// break;
// case 6:
// word_length = UART_DATA_6_BITS;
// break;
case 7:
word_length = UART_DATA_7_BITS;
break;
case 8:
word_length = UART_DATA_8_BITS;
break;
default:
// Won't hit this because shared-bindings limits to 7-9 bits. We error on 9 above.
break;
}
uart_set_word_length(self->uart_num, word_length);
uart_parity_t parity_mode = UART_PARITY_DISABLE;
switch (parity) {
case BUSIO_UART_PARITY_NONE:
parity_mode = UART_PARITY_DISABLE;
break;
case BUSIO_UART_PARITY_EVEN:
parity_mode = UART_PARITY_EVEN;
break;
case BUSIO_UART_PARITY_ODD:
parity_mode = UART_PARITY_ODD;
break;
default:
// Won't reach here because the input is an enum that is completely handled.
break;
}
uart_set_parity(self->uart_num, parity_mode);
// Stop is 1 or 2 always.
uart_stop_bits_t stop_bits= UART_STOP_BITS_1;
if (stop == 2) {
stop_bits = UART_STOP_BITS_2;
}
uart_set_stop_bits(self->uart_num, stop_bits);
self->tx_pin = NULL;
self->rx_pin = NULL;
self->rts_pin = NULL;
self->cts_pin = NULL;
int tx_num = -1;
int rx_num = -1;
int rts_num = -1;
int cts_num = -1;
if (have_tx) {
claim_pin(tx);
self->tx_pin = tx;
tx_num = tx->number;
}
if (have_rx) {
claim_pin(rx);
self->rx_pin = rx;
rx_num = rx->number;
}
if (have_rts) {
claim_pin(rts);
self->rts_pin = rts;
rts_num = rts->number;
}
if (have_cts) {
claim_pin(cts);
self->cts_pin = cts;
cts_num = cts->number;
}
if (have_rs485_dir) {
claim_pin(rs485_dir);
// RTS is used for RS485 direction.
self->rts_pin = rs485_dir;
rts_num = rs485_dir->number;
}
if (uart_set_pin(self->uart_num, tx_num, rx_num, rts_num, cts_num) != ESP_OK) {
mp_raise_ValueError(translate("Invalid pins"));
}
}
bool common_hal_busio_uart_deinited(busio_uart_obj_t *self) {
return self->rx_pin == NULL && self->tx_pin == NULL;
}
void common_hal_busio_uart_deinit(busio_uart_obj_t *self) {
if (common_hal_busio_uart_deinited(self)) {
return;
}
uart_driver_delete(self->uart_num);
common_hal_reset_pin(self->rx_pin);
common_hal_reset_pin(self->tx_pin);
common_hal_reset_pin(self->rts_pin);
common_hal_reset_pin(self->cts_pin);
self->rx_pin = NULL;
self->tx_pin = NULL;
self->cts_pin = NULL;
self->rts_pin = NULL;
}
// Read characters.
size_t common_hal_busio_uart_read(busio_uart_obj_t *self, uint8_t *data, size_t len, int *errcode) {
if (self->rx_pin == NULL) {
mp_raise_ValueError(translate("No RX pin"));
}
if (len == 0) {
// Nothing to read.
return 0;
}
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 = uart_read_bytes(self->uart_num, data, len, 0);
if (num_read < 0) {
break;
}
// 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 == NULL) {
mp_raise_ValueError(translate("No TX pin"));
}
while (len > 0) {
int count = uart_tx_chars(self->uart_num, (const char*) data, len);
if (count < 0) {
*errcode = MP_EAGAIN;
return MP_STREAM_ERROR;
}
len -= count;
data += count;
RUN_BACKGROUND_TASKS;
}
while (uart_wait_tx_done(self->uart_num, 0) == ESP_ERR_TIMEOUT) {
RUN_BACKGROUND_TASKS;
}
return len;
}
uint32_t common_hal_busio_uart_get_baudrate(busio_uart_obj_t *self) {
uint32_t baudrate;
uart_get_baudrate(self->uart_num, &baudrate);
return baudrate;
}
void common_hal_busio_uart_set_baudrate(busio_uart_obj_t *self, uint32_t baudrate) {
if (baudrate > UART_BITRATE_MAX ||
uart_set_baudrate(self->uart_num, baudrate) != ESP_OK) {
mp_raise_ValueError(translate("Unsupported baudrate"));
}
}
mp_float_t common_hal_busio_uart_get_timeout(busio_uart_obj_t *self) {
return (mp_float_t) (self->timeout_ms / 1000.0f);
}
void common_hal_busio_uart_set_timeout(busio_uart_obj_t *self, mp_float_t timeout) {
self->timeout_ms = timeout * 1000;
}
uint32_t common_hal_busio_uart_rx_characters_available(busio_uart_obj_t *self) {
size_t count;
uart_get_buffered_data_len(self->uart_num, &count);
return count;
}
void common_hal_busio_uart_clear_rx_buffer(busio_uart_obj_t *self) {
uart_flush(self->uart_num);
}
// 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 == NULL) {
return false;
}
return uart_wait_tx_done(self->uart_num, 0) != ESP_ERR_TIMEOUT;
}

View File

@ -0,0 +1,49 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2016 Scott Shawcroft
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_UART_H
#define MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_UART_H
#include "common-hal/microcontroller/Pin.h"
#include "esp-idf/components/soc/include/hal/uart_types.h"
#include "py/obj.h"
typedef struct {
mp_obj_base_t base;
const mcu_pin_obj_t* rx_pin;
const mcu_pin_obj_t* tx_pin;
const mcu_pin_obj_t* rts_pin;
const mcu_pin_obj_t* cts_pin;
uart_port_t uart_num;
uint8_t character_bits;
bool rx_error;
uint32_t timeout_ms;
} busio_uart_obj_t;
void uart_reset(void);
#endif // MICROPY_INCLUDED_ESP32S2_COMMON_HAL_BUSIO_UART_H

View File

@ -0,0 +1 @@
// No busio module functions.

View File

@ -46,7 +46,7 @@ digitalinout_result_t common_hal_digitalio_digitalinout_construct(
}
bool common_hal_digitalio_digitalinout_deinited(digitalio_digitalinout_obj_t *self) {
return self->pin == mp_const_none;
return self->pin == NULL;
}
void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t *self) {
@ -55,7 +55,7 @@ void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t *self
}
reset_pin_number(self->pin->number);
self->pin = mp_const_none;
self->pin = NULL;
}
void common_hal_digitalio_digitalinout_switch_to_input(

View File

@ -0,0 +1,66 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Lucian Copeland for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "shared-bindings/displayio/ParallelBus.h"
#include <stdint.h>
#include "common-hal/microcontroller/Pin.h"
#include "py/runtime.h"
#include "shared-bindings/digitalio/DigitalInOut.h"
#include "shared-bindings/microcontroller/__init__.h"
void common_hal_displayio_parallelbus_construct(displayio_parallelbus_obj_t* self,
const mcu_pin_obj_t* data0, const mcu_pin_obj_t* command, const mcu_pin_obj_t* chip_select,
const mcu_pin_obj_t* write, const mcu_pin_obj_t* read, const mcu_pin_obj_t* reset) {
mp_raise_NotImplementedError(translate("ParallelBus not yet supported"));
}
void common_hal_displayio_parallelbus_deinit(displayio_parallelbus_obj_t* self) {
}
bool common_hal_displayio_parallelbus_reset(mp_obj_t obj) {
return false;
}
bool common_hal_displayio_parallelbus_bus_free(mp_obj_t obj) {
return false;
}
bool common_hal_displayio_parallelbus_begin_transaction(mp_obj_t obj) {
return false;
}
void common_hal_displayio_parallelbus_send(mp_obj_t obj, display_byte_type_t byte_type, display_chip_select_behavior_t chip_select, uint8_t *data, uint32_t data_length) {
}
void common_hal_displayio_parallelbus_end_transaction(mp_obj_t obj) {
}

View File

@ -0,0 +1,36 @@
/*
* This file is part of the MicroPython project, http://micropython.org/
*
* The MIT License (MIT)
*
* Copyright (c) 2019 Lucian Copeland for Adafruit Industries
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#ifndef MICROPY_INCLUDED_ESP32S2_COMMON_HAL_DISPLAYIO_PARALLELBUS_H
#define MICROPY_INCLUDED_ESP32S2_COMMON_HAL_DISPLAYIO_PARALLELBUS_H
#include "common-hal/digitalio/DigitalInOut.h"
typedef struct {
mp_obj_base_t base;
} displayio_parallelbus_obj_t;
#endif // MICROPY_INCLUDED_ESP32S2_COMMON_HAL_DISPLAYIO_PARALLELBUS_H

View File

@ -35,11 +35,14 @@
STATIC uint32_t never_reset_pins[2];
STATIC uint32_t in_use[2];
bool apa102_mosi_in_use;
bool apa102_sck_in_use;
void never_reset_pin_number(gpio_num_t pin_number) {
never_reset_pins[pin_number / 32] |= 1 << pin_number % 32;
}
void never_reset_pin(const mcu_pin_obj_t* pin) {
void common_hal_never_reset_pin(const mcu_pin_obj_t* pin) {
never_reset_pin_number(pin->number);
}
@ -49,6 +52,10 @@ void reset_pin_number(gpio_num_t pin_number) {
in_use[pin_number / 32] &= ~(1 << pin_number % 32);
}
void common_hal_reset_pin(const mcu_pin_obj_t* pin) {
reset_pin_number(pin->number);
}
void reset_all_pins(void) {
for (uint8_t i = 0; i < GPIO_PIN_COUNT; i++) {
uint32_t iomux_address = GPIO_PIN_MUX_REG[i];

View File

@ -31,13 +31,16 @@
#include "peripherals/pins.h"
extern bool apa102_mosi_in_use;
extern bool apa102_sck_in_use;
void reset_all_pins(void);
// reset_pin_number takes the pin number instead of the pointer so that objects don't
// need to store a full pointer.
void reset_pin_number(gpio_num_t pin_number);
void common_hal_reset_pin(const mcu_pin_obj_t* pin);
void claim_pin(const mcu_pin_obj_t* pin);
bool pin_number_is_free(gpio_num_t pin_number);
void never_reset_pin_number(gpio_num_t pin_number);
void never_reset_pin(const mcu_pin_obj_t* pin);
#endif // MICROPY_INCLUDED_ESP32S2_COMMON_HAL_MICROCONTROLLER_PIN_H

@ -1 +1 @@
Subproject commit 7aae7f034bab68d2dd6aaa763924c91eb697d87e
Subproject commit 160ba4924d8b588e718f76e3a0d0e92c11052fa3

View File

@ -28,10 +28,10 @@
void never_reset_module_internal_pins(void) {
// SPI Flash
never_reset_pin(&pin_GPIO27);
never_reset_pin(&pin_GPIO28);
never_reset_pin(&pin_GPIO29);
never_reset_pin(&pin_GPIO30);
never_reset_pin(&pin_GPIO31);
never_reset_pin(&pin_GPIO32);
common_hal_never_reset_pin(&pin_GPIO27);
common_hal_never_reset_pin(&pin_GPIO28);
common_hal_never_reset_pin(&pin_GPIO29);
common_hal_never_reset_pin(&pin_GPIO30);
common_hal_never_reset_pin(&pin_GPIO31);
common_hal_never_reset_pin(&pin_GPIO32);
}

View File

@ -28,11 +28,11 @@
void never_reset_module_internal_pins(void) {
// SPI Flash and RAM
never_reset_pin(&pin_GPIO26);
never_reset_pin(&pin_GPIO27);
never_reset_pin(&pin_GPIO28);
never_reset_pin(&pin_GPIO29);
never_reset_pin(&pin_GPIO30);
never_reset_pin(&pin_GPIO31);
never_reset_pin(&pin_GPIO32);
common_hal_never_reset_pin(&pin_GPIO26);
common_hal_never_reset_pin(&pin_GPIO27);
common_hal_never_reset_pin(&pin_GPIO28);
common_hal_never_reset_pin(&pin_GPIO29);
common_hal_never_reset_pin(&pin_GPIO30);
common_hal_never_reset_pin(&pin_GPIO31);
common_hal_never_reset_pin(&pin_GPIO32);
}

View File

@ -16,11 +16,11 @@ CIRCUITPY_FULL_BUILD = 0
CIRCUITPY_ANALOGIO = 0
CIRCUITPY_AUDIOBUSIO = 0
CIRCUITPY_AUDIOIO = 0
CIRCUITPY_BITBANGIO = 0
CIRCUITPY_BITBANGIO = 1
CIRCUITPY_BOARD = 1
CIRCUITPY_DIGITALIO = 1
CIRCUITPY_BUSIO = 0
CIRCUITPY_DISPLAYIO = 0
CIRCUITPY_BUSIO = 1
CIRCUITPY_DISPLAYIO = 1
CIRCUITPY_FREQUENCYIO = 0
CIRCUITPY_I2CPERIPHERAL = 0
CIRCUITPY_MICROCONTROLLER = 1

View File

@ -32,9 +32,10 @@
#include "py/gc.h"
#include "esp-idf/components/xtensa/include/esp_debug_helpers.h"
#include "esp-idf/components/esp_rom/include/esp32s2/rom/ets_sys.h"
void mp_hal_delay_us(mp_uint_t delay) {
mp_hal_delay_ms(delay / 1000);
ets_delay_us(delay);
}
// This is provided by the esp-idf/components/xtensa/esp32s2/libhal.a binary

View File

@ -190,9 +190,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=256
# ESP32S2-specific
#
# CONFIG_ESP32S2_DEFAULT_CPU_FREQ_80 is not set
CONFIG_ESP32S2_DEFAULT_CPU_FREQ_160=y
# CONFIG_ESP32S2_DEFAULT_CPU_FREQ_240 is not set
CONFIG_ESP32S2_DEFAULT_CPU_FREQ_MHZ=160
# CONFIG_ESP32S2_DEFAULT_CPU_FREQ_160 is not set
CONFIG_ESP32S2_DEFAULT_CPU_FREQ_240=y
CONFIG_ESP32S2_DEFAULT_CPU_FREQ_MHZ=240
#
# Memory protection
@ -271,10 +271,7 @@ CONFIG_ESP_CONSOLE_UART_RX_GPIO=3
CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200
CONFIG_ESP_INT_WDT=y
CONFIG_ESP_INT_WDT_TIMEOUT_MS=300
CONFIG_ESP_TASK_WDT=y
# CONFIG_ESP_TASK_WDT_PANIC is not set
CONFIG_ESP_TASK_WDT_TIMEOUT_S=5
CONFIG_ESP_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
# CONFIG_ESP_TASK_WDT is not set
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y
CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y
# end of Common ESP-related
@ -528,6 +525,7 @@ CONFIG_MBEDTLS_INTERNAL_MEM_ALLOC=y
CONFIG_MBEDTLS_ASYMMETRIC_CONTENT_LEN=y
CONFIG_MBEDTLS_SSL_IN_CONTENT_LEN=16384
CONFIG_MBEDTLS_SSL_OUT_CONTENT_LEN=4096
# CONFIG_MBEDTLS_DYNAMIC_BUFFER is not set
# CONFIG_MBEDTLS_DEBUG is not set
#
@ -547,8 +545,12 @@ CONFIG_MBEDTLS_AES_USE_INTERRUPT=y
CONFIG_MBEDTLS_HARDWARE_GCM=y
CONFIG_MBEDTLS_HARDWARE_MPI=y
CONFIG_MBEDTLS_HARDWARE_SHA=y
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_SIGN is not set
# CONFIG_MBEDTLS_ATCA_HW_ECDSA_VERIFY is not set
CONFIG_MBEDTLS_HAVE_TIME=y
# CONFIG_MBEDTLS_HAVE_TIME_DATE is not set
CONFIG_MBEDTLS_ECDSA_DETERMINISTIC=y
CONFIG_MBEDTLS_SHA512_C=y
CONFIG_MBEDTLS_TLS_SERVER_AND_CLIENT=y
# CONFIG_MBEDTLS_TLS_SERVER_ONLY is not set
# CONFIG_MBEDTLS_TLS_CLIENT_ONLY is not set
@ -627,6 +629,10 @@ CONFIG_MBEDTLS_ECP_DP_BP384R1_ENABLED=y
CONFIG_MBEDTLS_ECP_DP_BP512R1_ENABLED=y
CONFIG_MBEDTLS_ECP_DP_CURVE25519_ENABLED=y
CONFIG_MBEDTLS_ECP_NIST_OPTIM=y
# CONFIG_MBEDTLS_POLY1305_C is not set
# CONFIG_MBEDTLS_CHACHA20_C is not set
# CONFIG_MBEDTLS_HKDF_C is not set
# CONFIG_MBEDTLS_THREADING_C is not set
# CONFIG_MBEDTLS_SECURITY_RISKS is not set
# end of mbedTLS
@ -705,6 +711,7 @@ CONFIG_WPA_MBEDTLS_CRYPTO=y
# CONFIG_WPA_DEBUG_PRINT is not set
# CONFIG_WPA_TESTING_OPTIONS is not set
# CONFIG_WPA_TLS_V12 is not set
# CONFIG_WPA_WPS_WARS is not set
# end of Supplicant
# end of Component config
@ -756,7 +763,7 @@ CONFIG_ESP32_APPTRACE_LOCK_ENABLE=y
CONFIG_ADC2_DISABLE_DAC=y
CONFIG_SYSTEM_EVENT_QUEUE_SIZE=32
CONFIG_SYSTEM_EVENT_TASK_STACK_SIZE=2304
CONFIG_MAIN_TASK_STACK_SIZE=3584
CONFIG_MAIN_TASK_STACK_SIZE=8192
CONFIG_IPC_TASK_STACK_SIZE=1024
CONFIG_CONSOLE_UART_DEFAULT=y
# CONFIG_CONSOLE_UART_CUSTOM is not set
@ -767,10 +774,7 @@ CONFIG_CONSOLE_UART_RX_GPIO=3
CONFIG_CONSOLE_UART_BAUDRATE=115200
CONFIG_INT_WDT=y
CONFIG_INT_WDT_TIMEOUT_MS=300
CONFIG_TASK_WDT=y
# CONFIG_TASK_WDT_PANIC is not set
CONFIG_TASK_WDT_TIMEOUT_S=5
CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU0=y
# CONFIG_TASK_WDT is not set
# CONFIG_EVENT_LOOP_PROFILING is not set
CONFIG_POST_EVENTS_FROM_ISR=y
CONFIG_POST_EVENTS_FROM_IRAM_ISR=y

View File

@ -39,11 +39,6 @@
#include "esp-idf/components/spi_flash/include/esp_partition.h"
#include "esp_log.h"
static const char* TAG = "CircuitPython Internal Flash";
#include "supervisor/usb.h"
STATIC const esp_partition_t * _partition;
@ -52,8 +47,6 @@ void supervisor_flash_init(void) {
_partition = esp_partition_find_first(ESP_PARTITION_TYPE_DATA,
ESP_PARTITION_SUBTYPE_DATA_FAT,
NULL);
ESP_EARLY_LOGW(TAG, "fatfs partition %p", _partition);
}
uint32_t supervisor_flash_get_block_size(void) {
@ -74,11 +67,10 @@ STATIC uint8_t _cache[SECTOR_SIZE];
STATIC uint32_t _cache_lba;
mp_uint_t supervisor_flash_read_blocks(uint8_t *dest, uint32_t block, uint32_t num_blocks) {
esp_err_t ok = esp_partition_read(_partition,
block * FILESYSTEM_BLOCK_SIZE,
dest,
num_blocks * FILESYSTEM_BLOCK_SIZE);
ESP_EARLY_LOGW(TAG, "read %d", ok);
esp_partition_read(_partition,
block * FILESYSTEM_BLOCK_SIZE,
dest,
num_blocks * FILESYSTEM_BLOCK_SIZE);
return 0;
}
@ -90,13 +82,11 @@ mp_uint_t supervisor_flash_write_blocks(const uint8_t *src, uint32_t lba, uint32
uint32_t sector_offset = block_address / blocks_per_sector * SECTOR_SIZE;
uint8_t block_offset = block_address % blocks_per_sector;
esp_err_t result;
if (_cache_lba != block_address) {
result = esp_partition_read(_partition,
sector_offset,
_cache,
SECTOR_SIZE);
ESP_EARLY_LOGW(TAG, "flash read before write %d", result);
esp_partition_read(_partition,
sector_offset,
_cache,
SECTOR_SIZE);
_cache_lba = sector_offset;
}
for (uint8_t b = block_offset; b < blocks_per_sector; b++) {
@ -109,11 +99,11 @@ mp_uint_t supervisor_flash_write_blocks(const uint8_t *src, uint32_t lba, uint32
FILESYSTEM_BLOCK_SIZE);
block++;
}
result = esp_partition_erase_range(_partition, sector_offset, SECTOR_SIZE);
result = esp_partition_write(_partition,
sector_offset,
_cache,
SECTOR_SIZE);
esp_partition_erase_range(_partition, sector_offset, SECTOR_SIZE);
esp_partition_write(_partition,
sector_offset,
_cache,
SECTOR_SIZE);
}
return 0; // success

View File

@ -35,13 +35,12 @@
#include "freertos/task.h"
#include "common-hal/microcontroller/Pin.h"
#include "common-hal/busio/I2C.h"
#include "common-hal/busio/SPI.h"
#include "common-hal/busio/UART.h"
#include "supervisor/memory.h"
#include "supervisor/shared/tick.h"
#include "esp_log.h"
static const char* TAG = "CircuitPython";
STATIC esp_timer_handle_t _tick_timer;
void tick_timer_cb(void* arg) {
@ -54,18 +53,22 @@ safe_mode_t port_init(void) {
args.arg = NULL;
args.dispatch_method = ESP_TIMER_TASK;
args.name = "CircuitPython Tick";
esp_err_t result = esp_timer_create(&args, &_tick_timer);
if (result != ESP_OK) {
ESP_EARLY_LOGE(TAG, "Unable to create tick timer.");
}
esp_timer_create(&args, &_tick_timer);
never_reset_module_internal_pins();
ESP_EARLY_LOGW(TAG, "port init done");
return NO_SAFE_MODE;
}
void reset_port(void) {
reset_all_pins();
// A larger delay so the idle task can run and do any IDF cleanup needed.
vTaskDelay(4);
#if CIRCUITPY_BUSIO
i2c_reset();
spi_reset();
uart_reset();
#endif
}
void reset_to_bootloader(void) {
@ -98,12 +101,8 @@ uint32_t *port_stack_get_top(void) {
supervisor_allocation _fixed_stack;
supervisor_allocation* port_fixed_stack(void) {
ESP_EARLY_LOGW(TAG, "port fixed stack");
_fixed_stack.ptr = port_stack_get_limit();
ESP_EARLY_LOGW(TAG, "got limit %p", _fixed_stack.ptr);
_fixed_stack.length = (port_stack_get_top() - port_stack_get_limit()) * sizeof(uint32_t);
ESP_EARLY_LOGW(TAG, "got length %d", _fixed_stack.length);
return &_fixed_stack;
}
@ -128,10 +127,7 @@ uint64_t port_get_raw_ticks(uint8_t* subticks) {
// Enable 1/1024 second tick.
void port_enable_tick(void) {
esp_err_t result = esp_timer_start_periodic(_tick_timer, 1000000 / 1024);
if (result != ESP_OK) {
ESP_EARLY_LOGE(TAG, "Unable to start tick timer.");
}
esp_timer_start_periodic(_tick_timer, 1000000 / 1024);
}
// Disable 1/1024 second tick.
@ -142,14 +138,12 @@ void port_disable_tick(void) {
TickType_t sleep_time_set;
TickType_t sleep_time_duration;
void port_interrupt_after_ticks(uint32_t ticks) {
// ESP_EARLY_LOGW(TAG, "after ticks");
sleep_time_set = xTaskGetTickCount();
sleep_time_duration = ticks / portTICK_PERIOD_MS;
// esp_sleep_enable_timer_wakeup(uint64_t time_in_us)
}
void port_sleep_until_interrupt(void) {
// ESP_EARLY_LOGW(TAG, "sleep until");
// FreeRTOS delay here maybe.
// Light sleep shuts down BLE and wifi.
// esp_light_sleep_start()
@ -163,8 +157,5 @@ void port_sleep_until_interrupt(void) {
// Wrap main in app_main that the IDF expects.
extern void main(void);
void app_main(void) {
ESP_EARLY_LOGW(TAG, "Hello from CircuitPython");
// ESP_LOGW(TAG, "Hello from CircuitPython");
main();
}

View File

@ -46,7 +46,7 @@ digitalinout_result_t common_hal_digitalio_digitalinout_construct(
}
bool common_hal_digitalio_digitalinout_deinited(digitalio_digitalinout_obj_t *self) {
return self->pin == mp_const_none;
return self->pin == NULL;
}
void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t *self) {
@ -55,7 +55,7 @@ void common_hal_digitalio_digitalinout_deinit(digitalio_digitalinout_obj_t *self
}
// reset_pin_number(0, self->pin->number);
self->pin = mp_const_none;
self->pin = NULL;
}
void common_hal_digitalio_digitalinout_switch_to_input(

View File

@ -321,7 +321,7 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self,
return (status == kStatus_Success);
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uint8_t *data_in, size_t len) {
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len) {
if (len == 0) {
return true;
}
@ -332,7 +332,7 @@ bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uin
LPSPI_SetDummyData(self->spi, 0xFF);
lpspi_transfer_t xfer = { 0 };
xfer.txData = data_out;
xfer.txData = (uint8_t *)data_out;
xfer.rxData = data_in;
xfer.dataSize = len;

View File

@ -85,7 +85,7 @@ 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, uart_parity_t parity, uint8_t stop,
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) {
@ -94,7 +94,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
self->timeout_ms = timeout * 1000;
// We are transmitting one direction if one pin is NULL and the other isn't.
bool is_onedirection = (rx != NULL) != (tx != NULL);
bool is_onedirection = (rx == NULL) != (tx == NULL);
bool uart_taken = false;
const uint32_t rx_count = MP_ARRAY_SIZE(mcu_uart_rx_list);

View File

@ -271,13 +271,13 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self, uint8_t *data, size_t len,
return true;
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uint8_t *data_in, size_t len) {
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len) {
const bool is_spim3 = self->spim_peripheral->spim.p_reg == NRF_SPIM3;
uint8_t *next_chunk_out = data_out;
const uint8_t *next_chunk_out = data_out;
uint8_t *next_chunk_in = data_in;
while (len > 0) {
uint8_t *chunk_out = next_chunk_out;
const uint8_t *chunk_out = next_chunk_out;
size_t chunk_size = MIN(len, self->spim_peripheral->max_xfer_size);
if (is_spim3) {
// If SPIM3, copy into unused RAM block, and do DMA from there.

View File

@ -133,7 +133,7 @@ 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, uart_parity_t parity, uint8_t stop,
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) {
@ -162,7 +162,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
mp_raise_ValueError(translate("Invalid buffer size"));
}
if ( parity == PARITY_ODD ) {
if ( parity == BUSIO_UART_PARITY_ODD ) {
mp_raise_ValueError(translate("Odd parity is not supported"));
}
@ -176,7 +176,7 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
.interrupt_priority = 7,
.hal_cfg = {
.hwfc = NRF_UARTE_HWFC_DISABLED,
.parity = (parity == PARITY_NONE) ? NRF_UARTE_PARITY_EXCLUDED : NRF_UARTE_PARITY_INCLUDED
.parity = (parity == BUSIO_UART_PARITY_NONE) ? NRF_UARTE_PARITY_EXCLUDED : NRF_UARTE_PARITY_INCLUDED
}
};

View File

@ -380,12 +380,12 @@ bool common_hal_busio_spi_read(busio_spi_obj_t *self,
}
bool common_hal_busio_spi_transfer(busio_spi_obj_t *self,
uint8_t *data_out, uint8_t *data_in, size_t len) {
const uint8_t *data_out, uint8_t *data_in, size_t len) {
if (self->miso == NULL || self->mosi == NULL) {
mp_raise_ValueError(translate("Missing MISO or MOSI Pin"));
}
HAL_StatusTypeDef result = HAL_SPI_TransmitReceive (&self->handle,
data_out, data_in, (uint16_t)len,HAL_MAX_DELAY);
(uint8_t *) data_out, data_in, (uint16_t)len,HAL_MAX_DELAY);
return result == HAL_OK;
}

View File

@ -79,7 +79,7 @@ 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, uart_parity_t parity, uint8_t stop,
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) {
@ -201,8 +201,8 @@ void common_hal_busio_uart_construct(busio_uart_obj_t *self,
self->handle.Init.BaudRate = baudrate;
self->handle.Init.WordLength = (bits == 9) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
self->handle.Init.StopBits = (stop > 1) ? UART_STOPBITS_2 : UART_STOPBITS_1;
self->handle.Init.Parity = (parity == PARITY_ODD) ? UART_PARITY_ODD :
(parity == PARITY_EVEN) ? UART_PARITY_EVEN :
self->handle.Init.Parity = (parity == BUSIO_UART_PARITY_ODD) ? UART_PARITY_ODD :
(parity == BUSIO_UART_PARITY_EVEN) ? UART_PARITY_EVEN :
UART_PARITY_NONE;
self->handle.Init.Mode = (self->tx != NULL && self->rx != NULL) ? UART_MODE_TX_RX :
(self->tx != NULL) ? UART_MODE_TX :

View File

@ -56,7 +56,7 @@ extern bool common_hal_busio_spi_write(busio_spi_obj_t *self, const uint8_t *dat
extern bool common_hal_busio_spi_read(busio_spi_obj_t *self, uint8_t *data, size_t len, uint8_t write_value);
// Reads and write len bytes simultaneously.
extern bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, uint8_t *data_out, uint8_t *data_in, size_t len);
extern bool common_hal_busio_spi_transfer(busio_spi_obj_t *self, const uint8_t *data_out, uint8_t *data_in, size_t len);
// Return actual SPI bus frequency.
uint32_t common_hal_busio_spi_get_frequency(busio_spi_obj_t* self);

View File

@ -52,8 +52,8 @@
//| :param ~microcontroller.Pin rx: the pin to receive on, or ``None`` if this ``UART`` is transmit-only.
//| :param ~microcontroller.Pin rts: the pin for rts, or ``None`` if rts not in use.
//| :param ~microcontroller.Pin cts: the pin for cts, or ``None`` if cts not in use.
//| :param ~microcontroller.Pin rs485_dir: the pin for rs485 direction setting, or ``None`` if rs485 not in use.
//| :param bool rs485_invert: set to invert the sense of the rs485_dir pin.
//| :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 Parity parity: the parity used for error checking.
@ -87,8 +87,8 @@ STATIC mp_obj_t busio_uart_make_new(const mp_obj_type_t *type, size_t n_args, co
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};
static const mp_arg_t allowed_args[] = {
{ MP_QSTR_tx, MP_ARG_REQUIRED | MP_ARG_OBJ },
{ MP_QSTR_rx, MP_ARG_REQUIRED | MP_ARG_OBJ },
{ MP_QSTR_tx, MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_rx, MP_ARG_OBJ, {.u_obj = mp_const_none} },
{ MP_QSTR_baudrate, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 9600} },
{ MP_QSTR_bits, MP_ARG_KW_ONLY | MP_ARG_INT, {.u_int = 8} },
{ MP_QSTR_parity, MP_ARG_KW_ONLY | MP_ARG_OBJ, {.u_obj = mp_const_none} },
@ -115,11 +115,11 @@ STATIC mp_obj_t busio_uart_make_new(const mp_obj_type_t *type, size_t n_args, co
mp_raise_ValueError(translate("bits must be 7, 8 or 9"));
}
uart_parity_t parity = PARITY_NONE;
busio_uart_parity_t parity = BUSIO_UART_PARITY_NONE;
if (args[ARG_parity].u_obj == &busio_uart_parity_even_obj) {
parity = PARITY_EVEN;
parity = BUSIO_UART_PARITY_EVEN;
} else if (args[ARG_parity].u_obj == &busio_uart_parity_odd_obj) {
parity = PARITY_ODD;
parity = BUSIO_UART_PARITY_ODD;
}
uint8_t stop = args[ARG_stop].u_int;

View File

@ -34,17 +34,17 @@
extern const mp_obj_type_t busio_uart_type;
typedef enum {
PARITY_NONE,
PARITY_EVEN,
PARITY_ODD
} uart_parity_t;
BUSIO_UART_PARITY_NONE,
BUSIO_UART_PARITY_EVEN,
BUSIO_UART_PARITY_ODD
} busio_uart_parity_t;
// Construct an underlying UART object.
extern 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, uart_parity_t parity, uint8_t stop,
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);

View File

@ -123,7 +123,7 @@ mp_obj_t common_hal_board_create_uart(void) {
#endif
common_hal_busio_uart_construct(self, tx, rx, rts, cts, rs485_dir, rs485_invert,
9600, 8, PARITY_NONE, 1, 1.0f, 64, NULL, false);
9600, 8, BUSIO_UART_PARITY_NONE, 1, 1.0f, 64, NULL, false);
MP_STATE_VM(shared_uart_bus) = MP_OBJ_FROM_PTR(self);
return MP_STATE_VM(shared_uart_bus);
}

View File

@ -29,7 +29,9 @@
#include "shared-bindings/digitalio/DigitalInOut.h"
#include "shared-bindings/displayio/Group.h"
#if CIRCUITPY_PULSEIO
#include "shared-bindings/pulseio/PWMOut.h"
#endif
#include "shared-module/displayio/area.h"
#include "shared-module/displayio/display_core.h"
@ -39,7 +41,9 @@ typedef struct {
displayio_display_core_t core;
union {
digitalio_digitalinout_obj_t backlight_inout;
#if CIRCUITPY_PULSEIO
pulseio_pwmout_obj_t backlight_pwm;
#endif
};
uint64_t last_backlight_refresh;
uint64_t last_refresh_call;

View File

@ -29,7 +29,6 @@
#include "shared-bindings/digitalio/DigitalInOut.h"
#include "shared-bindings/displayio/Group.h"
#include "shared-bindings/pulseio/PWMOut.h"
#include "shared-module/displayio/area.h"
#include "shared-module/displayio/display_core.h"

View File

@ -55,7 +55,7 @@ void serial_early_init(void) {
const mcu_pin_obj_t* tx = MP_OBJ_TO_PTR(DEBUG_UART_TX);
common_hal_busio_uart_construct(&debug_uart, tx, rx, NULL, NULL, NULL,
false, 115200, 8, PARITY_NONE, 1, 1.0f, 64,
false, 115200, 8, UART_PARITY_NONE, 1, 1.0f, 64,
buf_array, true);
common_hal_busio_uart_never_reset(&debug_uart);
#endif