Merge remote-tracking branch 'upstream/main' into esp32-analogin
This commit is contained in:
commit
97d217a764
|
@ -152,4 +152,4 @@
|
|||
url = https://github.com/adafruit/Adafruit_CircuitPython_RFM69.git
|
||||
[submodule "ports/esp32s2/esp-idf"]
|
||||
path = ports/esp32s2/esp-idf
|
||||
url = https://github.com/hierophect/esp-idf.git
|
||||
url = https://github.com/espressif/esp-idf.git
|
||||
|
|
|
@ -41,9 +41,6 @@ typedef struct canio_can_obj {
|
|||
mp_obj_base_t base;
|
||||
Can *hw;
|
||||
canio_can_state_t *state;
|
||||
volatile uint32_t error_warning_state_count;
|
||||
volatile uint32_t error_passive_state_count;
|
||||
volatile uint32_t bus_off_state_count;
|
||||
int baudrate;
|
||||
uint8_t rx_pin_number:8;
|
||||
uint8_t tx_pin_number:8;
|
||||
|
|
|
@ -271,8 +271,7 @@ menuconfig: $(BUILD)/esp-idf/config
|
|||
# qstr builds include headers so we need to make sure they are up to date
|
||||
$(HEADER_BUILD)/qstr.i.last: | $(BUILD)/esp-idf/config/sdkconfig.h
|
||||
|
||||
# Order here matters
|
||||
ESP_IDF_COMPONENTS_LINK = freertos log esp_system esp_adc_cal esp32s2 bootloader_support pthread esp_timer vfs spi_flash app_update esp_common esp32s2 heap newlib driver xtensa soc esp_ringbuf esp_wifi esp_event wpa_supplicant mbedtls efuse nvs_flash esp_netif lwip esp_rom esp-tls
|
||||
ESP_IDF_COMPONENTS_LINK = freertos log hal esp_system esp_adc_cal esp32s2 bootloader_support pthread esp_timer vfs spi_flash app_update esp_common esp32s2 heap newlib driver xtensa soc esp_ringbuf esp_wifi esp_event wpa_supplicant mbedtls efuse nvs_flash esp_netif lwip esp_rom esp-tls
|
||||
|
||||
ESP_IDF_COMPONENTS_INCLUDE = driver freertos log soc
|
||||
|
||||
|
@ -284,11 +283,11 @@ ESP_IDF_WIFI_COMPONENTS_EXPANDED = $(foreach component, $(ESP_IDF_WIFI_COMPONENT
|
|||
MBEDTLS_COMPONENTS_LINK = crypto tls x509
|
||||
MBEDTLS_COMPONENTS_LINK_EXPANDED = $(foreach component, $(MBEDTLS_COMPONENTS_LINK), $(BUILD)/esp-idf/esp-idf/mbedtls/mbedtls/library/libmbed$(component).a)
|
||||
|
||||
BINARY_BLOBS = esp-idf/components/xtensa/esp32s2/libhal.a
|
||||
BINARY_BLOBS = esp-idf/components/xtensa/esp32s2/libxt_hal.a
|
||||
BINARY_WIFI_BLOBS = libcoexist.a libcore.a libespnow.a libmesh.a libnet80211.a libpp.a librtc.a libsmartconfig.a libphy.a
|
||||
BINARY_BLOBS += $(addprefix esp-idf/components/esp_wifi/lib/esp32s2/, $(BINARY_WIFI_BLOBS))
|
||||
|
||||
ESP_IDF_COMPONENTS_EXPANDED += $(BUILD)/esp-idf/esp-idf/soc/soc/esp32s2/libsoc_esp32s2.a esp-idf/components/xtensa/esp32s2/libhal.a
|
||||
ESP_IDF_COMPONENTS_EXPANDED += $(BUILD)/esp-idf/esp-idf/soc/soc/esp32s2/libsoc_esp32s2.a esp-idf/components/xtensa/esp32s2/libxt_hal.a
|
||||
ESP_AUTOGEN_LD = $(BUILD)/esp-idf/esp-idf/esp32s2/esp32s2_out.ld $(BUILD)/esp-idf/esp-idf/esp32s2/ld/esp32s2.project.ld
|
||||
|
||||
FLASH_FLAGS = --flash_mode $(CIRCUITPY_ESP_FLASH_MODE) --flash_freq $(CIRCUITPY_ESP_FLASH_FREQ) --flash_size $(CIRCUITPY_ESP_FLASH_SIZE)
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
#include "common-hal/microcontroller/Pin.h"
|
||||
|
||||
#include "components/soc/include/hal/adc_types.h"
|
||||
#include "components/hal/include/hal/adc_types.h"
|
||||
#include "FreeRTOS.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "py/obj.h"
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
#include "common-hal/microcontroller/Pin.h"
|
||||
|
||||
#include "components/soc/include/hal/i2c_types.h"
|
||||
#include "components/hal/include/hal/i2c_types.h"
|
||||
#include "FreeRTOS.h"
|
||||
#include "freertos/semphr.h"
|
||||
#include "py/obj.h"
|
||||
|
|
|
@ -30,8 +30,8 @@
|
|||
#include "common-hal/microcontroller/Pin.h"
|
||||
|
||||
#include "components/driver/include/driver/spi_common_internal.h"
|
||||
#include "components/soc/include/hal/spi_hal.h"
|
||||
#include "components/soc/include/hal/spi_types.h"
|
||||
#include "components/hal/include/hal/spi_hal.h"
|
||||
#include "components/hal/include/hal/spi_types.h"
|
||||
#include "py/obj.h"
|
||||
|
||||
typedef struct {
|
||||
|
|
|
@ -29,7 +29,7 @@
|
|||
|
||||
#include "common-hal/microcontroller/Pin.h"
|
||||
|
||||
#include "components/soc/include/hal/uart_types.h"
|
||||
#include "components/hal/include/hal/uart_types.h"
|
||||
#include "py/obj.h"
|
||||
|
||||
typedef struct {
|
||||
|
|
|
@ -30,7 +30,7 @@
|
|||
|
||||
#include "components/driver/include/driver/gpio.h"
|
||||
|
||||
#include "components/soc/include/hal/gpio_hal.h"
|
||||
#include "components/hal/include/hal/gpio_hal.h"
|
||||
|
||||
void common_hal_digitalio_digitalinout_never_reset(
|
||||
digitalio_digitalinout_obj_t *self) {
|
||||
|
|
|
@ -32,7 +32,7 @@
|
|||
#include "py/mphal.h"
|
||||
|
||||
#include "components/driver/include/driver/gpio.h"
|
||||
#include "components/soc/include/hal/gpio_hal.h"
|
||||
#include "components/hal/include/hal/gpio_hal.h"
|
||||
|
||||
#ifdef MICROPY_HW_NEOPIXEL
|
||||
bool neopixel_in_use;
|
||||
|
|
|
@ -1 +1 @@
|
|||
Subproject commit a7f77798816661f7c4ae198f3878bc92a9274f82
|
||||
Subproject commit 8bc19ba893e5544d571a753d82b44a84799b94b1
|
|
@ -35,8 +35,8 @@
|
|||
#include "esp32s2_peripherals_config.h"
|
||||
#include "esp-idf/config/sdkconfig.h"
|
||||
|
||||
#include "components/soc/include/hal/gpio_types.h"
|
||||
#include "components/soc/include/hal/adc_types.h"
|
||||
#include "components/hal/include/hal/gpio_types.h"
|
||||
#include "components/hal/include/hal/adc_types.h"
|
||||
|
||||
typedef struct {
|
||||
PIN_PREFIX_FIELDS
|
||||
|
|
|
@ -33,6 +33,8 @@
|
|||
#include "components/driver/include/driver/periph_ctrl.h"
|
||||
#include "components/driver/include/driver/gpio.h"
|
||||
#include "components/esp_rom/include/esp32s2/rom/gpio.h"
|
||||
#include "components/esp_rom/include/esp_rom_gpio.h"
|
||||
#include "components/hal/esp32s2/include/hal/gpio_ll.h"
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
|
@ -68,6 +70,33 @@ void usb_device_task(void* param)
|
|||
}
|
||||
}
|
||||
|
||||
static void configure_pins (usb_hal_context_t *usb)
|
||||
{
|
||||
/* usb_periph_iopins currently configures USB_OTG as USB Device.
|
||||
* Introduce additional parameters in usb_hal_context_t when adding support
|
||||
* for USB Host.
|
||||
*/
|
||||
for ( const usb_iopin_dsc_t *iopin = usb_periph_iopins; iopin->pin != -1; ++iopin ) {
|
||||
if ( (usb->use_external_phy) || (iopin->ext_phy_only == 0) ) {
|
||||
esp_rom_gpio_pad_select_gpio(iopin->pin);
|
||||
if ( iopin->is_output ) {
|
||||
esp_rom_gpio_connect_out_signal(iopin->pin, iopin->func, false, false);
|
||||
}
|
||||
else {
|
||||
esp_rom_gpio_connect_in_signal(iopin->pin, iopin->func, false);
|
||||
if ( (iopin->pin != GPIO_FUNC_IN_LOW) && (iopin->pin != GPIO_FUNC_IN_HIGH) ) {
|
||||
gpio_ll_input_enable(&GPIO, iopin->pin);
|
||||
}
|
||||
}
|
||||
esp_rom_gpio_pad_unhold(iopin->pin);
|
||||
}
|
||||
}
|
||||
if ( !usb->use_external_phy ) {
|
||||
gpio_set_drive_capability(USBPHY_DM_NUM, GPIO_DRIVE_CAP_3);
|
||||
gpio_set_drive_capability(USBPHY_DP_NUM, GPIO_DRIVE_CAP_3);
|
||||
}
|
||||
}
|
||||
|
||||
void init_usb_hardware(void) {
|
||||
periph_module_reset(PERIPH_USB_MODULE);
|
||||
periph_module_enable(PERIPH_USB_MODULE);
|
||||
|
@ -75,10 +104,7 @@ void init_usb_hardware(void) {
|
|||
.use_external_phy = false // use built-in PHY
|
||||
};
|
||||
usb_hal_init(&hal);
|
||||
|
||||
// Initialize the pin drive strength.
|
||||
gpio_set_drive_capability(USBPHY_DM_NUM, GPIO_DRIVE_CAP_3);
|
||||
gpio_set_drive_capability(USBPHY_DP_NUM, GPIO_DRIVE_CAP_3);
|
||||
configure_pins(&hal);
|
||||
|
||||
(void) xTaskCreateStatic(usb_device_task,
|
||||
"usbd",
|
||||
|
|
|
@ -198,6 +198,10 @@ SRC_STM32 = $(addprefix $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_,\
|
|||
ll_utils.c \
|
||||
)
|
||||
|
||||
ifeq ($(CIRCUITPY_CANIO),1)
|
||||
SRC_STM32 += $(HAL_DIR)/Src/stm32$(MCU_SERIES_LOWER)xx_hal_can.c
|
||||
endif
|
||||
|
||||
# Need this to avoid UART linker problems. TODO: rewrite to use registered callbacks.
|
||||
# Does not exist for F4 and lower
|
||||
ifeq ($(MCU_VARIANT),$(filter $(MCU_VARIANT),STM32F765xx STM32F767xx STM32F769xx STM32H743xx))
|
||||
|
|
|
@ -47,5 +47,8 @@ STATIC const mp_rom_map_elem_t board_module_globals_table[] = {
|
|||
{ MP_ROM_QSTR(MP_QSTR_SDIO_CLOCK), MP_ROM_PTR(&pin_PC12) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_SDIO_COMMAND), MP_ROM_PTR(&pin_PD02) },
|
||||
{ MP_ROM_QSTR(MP_QSTR_SDIO_DATA), MP_ROM_PTR(&sdio_data_tuple) },
|
||||
|
||||
{ MP_OBJ_NEW_QSTR(MP_QSTR_CAN_RX), MP_ROM_PTR(&pin_PB09) },
|
||||
{ MP_OBJ_NEW_QSTR(MP_QSTR_CAN_TX), MP_ROM_PTR(&pin_PB08) },
|
||||
};
|
||||
MP_DEFINE_CONST_DICT(board_module_globals, board_module_globals_table);
|
||||
|
|
|
@ -0,0 +1,297 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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 <string.h>
|
||||
|
||||
#include "py/runtime.h"
|
||||
#include "py/mperrno.h"
|
||||
|
||||
#include "common-hal/canio/CAN.h"
|
||||
#include "peripherals/periph.h"
|
||||
#include "shared-bindings/microcontroller/Pin.h"
|
||||
#include "shared-bindings/util.h"
|
||||
#include "supervisor/port.h"
|
||||
|
||||
STATIC bool reserved_can[MP_ARRAY_SIZE(mcu_can_banks)];
|
||||
|
||||
STATIC const mcu_periph_obj_t *find_pin_function(const mcu_periph_obj_t *table, size_t sz, const mcu_pin_obj_t *pin, int periph_index) {
|
||||
for(size_t i = 0; i<sz; i++, table++) {
|
||||
if (periph_index != -1 && periph_index != table->periph_index) {
|
||||
continue;
|
||||
}
|
||||
if (pin == table->pin) {
|
||||
return table;
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
void common_hal_canio_can_construct(canio_can_obj_t *self, mcu_pin_obj_t *tx, mcu_pin_obj_t *rx, int baudrate, bool loopback, bool silent)
|
||||
{
|
||||
#define DIV_ROUND(a, b) (((a) + (b)/2) / (b))
|
||||
#define DIV_ROUND_UP(a, b) (((a) + (b) - 1) / (b))
|
||||
|
||||
const uint8_t can_tx_len = MP_ARRAY_SIZE(mcu_can_tx_list);
|
||||
const uint8_t can_rx_len = MP_ARRAY_SIZE(mcu_can_rx_list);
|
||||
|
||||
const mcu_periph_obj_t *mcu_tx = find_pin_function(mcu_can_tx_list, can_tx_len, tx, -1);
|
||||
if (!mcu_tx) {
|
||||
mp_raise_ValueError_varg(translate("Invalid %q pin selection"), MP_QSTR_tx);
|
||||
}
|
||||
int periph_index = mcu_tx->periph_index;
|
||||
|
||||
const mcu_periph_obj_t *mcu_rx = find_pin_function(mcu_can_rx_list, can_rx_len, rx, periph_index);
|
||||
if (!mcu_rx) {
|
||||
mp_raise_ValueError_varg(translate("Invalid %q pin selection"), MP_QSTR_rx);
|
||||
}
|
||||
|
||||
if (reserved_can[periph_index]) {
|
||||
mp_raise_ValueError(translate("Hardware busy, try alternative pins"));
|
||||
}
|
||||
|
||||
const uint32_t can_frequency = 42000000;
|
||||
uint32_t clocks_per_bit = DIV_ROUND(can_frequency, baudrate);
|
||||
uint32_t clocks_to_sample = DIV_ROUND(clocks_per_bit * 7, 8);
|
||||
uint32_t clocks_after_sample = clocks_per_bit - clocks_to_sample;
|
||||
uint32_t divisor = MAX(DIV_ROUND_UP(clocks_to_sample, 16), DIV_ROUND_UP(clocks_after_sample, 8));
|
||||
const uint32_t sjw = 3;
|
||||
|
||||
uint32_t tq_per_bit = DIV_ROUND(clocks_per_bit, divisor);
|
||||
uint32_t tq_to_sample = DIV_ROUND(clocks_to_sample, divisor);
|
||||
uint32_t tq_after_sample = tq_per_bit - tq_to_sample;
|
||||
|
||||
if (divisor > 1023) {
|
||||
mp_raise_OSError(MP_EINVAL); // baudrate cannot be attained (16kHz or something is lower bound, should never happen)
|
||||
}
|
||||
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStruct = {
|
||||
.Pin = pin_mask(tx->number),
|
||||
.Speed = GPIO_SPEED_FREQ_VERY_HIGH,
|
||||
.Mode = GPIO_MODE_AF_PP,
|
||||
.Pull = GPIO_PULLUP,
|
||||
.Alternate = mcu_tx->altfn_index,
|
||||
};
|
||||
HAL_GPIO_Init(pin_port(tx->port), &GPIO_InitStruct);
|
||||
|
||||
GPIO_InitStruct.Pin = pin_mask(rx->number);
|
||||
GPIO_InitStruct.Alternate = mcu_rx->altfn_index;
|
||||
HAL_GPIO_Init(pin_port(rx->port), &GPIO_InitStruct);
|
||||
}
|
||||
|
||||
CAN_TypeDef *hw = mcu_can_banks[periph_index - 1];
|
||||
|
||||
// CAN2 shares resources with CAN1. So we always enable CAN1, then split
|
||||
// the filter banks equally between them.
|
||||
|
||||
__HAL_RCC_CAN1_CLK_ENABLE();
|
||||
|
||||
if(hw == CAN2) {
|
||||
__HAL_RCC_CAN2_CLK_ENABLE();
|
||||
self->start_filter_bank = 14;
|
||||
self->end_filter_bank = 28;
|
||||
self->filter_hw = CAN1;
|
||||
} else {
|
||||
self->start_filter_bank = 0;
|
||||
self->end_filter_bank = 14;
|
||||
self->filter_hw = hw;
|
||||
}
|
||||
|
||||
CAN_InitTypeDef init = {
|
||||
.AutoRetransmission = ENABLE,
|
||||
.AutoBusOff = ENABLE,
|
||||
.Prescaler = divisor,
|
||||
.Mode = (loopback ? CAN_MODE_LOOPBACK : 0) | (silent ? CAN_MODE_SILENT_LOOPBACK : 0),
|
||||
.SyncJumpWidth = (sjw-1) << CAN_BTR_SJW_Pos,
|
||||
.TimeSeg1 = (tq_to_sample-2) << CAN_BTR_TS1_Pos,
|
||||
.TimeSeg2 = (tq_after_sample-1) << CAN_BTR_TS2_Pos,
|
||||
};
|
||||
|
||||
self->periph_index = periph_index;
|
||||
self->silent = silent;
|
||||
self->loopback = loopback;
|
||||
self->baudrate = baudrate;
|
||||
|
||||
self->handle.Instance = hw;
|
||||
self->handle.Init = init;
|
||||
self->handle.State = HAL_CAN_STATE_RESET;
|
||||
|
||||
HAL_CAN_Init(&self->handle);
|
||||
|
||||
// Set the filter split as 14:14
|
||||
// COULDDO(@jepler): Dynamically allocate filter banks between CAN1/2
|
||||
self->filter_hw->FMR |= CAN_FMR_FINIT;
|
||||
self->filter_hw->FMR = CAN_FMR_FINIT | (14 << CAN_FMR_CAN2SB_Pos);
|
||||
|
||||
// Clear every filter enable bit for this can HW
|
||||
uint32_t fa1r = self->filter_hw->FA1R;
|
||||
for (int i = self->start_filter_bank; i<self->end_filter_bank; i++) {
|
||||
fa1r &= ~(1 << i);
|
||||
}
|
||||
self->filter_hw->FA1R = fa1r;
|
||||
CLEAR_BIT(self->filter_hw->FMR, CAN_FMR_FINIT);
|
||||
|
||||
HAL_CAN_Start(&self->handle);
|
||||
|
||||
reserved_can[periph_index] = true;
|
||||
}
|
||||
|
||||
bool common_hal_canio_can_loopback_get(canio_can_obj_t *self)
|
||||
{
|
||||
return self->loopback;
|
||||
}
|
||||
|
||||
int common_hal_canio_can_baudrate_get(canio_can_obj_t *self)
|
||||
{
|
||||
return self->baudrate;
|
||||
}
|
||||
|
||||
int common_hal_canio_can_transmit_error_count_get(canio_can_obj_t *self)
|
||||
{
|
||||
return (self->handle.Instance->ESR & CAN_ESR_TEC) >> CAN_ESR_TEC_Pos;
|
||||
}
|
||||
|
||||
int common_hal_canio_can_receive_error_count_get(canio_can_obj_t *self)
|
||||
{
|
||||
return (self->handle.Instance->ESR & CAN_ESR_REC) >> CAN_ESR_REC_Pos;
|
||||
}
|
||||
|
||||
canio_bus_state_t common_hal_canio_can_state_get(canio_can_obj_t *self) {
|
||||
uint32_t esr = self->handle.Instance->ESR;
|
||||
if (READ_BIT(esr, CAN_ESR_BOFF)) {
|
||||
return BUS_STATE_OFF;
|
||||
}
|
||||
if (READ_BIT(esr, CAN_ESR_EPVF)) {
|
||||
return BUS_STATE_ERROR_PASSIVE;
|
||||
}
|
||||
if (READ_BIT(esr, CAN_ESR_EWGF)) {
|
||||
return BUS_STATE_ERROR_WARNING;
|
||||
}
|
||||
return BUS_STATE_ERROR_ACTIVE;
|
||||
}
|
||||
|
||||
void common_hal_canio_can_restart(canio_can_obj_t *self) {
|
||||
if (!common_hal_canio_can_auto_restart_get(self)) {
|
||||
// "If ABOM is cleared, the software must initiate the recovering
|
||||
// sequence by requesting bxCAN to enter and to leave initialization
|
||||
// mode."
|
||||
self->handle.Instance->MCR |= CAN_MCR_INRQ;
|
||||
while ((self->handle.Instance->MSR & CAN_MSR_INAK) == 0) {
|
||||
}
|
||||
self->handle.Instance->MCR &= ~CAN_MCR_INRQ;
|
||||
while ((self->handle.Instance->MSR & CAN_MSR_INAK)) {
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool common_hal_canio_can_auto_restart_get(canio_can_obj_t *self) {
|
||||
return READ_BIT(self->handle.Instance->MCR, CAN_MCR_ABOM);
|
||||
}
|
||||
|
||||
void common_hal_canio_can_auto_restart_set(canio_can_obj_t *self, bool value) {
|
||||
if(value) {
|
||||
SET_BIT(self->handle.Instance->MCR, CAN_MCR_ABOM);
|
||||
} else {
|
||||
CLEAR_BIT(self->handle.Instance->MCR, CAN_MCR_ABOM);
|
||||
}
|
||||
}
|
||||
|
||||
void common_hal_canio_can_send(canio_can_obj_t *self, mp_obj_t message_in)
|
||||
{
|
||||
canio_message_obj_t *message = message_in;
|
||||
uint32_t mailbox;
|
||||
bool rtr = message->base.type == &canio_remote_transmission_request_type;
|
||||
CAN_TxHeaderTypeDef header = {
|
||||
.StdId = message->id,
|
||||
.ExtId = message->id,
|
||||
.IDE = message->extended ? CAN_ID_EXT : CAN_ID_STD,
|
||||
.RTR = rtr ? CAN_RTR_REMOTE : CAN_RTR_DATA,
|
||||
.DLC = message->size,
|
||||
};
|
||||
uint32_t free_level = HAL_CAN_GetTxMailboxesFreeLevel(&self->handle);
|
||||
if (free_level == 0) {
|
||||
// There's no free Tx mailbox. We need to cancel some message without
|
||||
// transmitting it, because once the bus returns to active state it's
|
||||
// preferable to transmit the newest messages instead of older messages.
|
||||
//
|
||||
// We don't strictly guarantee that we abort the oldest Tx request,
|
||||
// rather we just abort a different index each time. This permits us
|
||||
// to just track a single cancel index
|
||||
HAL_CAN_AbortTxRequest(&self->handle, 1 << (self->cancel_mailbox));
|
||||
self->cancel_mailbox = (self->cancel_mailbox + 1) % 3;
|
||||
// The abort request may not have completed immediately, so wait for
|
||||
// the Tx mailbox to become free
|
||||
do {
|
||||
free_level = HAL_CAN_GetTxMailboxesFreeLevel(&self->handle);
|
||||
} while (!free_level);
|
||||
}
|
||||
HAL_StatusTypeDef status = HAL_CAN_AddTxMessage(&self->handle, &header, message->data, &mailbox);
|
||||
if (status != HAL_OK) {
|
||||
// this is a "shouldn't happen" condition. we don't throw because the
|
||||
// contract of send() is that it queues the packet to be sent if
|
||||
// possible and does not signal success or failure to actually send.
|
||||
return;
|
||||
}
|
||||
|
||||
// wait 8ms (hard coded for now) for TX to occur
|
||||
uint64_t deadline = port_get_raw_ticks(NULL) + 8;
|
||||
while (port_get_raw_ticks(NULL) < deadline && HAL_CAN_IsTxMessagePending(&self->handle, 1 << mailbox)) {
|
||||
RUN_BACKGROUND_TASKS;
|
||||
}
|
||||
}
|
||||
|
||||
bool common_hal_canio_can_silent_get(canio_can_obj_t *self) {
|
||||
return self->silent;
|
||||
}
|
||||
|
||||
bool common_hal_canio_can_deinited(canio_can_obj_t *self) {
|
||||
return !self->handle.Instance;
|
||||
}
|
||||
|
||||
void common_hal_canio_can_check_for_deinit(canio_can_obj_t *self) {
|
||||
if (common_hal_canio_can_deinited(self)) {
|
||||
raise_deinited_error();
|
||||
}
|
||||
}
|
||||
|
||||
void common_hal_canio_can_deinit(canio_can_obj_t *self)
|
||||
{
|
||||
if (self->handle.Instance) {
|
||||
SET_BIT(self->handle.Instance->MCR, CAN_MCR_RESET);
|
||||
while (READ_BIT(self->handle.Instance->MCR, CAN_MCR_RESET)) {
|
||||
}
|
||||
reserved_can[self->periph_index] = 0;
|
||||
}
|
||||
self->handle.Instance = NULL;
|
||||
}
|
||||
|
||||
void common_hal_canio_reset(void) {
|
||||
for (size_t i=0; i<MP_ARRAY_SIZE(mcu_can_banks); i++) {
|
||||
SET_BIT(mcu_can_banks[i]->MCR, CAN_MCR_RESET);
|
||||
reserved_can[i] = 0;
|
||||
}
|
||||
}
|
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "py/obj.h"
|
||||
#include "shared-bindings/canio/__init__.h"
|
||||
#include "shared-bindings/canio/CAN.h"
|
||||
#include "common-hal/microcontroller/Pin.h"
|
||||
#include "common-hal/canio/__init__.h"
|
||||
#include "shared-module/canio/Message.h"
|
||||
|
||||
#include "stm32f4xx_hal.h"
|
||||
#include "stm32f4xx_hal_can.h"
|
||||
|
||||
#define FILTER_BANK_COUNT (28)
|
||||
|
||||
typedef struct canio_can_obj {
|
||||
mp_obj_base_t base;
|
||||
CAN_HandleTypeDef handle;
|
||||
CAN_TypeDef *filter_hw;
|
||||
int baudrate;
|
||||
const mcu_pin_obj_t *rx_pin;
|
||||
const mcu_pin_obj_t *tx_pin;
|
||||
bool loopback:1;
|
||||
bool silent:1;
|
||||
bool auto_restart:1;
|
||||
bool fifo0_in_use:1;
|
||||
bool fifo1_in_use:1;
|
||||
uint8_t periph_index:2;
|
||||
uint8_t cancel_mailbox;
|
||||
uint8_t start_filter_bank;
|
||||
uint8_t end_filter_bank;
|
||||
long filter_in_use; // bitmask for the 28 filter banks
|
||||
} canio_can_obj_t;
|
|
@ -0,0 +1,315 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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 <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "py/obj.h"
|
||||
#include "py/runtime.h"
|
||||
|
||||
#include "common-hal/canio/__init__.h"
|
||||
#include "common-hal/canio/Listener.h"
|
||||
#include "shared-bindings/canio/Listener.h"
|
||||
#include "shared-bindings/util.h"
|
||||
#include "supervisor/shared/tick.h"
|
||||
#include "supervisor/shared/safe_mode.h"
|
||||
|
||||
STATIC void allow_filter_change(canio_can_obj_t *can) {
|
||||
can->filter_hw->FMR |= CAN_FMR_FINIT;
|
||||
}
|
||||
|
||||
STATIC void prevent_filter_change(canio_can_obj_t *can) {
|
||||
can->filter_hw->FMR &= ~CAN_FMR_FINIT;
|
||||
}
|
||||
|
||||
STATIC bool filter_in_use(canio_can_obj_t *can, int idx) {
|
||||
return can->filter_hw->FA1R & (1<<idx);
|
||||
}
|
||||
|
||||
// One filter bank can hold:
|
||||
// * one extended mask
|
||||
// * two extended ids
|
||||
// * two standard masks
|
||||
// * four extended ids
|
||||
// However, stm needs two filters to permit RTR and non-RTR messages
|
||||
// so we ONLY use mask-type filter banks
|
||||
STATIC size_t num_filters_needed(size_t nmatch, canio_match_obj_t **matches) {
|
||||
if (nmatch == 0) {
|
||||
return 1;
|
||||
}
|
||||
size_t num_extended_mask = 0;
|
||||
size_t num_standard_mask = 1;
|
||||
for(size_t i=0; i<nmatch; i++) {
|
||||
if (matches[i]->extended) {
|
||||
num_extended_mask += 1;
|
||||
} else {
|
||||
num_standard_mask += 1;
|
||||
}
|
||||
}
|
||||
return num_extended_mask + num_standard_mask/2;
|
||||
}
|
||||
|
||||
STATIC size_t num_filters_available(canio_can_obj_t *can) {
|
||||
size_t available = 0;
|
||||
for(size_t i = can->start_filter_bank; i < can->end_filter_bank; i++) {
|
||||
if (!filter_in_use(can, i)) {
|
||||
available++;
|
||||
}
|
||||
}
|
||||
return available;
|
||||
}
|
||||
|
||||
STATIC void clear_filters(canio_listener_obj_t *self) {
|
||||
canio_can_obj_t *can = self->can;
|
||||
|
||||
allow_filter_change(can);
|
||||
uint32_t fa1r = can->filter_hw->FA1R;
|
||||
for(size_t i = can->start_filter_bank; i < can->end_filter_bank; i++) {
|
||||
if (((can->filter_hw->FFA1R >> i) & 1) == self->fifo_idx) {
|
||||
fa1r &= ~(1<<i);
|
||||
}
|
||||
}
|
||||
can->filter_hw->FA1R = fa1r;
|
||||
prevent_filter_change(can);
|
||||
}
|
||||
|
||||
STATIC int next_filter(canio_can_obj_t *can) {
|
||||
uint32_t fa1r = can->filter_hw->FA1R;
|
||||
for(size_t i = can->start_filter_bank; i < can->end_filter_bank; i++) {
|
||||
if (!(fa1r & (1<<i))) {
|
||||
return i;
|
||||
}
|
||||
}
|
||||
reset_into_safe_mode(MICROPY_FATAL_ERROR);
|
||||
return -1;
|
||||
}
|
||||
|
||||
// IDE = "extended ID" flag of packet header. We always add this bit to the
|
||||
// mask because a match is always for just one kind of address length
|
||||
#define FILTER16_IDE (1<<3)
|
||||
#define FILTER32_IDE (1<<2)
|
||||
|
||||
STATIC void install_standard_filter(canio_listener_obj_t *self, canio_match_obj_t *match1, canio_match_obj_t *match2) {
|
||||
int bank = next_filter(self->can);
|
||||
|
||||
// filter is already deactivated, so we skip deactivating it here
|
||||
// CLEAR_BIT(self->can->filter_hw->FA1R, bank);
|
||||
|
||||
self->can->filter_hw->sFilterRegister[bank].FR1 =
|
||||
(((match1->id & 0x7ff) << 5)) |
|
||||
(((match1->mask & 0x7ff) << 5 | FILTER16_IDE)) << 16;
|
||||
self->can->filter_hw->sFilterRegister[bank].FR2 =
|
||||
(((match2->id & 0x7ff) << 5)) |
|
||||
(((match2->mask & 0x7ff) << 5 | FILTER16_IDE)) << 16;
|
||||
|
||||
// filter mode: 0 = mask
|
||||
// (this bit should be clear already, we never set it; but just in case)
|
||||
CLEAR_BIT(self->can->filter_hw->FM1R, 1 << bank);
|
||||
// filter scale: 0 = 16 bits
|
||||
CLEAR_BIT(self->can->filter_hw->FS1R, 1 << bank);
|
||||
// fifo assignment: 1 = FIFO 1
|
||||
if (self->fifo_idx) {
|
||||
SET_BIT(self->can->filter_hw->FFA1R, 1 << bank);
|
||||
} else {
|
||||
CLEAR_BIT(self->can->filter_hw->FFA1R, 1 << bank);
|
||||
}
|
||||
|
||||
// filter activation: 1 = enabled
|
||||
SET_BIT(self->can->filter_hw->FA1R, 1 << bank);
|
||||
}
|
||||
|
||||
STATIC void install_extended_filter(canio_listener_obj_t *self, canio_match_obj_t *match) {
|
||||
int bank = next_filter(self->can);
|
||||
|
||||
// filter is already deactivated, so we skip deactivating it here
|
||||
// CLEAR_BIT(self->can->filter_hw->FA1R, bank);
|
||||
|
||||
self->can->filter_hw->sFilterRegister[bank].FR1 =
|
||||
((match->id << 3) | FILTER32_IDE);
|
||||
self->can->filter_hw->sFilterRegister[bank].FR2 =
|
||||
((match->mask << 3) | FILTER32_IDE);
|
||||
|
||||
// filter mode: 0 = mask
|
||||
// (this bit should be clear already, we never set it; but just in case)
|
||||
CLEAR_BIT(self->can->filter_hw->FM1R, 1 << bank);
|
||||
// filter scale: 1 = 32 bits
|
||||
SET_BIT(self->can->filter_hw->FS1R, 1 << bank);
|
||||
// fifo assignment: 1 = FIFO 1
|
||||
if (self->fifo_idx) {
|
||||
SET_BIT(self->can->filter_hw->FFA1R, 1 << bank);
|
||||
} else {
|
||||
CLEAR_BIT(self->can->filter_hw->FFA1R, 1 << bank);
|
||||
}
|
||||
|
||||
// filter activation: 1 = enabled
|
||||
SET_BIT(self->can->filter_hw->FA1R, 1 << bank);
|
||||
}
|
||||
|
||||
STATIC void install_all_match_filter(canio_listener_obj_t *self) {
|
||||
int bank = next_filter(self->can);
|
||||
|
||||
// filter is already deactivated, so we skip deactivating it here
|
||||
// CLEAR_BIT(self->can->filter_hw->FA1R, bank);
|
||||
|
||||
self->can->filter_hw->sFilterRegister[bank].FR1 = 0;
|
||||
self->can->filter_hw->sFilterRegister[bank].FR2 = 0;
|
||||
|
||||
// filter mode: 0 = mask
|
||||
// (this bit should be clear already, we never set it; but just in case)
|
||||
CLEAR_BIT(self->can->filter_hw->FM1R, bank);
|
||||
// filter scale: 1 = 32 bits
|
||||
SET_BIT(self->can->filter_hw->FS1R, bank);
|
||||
// fifo assignment: 1 = FIFO 1
|
||||
if (self->fifo_idx) {
|
||||
SET_BIT(self->can->filter_hw->FFA1R, bank);
|
||||
} else {
|
||||
CLEAR_BIT(self->can->filter_hw->FFA1R, bank);
|
||||
}
|
||||
|
||||
// filter activation: 1 = enabled
|
||||
SET_BIT(self->can->filter_hw->FA1R, (1 << bank));
|
||||
}
|
||||
|
||||
|
||||
#define NO_ADDRESS (-1)
|
||||
void set_filters(canio_listener_obj_t *self, size_t nmatch, canio_match_obj_t **matches) {
|
||||
allow_filter_change(self->can);
|
||||
if (!nmatch) {
|
||||
install_all_match_filter(self);
|
||||
} else {
|
||||
canio_match_obj_t *first_match = NULL;
|
||||
for(size_t i = 0; i<nmatch; i++) {
|
||||
if(matches[i]->extended) {
|
||||
install_extended_filter(self, matches[i]);
|
||||
} else {
|
||||
if (first_match) {
|
||||
install_standard_filter(self, first_match, matches[i]);
|
||||
first_match = NULL;
|
||||
} else {
|
||||
first_match = matches[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
if (first_match) {
|
||||
install_standard_filter(self, first_match, first_match);
|
||||
}
|
||||
}
|
||||
prevent_filter_change(self->can);
|
||||
}
|
||||
|
||||
|
||||
void common_hal_canio_listener_construct(canio_listener_obj_t *self, canio_can_obj_t *can, size_t nmatch, canio_match_obj_t **matches, float timeout) {
|
||||
if (!can->fifo0_in_use) {
|
||||
self->fifo_idx = 0;
|
||||
self->rfr = &can->handle.Instance->RF0R;
|
||||
can->fifo0_in_use = true;
|
||||
} else if (!can->fifo1_in_use) {
|
||||
self->fifo_idx = 1;
|
||||
self->rfr = &can->handle.Instance->RF1R;
|
||||
can->fifo1_in_use = true;
|
||||
} else {
|
||||
mp_raise_ValueError(translate("All RX FIFOs in use"));
|
||||
}
|
||||
|
||||
if (num_filters_needed(nmatch, matches) > num_filters_available(can)) {
|
||||
mp_raise_ValueError(translate("Filters too complex"));
|
||||
}
|
||||
|
||||
// Nothing can fail now so it's safe to assign self->can
|
||||
self->can = can;
|
||||
|
||||
self->mailbox = &can->handle.Instance->sFIFOMailBox[self->fifo_idx];
|
||||
set_filters(self, nmatch, matches);
|
||||
common_hal_canio_listener_set_timeout(self, timeout);
|
||||
}
|
||||
|
||||
void common_hal_canio_listener_set_timeout(canio_listener_obj_t *self, float timeout) {
|
||||
self->timeout_ms = (int)MICROPY_FLOAT_C_FUN(ceil)(timeout * 1000);
|
||||
}
|
||||
|
||||
float common_hal_canio_listener_get_timeout(canio_listener_obj_t *self) {
|
||||
return self->timeout_ms / 1000.0f;
|
||||
}
|
||||
|
||||
void common_hal_canio_listener_check_for_deinit(canio_listener_obj_t *self) {
|
||||
if (!self->can) {
|
||||
raise_deinited_error();
|
||||
}
|
||||
common_hal_canio_can_check_for_deinit(self->can);
|
||||
}
|
||||
|
||||
int common_hal_canio_listener_in_waiting(canio_listener_obj_t *self) {
|
||||
return *(self->rfr) & CAN_RF0R_FMP0;
|
||||
}
|
||||
|
||||
mp_obj_t common_hal_canio_listener_receive(canio_listener_obj_t *self) {
|
||||
if (!common_hal_canio_listener_in_waiting(self)) {
|
||||
uint64_t deadline = supervisor_ticks_ms64() + self->timeout_ms;
|
||||
do {
|
||||
if (supervisor_ticks_ms64() > deadline) {
|
||||
return NULL;
|
||||
}
|
||||
} while (!common_hal_canio_listener_in_waiting(self));
|
||||
}
|
||||
|
||||
uint32_t rir = self->mailbox->RIR;
|
||||
uint32_t rdtr = self->mailbox->RDTR;
|
||||
|
||||
bool rtr = rir & CAN_RI0R_RTR;
|
||||
canio_message_obj_t *message = m_new_obj(canio_message_obj_t);
|
||||
message->base.type = rtr ? &canio_remote_transmission_request_type : &canio_message_type;
|
||||
message->extended = rir & CAN_RI0R_IDE;
|
||||
if (message->extended) {
|
||||
message->id = rir >> 3;
|
||||
} else {
|
||||
message->id = rir >> 21;
|
||||
}
|
||||
message->size = rdtr & CAN_RDT0R_DLC;
|
||||
if (!rtr) {
|
||||
uint32_t payload[] = { self->mailbox->RDLR, self->mailbox->RDHR };
|
||||
MP_STATIC_ASSERT(sizeof(payload) == sizeof(message->data));
|
||||
memcpy(message->data, payload, sizeof(payload));
|
||||
}
|
||||
// Release the mailbox
|
||||
SET_BIT(*self->rfr, CAN_RF0R_RFOM0);
|
||||
return message;
|
||||
}
|
||||
|
||||
void common_hal_canio_listener_deinit(canio_listener_obj_t *self) {
|
||||
if (self->can) {
|
||||
clear_filters(self);
|
||||
if (self->fifo_idx == 0) {
|
||||
self->can->fifo0_in_use = false;
|
||||
}
|
||||
if (self->fifo_idx == 1) {
|
||||
self->can->fifo1_in_use = false;
|
||||
}
|
||||
}
|
||||
self->fifo_idx = -1;
|
||||
self->can = NULL;
|
||||
self->mailbox = NULL;
|
||||
self->rfr = NULL;
|
||||
}
|
|
@ -0,0 +1,39 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common-hal/canio/CAN.h"
|
||||
#include "shared-module/canio/Match.h"
|
||||
|
||||
typedef struct canio_listener_obj {
|
||||
mp_obj_base_t base;
|
||||
canio_can_obj_t *can;
|
||||
CAN_FIFOMailBox_TypeDef *mailbox;
|
||||
__IO uint32_t *rfr;
|
||||
uint32_t timeout_ms;
|
||||
uint8_t fifo_idx;
|
||||
} canio_listener_obj_t;
|
|
@ -0,0 +1,25 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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.
|
||||
*/
|
|
@ -0,0 +1,27 @@
|
|||
/*
|
||||
* This file is part of the MicroPython project, http://micropython.org/
|
||||
*
|
||||
* The MIT License (MIT)
|
||||
*
|
||||
* Copyright (c) 2020 Jeff Epler 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.
|
||||
*/
|
||||
|
||||
#pragma once
|
|
@ -11,7 +11,7 @@
|
|||
*/
|
||||
#define HAL_MODULE_ENABLED
|
||||
#define HAL_ADC_MODULE_ENABLED
|
||||
// #define HAL_CAN_MODULE_ENABLED
|
||||
#define HAL_CAN_MODULE_ENABLED
|
||||
// #define HAL_CEC_MODULE_ENABLED
|
||||
// #define HAL_COMP_MODULE_ENABLED
|
||||
#define HAL_CORTEX_MODULE_ENABLED
|
||||
|
|
|
@ -4,6 +4,7 @@ INTERNAL_LIBM ?= 1
|
|||
USB_SERIAL_NUMBER_LENGTH ?= 24
|
||||
|
||||
ifeq ($(MCU_VARIANT),STM32F405xx)
|
||||
CIRCUITPY_CANIO = 1
|
||||
CIRCUITPY_FRAMEBUFFERIO ?= 1
|
||||
CIRCUITPY_RGBMATRIX ?= 1
|
||||
CIRCUITPY_SDIOIO ?= 1
|
||||
|
|
|
@ -216,3 +216,26 @@ const mcu_periph_obj_t mcu_sdio_data2_list[1] = {
|
|||
const mcu_periph_obj_t mcu_sdio_data3_list[1] = {
|
||||
PERIPH(1, 12, &pin_PC11),
|
||||
};
|
||||
|
||||
//CAN
|
||||
CAN_TypeDef * mcu_can_banks[2] = {CAN1, CAN2};
|
||||
|
||||
const mcu_periph_obj_t mcu_can_tx_list[6] = {
|
||||
PERIPH(1, 9, &pin_PA11),
|
||||
PERIPH(1, 9, &pin_PB08),
|
||||
PERIPH(1, 9, &pin_PD00),
|
||||
PERIPH(1, 9, &pin_PI09),
|
||||
|
||||
PERIPH(2, 9, &pin_PB12),
|
||||
PERIPH(2, 9, &pin_PB05),
|
||||
};
|
||||
|
||||
const mcu_periph_obj_t mcu_can_rx_list[6] = {
|
||||
PERIPH(1, 9, &pin_PA12),
|
||||
PERIPH(1, 9, &pin_PB09),
|
||||
PERIPH(1, 9, &pin_PD01),
|
||||
PERIPH(1, 9, &pin_PH13),
|
||||
|
||||
PERIPH(2, 9, &pin_PB13),
|
||||
PERIPH(2, 9, &pin_PB06),
|
||||
};
|
||||
|
|
|
@ -71,5 +71,11 @@ extern const mcu_periph_obj_t mcu_sdio_data1_list[1];
|
|||
extern const mcu_periph_obj_t mcu_sdio_data2_list[1];
|
||||
extern const mcu_periph_obj_t mcu_sdio_data3_list[1];
|
||||
|
||||
// CAN
|
||||
extern CAN_TypeDef * mcu_can_banks[2];
|
||||
|
||||
extern const mcu_periph_obj_t mcu_can_tx_list[6];
|
||||
extern const mcu_periph_obj_t mcu_can_rx_list[6];
|
||||
|
||||
|
||||
#endif // MICROPY_INCLUDED_STM32_PERIPHERALS_STM32F405XX_PERIPH_H
|
||||
|
|
Loading…
Reference in New Issue