Commit f126b6fe authored by Johny Mattsson's avatar Johny Mattsson Committed by J Mattsson
Browse files

Initial migration to IDFv5.0

Plenty of dependency adjustments, printf format specificier updates,
FreeRTOS type and macro name modernisation, not to mention API changes.

Still plenty of legacy/deprecated drivers in use which will need updating.

The following features have been removed due to no longer being available
from the IDF:
  - ADC hall effect sensor reading
  - Configuration of SD SPI host via sdmmc module (now must be done first
    via the spimaster module)
  - FAT partition selection on external SD cards; only the first FAT
    partition is supported by the IDF now

On the other hand, the eth module now supports the following new chipsets:
  - KSZ8001
  - KSZ8021
  - KSZ8031
  - KSZ8051
  - KSZ8061
  - KSZ8091
  - Possibly additional models in the LAN87xx series (the IDF docs aren't
    clear on precisely which models are handled)

Further, the sdmmc module is now available on the ESP32-S3 as well.
parent 2b8e3271
......@@ -37,6 +37,7 @@
#include "esp_system.h"
#include "esp_ota_ops.h"
#include "esp_partition.h"
#include "spi_flash_mmap.h"
static esp_ota_handle_t ota_handle;
static const esp_partition_t *next;
......
......@@ -114,7 +114,7 @@ static void pulsecnt_task(task_param_t param, task_prio_t prio)
(void)prio;
// we bit packed the unit number and status into 1 int in the IRAM interrupt so need to unpack here
uint32_t unit = (uint32_t)param & 0xffu;
uint8_t unit = (uint8_t)param & 0xffu;
int status = ((uint32_t)param >> 8);
// int16_t cur_count, evt_count = 0;
......@@ -217,7 +217,7 @@ static void pulsecnt_task(task_param_t param, task_prio_t prio)
// lua_pushinteger (L, status);
luaL_pcallx (L, 6, 0);
} else {
if (pc->is_debug) ESP_LOGI("pulsecnt", "Could not find cb for unit %d with ptr %d", unit, pc->cb_ref);
if (pc->is_debug) ESP_LOGI("pulsecnt", "Could not find cb for unit %d with ptr %ld", unit, pc->cb_ref);
}
}
......@@ -599,7 +599,7 @@ static int pulsecnt_create( lua_State *L ) {
pc->is_debug = true;
}
if (pc->is_debug) ESP_LOGI("pulsecnt", "Created obj for unit %d with callback ref of %d", pc->unit, pc->cb_ref );
if (pc->is_debug) ESP_LOGI("pulsecnt", "Created obj for unit %d with callback ref of %ld", pc->unit, pc->cb_ref );
return 1;
}
......
......@@ -13,6 +13,7 @@
#include "driver/sdspi_host.h"
#include "common.h"
#include "platform.h"
// We're limiting ourselves to the number of FAT volumes configured.
#define NUM_CARDS FF_VOLUMES
......@@ -20,8 +21,12 @@ sdmmc_card_t *lsdmmc_card[NUM_CARDS];
// local definition for SDSPI host
#define LSDMMC_HOST_SDSPI 100
#ifdef CONFIG_IDF_TARGET_ESP32
#define LSDMMC_HOST_HSPI (LSDMMC_HOST_SDSPI + HSPI_HOST)
#define LSDMMC_HOST_VSPI (LSDMMC_HOST_SDSPI + VSPI_HOST)
#endif
#define LSDMMC_HOST_SPI2 (LSDMMC_HOST_SDSPI + SPI2_HOST)
#define LSDMMC_HOST_SPI3 (LSDMMC_HOST_SDSPI + SPI3_HOST)
typedef struct {
sdmmc_card_t *card;
......@@ -31,25 +36,21 @@ typedef struct {
} lsdmmc_ud_t;
static void choose_partition(uint8_t pdrv, uint8_t part)
static bool is_field_present(lua_State *L, int idx, const char *field)
{
// Update the volume->partition mapping in FatFS
for (unsigned i = 0; i < FF_VOLUMES; ++i)
{
if (VolToPart[i].pd == pdrv)
VolToPart[i].pt = part;
}
lua_getfield(L, idx, field);
bool present = !lua_isnoneornil(L, -1);
lua_pop(L, 1);
return present;
}
static esp_err_t sdmmc_mount_fat(lsdmmc_ud_t *ud, const char *base_path, uint8_t partition)
static esp_err_t sdmmc_mount_fat(lsdmmc_ud_t *ud, const char *base_path)
{
esp_err_t err = ff_diskio_get_drive(&ud->pdrv);
if (err != ESP_OK)
return err;
choose_partition(ud->pdrv, partition);
ff_diskio_register_sdmmc(ud->pdrv, ud->card);
char drv[3] = { (char)('0' + ud->pdrv), ':', 0 };
......@@ -73,7 +74,6 @@ fail:
ud->fs = NULL;
}
esp_vfs_fat_unregister_path(base_path);
choose_partition(ud->pdrv, 0);
ff_diskio_unregister(ud->pdrv);
return err;
......@@ -101,7 +101,10 @@ static int lsdmmc_init( lua_State *L )
int slot = luaL_checkint( L, ++stack );
luaL_argcheck( L, slot == SDMMC_HOST_SLOT_0 || slot == SDMMC_HOST_SLOT_1 ||
slot == LSDMMC_HOST_HSPI || slot == LSDMMC_HOST_VSPI,
#ifdef CONFIG_IDF_TARGET_ESP32
slot == LSDMMC_HOST_HSPI || slot == LSDMMC_HOST_VSPI ||
#endif
slot == LSDMMC_HOST_SPI2 || slot == LSDMMC_HOST_SPI3,
stack, "invalid slot" );
bool is_sdspi = false;
......@@ -115,10 +118,7 @@ static int lsdmmc_init( lua_State *L )
int wp_pin = SDMMC_SLOT_NO_WP;
int freq_khz = SDMMC_FREQ_DEFAULT;
int width = SDMMC_HOST_FLAG_1BIT;
// additional entries for SDSPI configuration
int sck_pin = -1;
int mosi_pin = -1;
int miso_pin = -1;
// additional cs for SDSPI configuration
int cs_pin = -1;
if (lua_type( L, ++stack ) == LUA_TTABLE) {
......@@ -131,9 +131,12 @@ static int lsdmmc_init( lua_State *L )
// mandatory entries for SDSPI configuration
if (is_sdspi) {
sck_pin = opt_checkint_range( L, "sck_pin", -1, 0, GPIO_NUM_MAX );
mosi_pin = opt_checkint_range( L, "mosi_pin", -1, 0, GPIO_NUM_MAX );
miso_pin = opt_checkint_range( L, "miso_pin", -1, 0, GPIO_NUM_MAX );
if (is_field_present(L, -1, "sck_pin") ||
is_field_present(L, -1, "mosi_pin") ||
is_field_present(L, -1, "miso_pin"))
{
platform_print_deprecation_note("SCK/MOSI/MISO ignored; please configure via spimaster instead", "IDFv5");
}
cs_pin = opt_checkint_range( L, "cs_pin", -1, 0, GPIO_NUM_MAX );
}
......@@ -166,16 +169,16 @@ static int lsdmmc_init( lua_State *L )
}
if (res == ESP_OK || res == ESP_ERR_INVALID_STATE) {
sdmmc_host_t sdspi_host_config = SDSPI_HOST_DEFAULT();
sdmmc_host_t sdmmc_host_config = SDMMC_HOST_DEFAULT();
if (is_sdspi) {
// configure SDSPI slot
sdspi_slot_config_t slot_config = SDSPI_SLOT_CONFIG_DEFAULT();
slot_config.gpio_miso = miso_pin;
slot_config.gpio_mosi = mosi_pin;
slot_config.gpio_sck = sck_pin;
slot_config.gpio_cs = cs_pin;
slot_config.gpio_cd = cd_pin;
slot_config.gpio_wp = wp_pin;
res = sdspi_host_init_slot( slot, &slot_config );
sdspi_device_config_t dev_config = SDSPI_DEVICE_CONFIG_DEFAULT();
dev_config.gpio_cs = cs_pin;
dev_config.gpio_cd = cd_pin;
dev_config.gpio_wp = wp_pin;
res = sdspi_host_init_device(&dev_config, &sdspi_host_config.slot);
} else {
// configure SDMMC slot
sdmmc_slot_config_t slot_config = SDMMC_SLOT_CONFIG_DEFAULT();
......@@ -184,10 +187,7 @@ static int lsdmmc_init( lua_State *L )
res = sdmmc_host_init_slot( slot, &slot_config );
}
if (res == ESP_OK) {
// initialize card
sdmmc_host_t sdspi_host_config = SDSPI_HOST_DEFAULT();
sdmmc_host_t sdmmc_host_config = SDMMC_HOST_DEFAULT();
sdmmc_host_t *host_config = is_sdspi ? &sdspi_host_config : &sdmmc_host_config;
host_config->slot = slot;
host_config->flags &= ~SDMMC_HOST_FLAG_8BIT;
......@@ -352,13 +352,21 @@ static int lsdmmc_mount( lua_State *L )
(void)card;
const char *ldrv = luaL_checkstring(L, 2);
int part = luaL_optint(L, 3, 0);
if (!lua_isnoneornil(L, 3))
{
// Warn that this feature isn't around
platform_print_deprecation_note(
"partition selection not supported", "IDFv5");
// ...and error if used to select something we can no longer do
if (luaL_optint(L, 3, 0) > 1)
return luaL_error(L, "only first partition supported since IDFv5");
}
lua_settop(L, 2);
if (ud->fs == NULL)
{
esp_err_t err = sdmmc_mount_fat(ud, ldrv, part);
esp_err_t err = sdmmc_mount_fat(ud, ldrv);
if (err == ESP_OK)
{
// We need this when we unmount
......@@ -408,8 +416,12 @@ LROT_BEGIN(sdmmc, NULL, 0)
LROT_FUNCENTRY( init, lsdmmc_init )
LROT_NUMENTRY( HS1, SDMMC_HOST_SLOT_0 )
LROT_NUMENTRY( HS2, SDMMC_HOST_SLOT_1 )
#ifdef CONFIG_IDF_TARGET_ESP32
LROT_NUMENTRY( HSPI, LSDMMC_HOST_HSPI )
LROT_NUMENTRY( VSPI, LSDMMC_HOST_VSPI )
#endif
LROT_NUMENTRY( SPI2, LSDMMC_HOST_SPI2 )
LROT_NUMENTRY( SPI3, LSDMMC_HOST_SPI3 )
LROT_NUMENTRY( W1BIT, SDMMC_HOST_FLAG_1BIT )
LROT_NUMENTRY( W4BIT, SDMMC_HOST_FLAG_1BIT |
SDMMC_HOST_FLAG_4BIT )
......
......@@ -190,7 +190,7 @@ static int touch_create( lua_State *L ) {
tp->is_intr = opt_checkbool(L, "intrInitAtStart", true);
tp->thresTrigger = opt_checkint_range(L, "thresTrigger", TOUCH_TRIGGER_BELOW, TOUCH_TRIGGER_BELOW, TOUCH_TRIGGER_MAX);
if (tp->is_debug) ESP_LOGI(TAG, "isDebug: %d, filterMs: %d, lvolt: %d, hvolt: %d, atten: %d, slope: %d, intrInitAtStart: %d, thresTrigger: %d",
if (tp->is_debug) ESP_LOGI(TAG, "isDebug: %d, filterMs: %lu, lvolt: %d, hvolt: %d, atten: %d, slope: %d, intrInitAtStart: %d, thresTrigger: %d",
tp->is_debug, tp->filterMs, tp->lvolt, tp->hvolt, tp->atten, tp->slope, tp->is_intr, tp->thresTrigger);
// get the field pad. this can be passed in as int or table of ints. pad = 0 || {0,1,2,3,4,5,6,7,8,9}
......@@ -277,7 +277,7 @@ static int touch_create( lua_State *L ) {
// Initialize and start a software filter to detect slight change of capacitance.
if (tp->filterMs > 0) {
touch_pad_filter_start(tp->filterMs);
if (tp->is_debug) ESP_LOGI(TAG, "Set filter period to %d ms", tp->filterMs );
if (tp->is_debug) ESP_LOGI(TAG, "Set filter period to %lu ms", tp->filterMs );
}
// Register touch interrupt ISR
......@@ -320,7 +320,7 @@ static int touch_create( lua_State *L ) {
// prevent false triggering when detecting slight change of capacitance. Need to call
// touch_pad_filter_start before all touch filter APIs
if (tp->filterMs > 0) {
if (tp->is_debug) ESP_LOGI(TAG, "You provided a filter so turning on filter mode. filterMs: %d", tp->filterMs);
if (tp->is_debug) ESP_LOGI(TAG, "You provided a filter so turning on filter mode. filterMs: %lu", tp->filterMs);
esp_err_t err = touch_pad_filter_start(tp->filterMs);
if (err == ESP_ERR_INVALID_ARG) {
ESP_LOGI(TAG, "Filter start parameter error");
......
idf_component_register(
SRCS "dht.c" "flash_api.c" "onewire.c" "platform.c"
"platform_flash.c" "platform_partition.c" "platform_rmt.c"
"u8x8_nodemcu_hal.c" "ucg_nodemcu_hal.c" "wdt.c" "ws2812.c"
SRCS
"dht.c"
"onewire.c"
"platform.c"
"platform_flash.c"
"platform_partition.c"
"platform_rmt.c"
"u8x8_nodemcu_hal.c"
"ucg_nodemcu_hal.c"
"wdt.c"
"ws2812.c"
INCLUDE_DIRS "include"
REQUIRES "spiffs" "u8g2" "ucg" "driver_i2c" "task"
PRIV_REQUIRES "bootloader_support" "lua" "esp32"
REQUIRES
"driver"
"driver_i2c"
"spi_flash"
"spiffs"
"task"
"u8g2"
"ucg"
PRIV_REQUIRES
"bootloader_support"
"esp_rom"
"lua"
"soc"
)
/******************************************************************************
* Flash api for NodeMCU
* NodeMCU Team
* 2014-12-31
*******************************************************************************/
#include "flash_api.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include "rom/spi_flash.h"
#include "platform_wdt.h"
#include "esp_image_format.h"
#include "esp_flash_partitions.h"
#define FLASH_HDR_ADDR 0x1000
static inline esp_image_header_t flash_load_rom_header (void)
{
esp_image_header_t hdr;
if (ESP_OK !=
spi_flash_read (FLASH_HDR_ADDR, (uint32_t *)&hdr, sizeof (hdr)))
{
NODE_ERR("Failed to load flash header block!\n");
abort();
}
return hdr;
}
#define IRAM_SECTION __attribute__((section(".iram1")))
static void IRAM_SECTION update_flash_chip_size (uint32_t sz)
{
esp_rom_spiflash_config_param (
g_rom_flashchip.device_id,
sz,
g_rom_flashchip.block_size,
g_rom_flashchip.sector_size,
g_rom_flashchip.page_size,
g_rom_flashchip.status_mask);
}
static uint32_t __attribute__((section(".iram1"))) flash_detect_size_byte(void)
{
#define DETECT_SZ 32
uint32_t detected_size = FLASH_SIZE_1MBYTE;
uint8_t data_orig[DETECT_SZ] PLATFORM_ALIGNMENT = {0};
uint8_t data_new[DETECT_SZ] PLATFORM_ALIGNMENT = {0};
// Ensure we read something which isn't just 0xff...
const uint32_t offs = ESP_PARTITION_TABLE_OFFSET;
// Detect read failure or wrap-around on flash read to find end of flash
if (ESP_OK == spi_flash_read (offs, (uint32_t *)data_orig, DETECT_SZ))
{
update_flash_chip_size (FLASH_SIZE_16MBYTE);
while ((detected_size < FLASH_SIZE_16MBYTE) &&
(ESP_OK == spi_flash_read (
detected_size + offs, (uint32_t *)data_new, DETECT_SZ)) &&
(0 != memcmp(data_orig, data_new, DETECT_SZ)))
{
detected_size *= 2;
}
update_flash_chip_size (detected_size);
};
return detected_size;
#undef FLASH_BUFFER_SIZE_DETECT
}
uint32_t flash_safe_get_size_byte(void)
{
static uint32_t flash_size = 0;
if (flash_size == 0)
{
flash_size = flash_detect_size_byte();
}
return flash_size;
}
uint16_t flash_safe_get_sec_num(void)
{
return (flash_safe_get_size_byte() / (SPI_FLASH_SEC_SIZE));
}
uint32_t flash_rom_get_size_byte(void)
{
static uint32_t flash_size = 0;
if (flash_size == 0)
{
switch (flash_load_rom_header ().spi_size)
{
default: // Unknown flash size, fall back mode.
case ESP_IMAGE_FLASH_SIZE_1MB: flash_size = FLASH_SIZE_1MBYTE; break;
case ESP_IMAGE_FLASH_SIZE_2MB: flash_size = FLASH_SIZE_2MBYTE; break;
case ESP_IMAGE_FLASH_SIZE_4MB: flash_size = FLASH_SIZE_4MBYTE; break;
case ESP_IMAGE_FLASH_SIZE_8MB: flash_size = FLASH_SIZE_8MBYTE; break;
case ESP_IMAGE_FLASH_SIZE_16MB: flash_size = FLASH_SIZE_16MBYTE; break;
}
}
return flash_size;
}
static bool flash_rom_set_size_type(uint8_t size_code)
{
// Dangerous, here are dinosaur infested!!!!!
// Reboot required!!!
// If you don't know what you're doing, your nodemcu may turn into stone ...
NODE_DBG("\nBEGIN SET FLASH HEADER\n");
esp_image_header_t *hdr = (esp_image_header_t *)malloc (SPI_FLASH_SEC_SIZE);
if (!hdr)
return false;
if (ESP_OK == spi_flash_read (FLASH_HDR_ADDR, (uint32_t *)hdr, SPI_FLASH_SEC_SIZE))
{
hdr->spi_size = size_code;
if (ESP_OK == spi_flash_erase_sector (FLASH_HDR_ADDR / SPI_FLASH_SEC_SIZE))
{
NODE_DBG("\nERASE SUCCESS\n");
}
if (ESP_OK == spi_flash_write(FLASH_HDR_ADDR, (uint32_t *)hdr, SPI_FLASH_SEC_SIZE))
{
NODE_DBG("\nWRITE SUCCESS, %u\n", size_code);
}
}
free (hdr);
NODE_DBG("\nEND SET FLASH HEADER\n");
return true;
}
bool flash_rom_set_size_byte(uint32_t size)
{
// Dangerous, here are dinosaur infested!!!!!
// Reboot required!!!
bool ok = true;
uint8_t size_code = 0;
switch (size)
{
case FLASH_SIZE_1MBYTE: size_code = ESP_IMAGE_FLASH_SIZE_1MB; break;
case FLASH_SIZE_2MBYTE: size_code = ESP_IMAGE_FLASH_SIZE_2MB; break;
case FLASH_SIZE_4MBYTE: size_code = ESP_IMAGE_FLASH_SIZE_4MB; break;
case FLASH_SIZE_8MBYTE: size_code = ESP_IMAGE_FLASH_SIZE_8MB; break;
case FLASH_SIZE_16MBYTE: size_code = ESP_IMAGE_FLASH_SIZE_16MB; break;
default: ok = false; break;
}
if (ok)
ok = flash_rom_set_size_type (size_code);
return ok;
}
uint16_t flash_rom_get_sec_num(void)
{
return ( flash_rom_get_size_byte() / (SPI_FLASH_SEC_SIZE) );
}
uint8_t flash_rom_get_mode(void)
{
return flash_load_rom_header ().spi_mode;
}
uint32_t flash_rom_get_speed(void)
{
switch (flash_load_rom_header ().spi_speed)
{
case ESP_IMAGE_SPI_SPEED_40M: return 40000000;
case ESP_IMAGE_SPI_SPEED_26M: return 26700000; // TODO: verify 26.7MHz
case ESP_IMAGE_SPI_SPEED_20M: return 20000000;
case ESP_IMAGE_SPI_SPEED_80M: return 80000000;
default: break;
}
return 0;
}
esp_err_t flash_erase(size_t sector)
{
platform_wdt_feed();
return spi_flash_erase_sector(sector);
}
......@@ -2,7 +2,7 @@
#define _CPU_ESP32_H_
#include "sdkconfig.h"
#include "esp_spi_flash.h"
#include "spi_flash_mmap.h"
#define NUM_UART SOC_UART_NUM
......@@ -10,12 +10,4 @@
#define INTERNAL_FLASH_WRITE_UNIT_SIZE 4
#define INTERNAL_FLASH_READ_UNIT_SIZE 4
#define FLASH_SEC_NUM (flash_safe_get_sec_num())
// Determine whether an address is in the flash-cache range
static inline bool is_cache_flash_addr (uint32_t addr)
{
return addr >= 0x3F400000 && addr < 0x3FC00000;
}
#endif
#ifndef __FLASH_API_H__
#define __FLASH_API_H__
#include "platform.h"
#include "esp_spi_flash.h"
uint32_t flash_safe_get_size_byte(void);
uint16_t flash_safe_get_sec_num(void);
uint32_t flash_rom_get_size_byte(void);
bool flash_rom_set_size_byte(uint32_t);
uint16_t flash_rom_get_sec_num(void);
uint8_t flash_rom_get_mode(void);
uint32_t flash_rom_get_speed(void);
#define FLASH_SIZE_1MBYTE ( 1 * 1024 * 1024)
#define FLASH_SIZE_2MBYTE ( 2 * 1024 * 1024)
#define FLASH_SIZE_4MBYTE ( 4 * 1024 * 1024)
#define FLASH_SIZE_8MBYTE ( 8 * 1024 * 1024)
#define FLASH_SIZE_16MBYTE (16 * 1024 * 1024)
#define flash_write spi_flash_write
esp_err_t flash_erase(size_t sector);
#define flash_read spi_flash_read
#endif // __FLASH_API_H__
......@@ -90,7 +90,7 @@ typedef struct {
typedef struct {
QueueHandle_t queue;
xTaskHandle taskHandle;
TaskHandle_t taskHandle;
int receive_rf;
int error_rf;
char *line_buffer;
......@@ -137,7 +137,6 @@ int platform_adc_channel_exists( uint8_t adc, uint8_t channel );
uint8_t platform_adc_set_width( uint8_t adc, int bits );
uint8_t platform_adc_setup( uint8_t adc, uint8_t channel, uint8_t attn );
int platform_adc_read( uint8_t adc, uint8_t channel );
int platform_adc_read_hall_sensor( );
enum {
PLATFORM_ADC_ATTEN_0db = 0,
PLATFORM_ADC_ATTEN_2_5db = 1,
......@@ -220,9 +219,6 @@ int platform_ws2812_send( void );
uint32_t platform_flash_get_sector_of_address( uint32_t addr );
uint32_t platform_flash_write( const void *from, uint32_t toaddr, uint32_t size );
uint32_t platform_flash_read( void *to, uint32_t fromaddr, uint32_t size );
uint32_t platform_s_flash_write( const void *from, uint32_t toaddr, uint32_t size );
uint32_t platform_s_flash_read( void *to, uint32_t fromaddr, uint32_t size );
uint32_t platform_flash_get_num_sectors(void);
int platform_flash_erase_sector( uint32_t sector_id );
......
......@@ -63,6 +63,8 @@ sample code bearing this copyright.
#include "driver/rmt.h"
#include "driver/gpio.h"
#include "rom/gpio.h" // for gpio_matrix_out()
#include "soc/gpio_periph.h"
#include "esp_log.h"
#define TRUE (1==1)
......@@ -108,7 +110,7 @@ static const uint8_t owDefaultPower = 0;
static int onewire_rmt_init( uint8_t gpio_num )
{
if(!GPIO_IS_VALID_GPIO(gpio_num)) {
if(!platform_gpio_exists(gpio_num)) {
return PLATFORM_ERR;
}
......@@ -187,7 +189,7 @@ static void onewire_flush_rmt_rx_buf( void )
// check rmt TX&RX channel assignment and eventually attach them to the requested pin
static int onewire_rmt_attach_pin( uint8_t gpio_num )
{
if(!GPIO_IS_VALID_GPIO(gpio_num)) {
if(!platform_gpio_exists(gpio_num)) {
return PLATFORM_ERR;
}
......
......@@ -5,7 +5,9 @@
#include "soc/uart_reg.h"
#include <stdio.h>
#include <string.h>
#include <freertos/semphr.h>
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#include "freertos/semphr.h"
#include "lua.h"
#include "rom/uart.h"
#include "esp_log.h"
......@@ -22,8 +24,24 @@ int platform_init (void)
// *****************************************************************************
// GPIO subsection
int platform_gpio_exists( unsigned gpio ) { return GPIO_IS_VALID_GPIO(gpio); }
int platform_gpio_output_exists( unsigned gpio ) { return GPIO_IS_VALID_OUTPUT_GPIO(gpio); }
int platform_gpio_exists(unsigned gpio)
{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wtype-limits"
// Suppress ">= is always true" due to unsigned type here
return GPIO_IS_VALID_GPIO(gpio);
#pragma GCC diagnostic pop
}
int platform_gpio_output_exists(unsigned gpio)
{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wtype-limits"
// Suppress ">= is always true" due to unsigned type here
return GPIO_IS_VALID_OUTPUT_GPIO(gpio);
#pragma GCC diagnostic pop
}
// ****************************************************************************
......@@ -136,7 +154,7 @@ static void task_uart( void *pvParameters ){
uart_event_t event;
for(;;) {
if(xQueueReceive(uart_status[id].queue, (void * )&event, (portTickType)portMAX_DELAY)) {
if(xQueueReceive(uart_status[id].queue, (void * )&event, (TickType_t)portMAX_DELAY)) {
switch(event.type) {
case UART_DATA: {
// Attempt to coalesce received bytes to reduce risk of overrunning
......@@ -222,6 +240,7 @@ uint32_t platform_uart_setup( unsigned id, uint32_t baud, int databits, int pari
.baud_rate = baud,
.flow_ctrl = flow_control,
.rx_flow_ctrl_thresh = UART_FIFO_LEN - 16,
.source_clk = UART_SCLK_DEFAULT,
};
switch (databits)
......@@ -523,14 +542,6 @@ int platform_adc_read( uint8_t adc, uint8_t channel ) {
return value;
}
int platform_adc_read_hall_sensor( ) {
#if defined(CONFIG_IDF_TARGET_ESP32)
int value = hall_sensor_read( );
return value;
#else
return -1;
#endif
}
// *****************************************************************************
// I2C platform interface
......
#include "platform.h"
#include "flash_api.h"
#include "platform_wdt.h"
#include "esp_flash.h"
#include <stddef.h>
#include <stdlib.h>
#include <string.h>
......@@ -21,183 +22,43 @@ static uint32_t flashh_find_sector( uint32_t address, uint32_t *pstart, uint32_t
return sect_id;
}
uint32_t platform_flash_get_sector_of_address( uint32_t addr )
{
return flashh_find_sector( addr, NULL, NULL );
}
uint32_t platform_flash_get_num_sectors(void)
{
return flash_safe_get_sec_num ();
}
uint32_t platform_flash_write( const void *from, uint32_t toaddr, uint32_t size )
{
#ifndef INTERNAL_FLASH_WRITE_UNIT_SIZE
return platform_s_flash_write( from, toaddr, size );
#else // #ifindef INTERNAL_FLASH_WRITE_UNIT_SIZE
uint32_t temp, rest, ssize = size;
unsigned i;
char tmpdata[ INTERNAL_FLASH_WRITE_UNIT_SIZE ];
const uint8_t *pfrom = ( const uint8_t* )from;
const uint32_t blksize = INTERNAL_FLASH_WRITE_UNIT_SIZE;
const uint32_t blkmask = INTERNAL_FLASH_WRITE_UNIT_SIZE - 1;
// Align the start
if( toaddr & blkmask )
{
rest = toaddr & blkmask;
temp = toaddr & ~blkmask; // this is the actual aligned address
// memcpy( tmpdata, ( const void* )temp, blksize );
platform_s_flash_read( tmpdata, temp, blksize );
for( i = rest; size && ( i < blksize ); i ++, size --, pfrom ++ )
tmpdata[ i ] = *pfrom;
platform_s_flash_write( tmpdata, temp, blksize );
if( size == 0 )
return ssize;
toaddr = temp + blksize;
}
// The start address is now a multiple of blksize
// Compute how many bytes we can write as multiples of blksize
rest = size & blkmask;
temp = size & ~blkmask;
// Program the blocks now
if( temp )
{
platform_s_flash_write( pfrom, toaddr, temp );
toaddr += temp;
pfrom += temp;
}
// And the final part of a block if needed
if( rest )
{
// memcpy( tmpdata, ( const void* )toaddr, blksize );
platform_s_flash_read( tmpdata, toaddr, blksize );
for( i = 0; size && ( i < rest ); i ++, size --, pfrom ++ )
tmpdata[ i ] = *pfrom;
platform_s_flash_write( tmpdata, toaddr, blksize );
}
return ssize;
#endif // #ifndef INTERNAL_FLASH_WRITE_UNIT_SIZE
}
uint32_t platform_flash_read( void *to, uint32_t fromaddr, uint32_t size )
{
#ifndef INTERNAL_FLASH_READ_UNIT_SIZE
return platform_s_flash_read( to, fromaddr, size );
#else // #ifindef INTERNAL_FLASH_READ_UNIT_SIZE
uint32_t temp, rest, ssize = size;
unsigned i;
char tmpdata[ INTERNAL_FLASH_READ_UNIT_SIZE ] __attribute__ ((aligned(INTERNAL_FLASH_READ_UNIT_SIZE)));
uint8_t *pto = ( uint8_t* )to;
const uint32_t blksize = INTERNAL_FLASH_READ_UNIT_SIZE;
const uint32_t blkmask = INTERNAL_FLASH_READ_UNIT_SIZE - 1;
// Align the start
if( fromaddr & blkmask )
{
rest = fromaddr & blkmask;
temp = fromaddr & ~blkmask; // this is the actual aligned address
platform_s_flash_read( tmpdata, temp, blksize );
for( i = rest; size && ( i < blksize ); i ++, size --, pto ++ )
*pto = tmpdata[ i ];
if( size == 0 )
return ssize;
fromaddr = temp + blksize;
}
// The start address is now a multiple of blksize
// Compute how many bytes we can read as multiples of blksize
rest = size & blkmask;
temp = size & ~blkmask;
// Program the blocks now
if( temp )
{
platform_s_flash_read( pto, fromaddr, temp );
fromaddr += temp;
pto += temp;
}
// And the final part of a block if needed
if( rest )
{
platform_s_flash_read( tmpdata, fromaddr, blksize );
for( i = 0; size && ( i < rest ); i ++, size --, pto ++ )
*pto = tmpdata[ i ];
}
return ssize;
#endif // #ifndef INTERNAL_FLASH_READ_UNIT_SIZE
}
/*
* Assumptions:
* > toaddr is INTERNAL_FLASH_WRITE_UNIT_SIZE aligned
* > size is a multiple of INTERNAL_FLASH_WRITE_UNIT_SIZE
*/
uint32_t platform_s_flash_write( const void *from, uint32_t toaddr, uint32_t size )
{
esp_err_t r;
const uint32_t blkmask = INTERNAL_FLASH_WRITE_UNIT_SIZE - 1;
uint32_t *apbuf = NULL;
uint32_t fromaddr = (uint32_t)from;
if( (fromaddr & blkmask ) || is_cache_flash_addr(fromaddr)) {
apbuf = (uint32_t *)malloc(size);
if(!apbuf)
return 0;
memcpy(apbuf, from, size);
}
r = flash_write(toaddr, apbuf?(uint32_t *)apbuf:(uint32_t *)from, size);
if(apbuf)
free(apbuf);
if(ESP_OK == r)
return size;
else{
NODE_ERR( "ERROR in flash_write: r=%d at %08X\n", ( int )r, ( unsigned )toaddr);
esp_err_t err = esp_flash_write(NULL, from, toaddr, size);
if (err != ESP_OK)
return 0;
}
else
return size;
}
/*
* Assumptions:
* > fromaddr is INTERNAL_FLASH_READ_UNIT_SIZE aligned
* > size is a multiple of INTERNAL_FLASH_READ_UNIT_SIZE
*/
uint32_t platform_s_flash_read( void *to, uint32_t fromaddr, uint32_t size )
uint32_t platform_flash_read( void *to, uint32_t fromaddr, uint32_t size )
{
if (size==0)
esp_err_t err = esp_flash_write(NULL, to, fromaddr, size);
if (err != ESP_OK)
return 0;
esp_err_t r;
const uint32_t blkmask = (INTERNAL_FLASH_READ_UNIT_SIZE - 1);
if( ((uint32_t)to) & blkmask )
{
uint32_t size2=size-INTERNAL_FLASH_READ_UNIT_SIZE;
uint32_t* to2=(uint32_t*)((((uint32_t)to)&(~blkmask))+INTERNAL_FLASH_READ_UNIT_SIZE);
r = flash_read(fromaddr, to2, size2);
if(ESP_OK == r)
{
memmove(to,to2,size2);
char back[ INTERNAL_FLASH_READ_UNIT_SIZE ] __attribute__ ((aligned(INTERNAL_FLASH_READ_UNIT_SIZE)));
r=flash_read(fromaddr+size2,(uint32_t*)back,INTERNAL_FLASH_READ_UNIT_SIZE);
memcpy((uint8_t*)to+size2,back,INTERNAL_FLASH_READ_UNIT_SIZE);
}
}
else
r = flash_read(fromaddr, (uint32_t *)to, size);
if(ESP_OK == r)
return size;
else{
NODE_ERR( "ERROR in flash_read: r=%d at %08X sz %x\n", ( int )r, ( unsigned )fromaddr, size);
return 0;
}
}
int platform_flash_erase_sector( uint32_t sector_id )
{
return flash_erase( sector_id ) == ESP_OK ? PLATFORM_OK : PLATFORM_ERR;
platform_wdt_feed();
uint32_t addr = sector_id * INTERNAL_FLASH_SECTOR_SIZE;
esp_err_t err =
esp_flash_erase_region(NULL, addr, INTERNAL_FLASH_SECTOR_SIZE);
if (err == ESP_OK)
return PLATFORM_OK;
else
return PLATFORM_ERR;
}
......@@ -36,7 +36,7 @@
#include <string.h>
#include <stdlib.h>
#include "esp_flash_partitions.h"
#include "esp_spi_flash.h"
#include "esp_flash.h"
static inline bool possible_idx (uint8_t idx)
{
......@@ -50,8 +50,12 @@ bool platform_partition_info (uint8_t idx, platform_partition_t *info)
return false;
esp_partition_info_t pi;
esp_err_t err = spi_flash_read (
ESP_PARTITION_TABLE_OFFSET + idx * sizeof(pi), (uint32_t *)&pi, sizeof (pi));
esp_err_t err = esp_flash_read(
NULL,
(uint32_t *)&pi,
ESP_PARTITION_TABLE_OFFSET + idx * sizeof(pi),
sizeof (pi));
if (err != ESP_OK)
return false;
......@@ -66,42 +70,3 @@ bool platform_partition_info (uint8_t idx, platform_partition_t *info)
return true;
}
bool platform_partition_add (const platform_partition_t *info)
{
esp_partition_info_t *part_table =
(esp_partition_info_t *)malloc(SPI_FLASH_SEC_SIZE);
if (!part_table)
return false;
esp_err_t err = spi_flash_read (
ESP_PARTITION_TABLE_OFFSET, (uint32_t *)part_table, SPI_FLASH_SEC_SIZE);
if (err != ESP_OK)
goto out;
uint8_t idx = 0;
for (; possible_idx (idx); ++idx)
if (part_table[idx].magic != ESP_PARTITION_MAGIC)
break;
if (possible_idx (idx))
{
esp_partition_info_t *slot = &part_table[idx];
slot->magic = ESP_PARTITION_MAGIC;
slot->type = info->type;
slot->subtype = info->subtype;
slot->pos.offset = info->offs;
slot->pos.size = info->size;
memcpy (slot->label, info->label, sizeof (slot->label));
slot->flags = 0;
err = spi_flash_erase_sector (
ESP_PARTITION_TABLE_OFFSET / SPI_FLASH_SEC_SIZE);
if (err == ESP_OK)
err = spi_flash_write (
ESP_PARTITION_TABLE_OFFSET, (uint32_t *)part_table, SPI_FLASH_SEC_SIZE);
}
out:
free (part_table);
return err == ESP_OK;
}
#include <string.h>
#include "platform_rmt.h"
......
......@@ -3,7 +3,7 @@
#include "driver/gpio.h"
#include "driver/i2c.h"
#include "driver/spi_master.h"
#include "rom/ets_sys.h"
#include "esp_rom_sys.h"
#include "esp_heap_caps.h"
#include <string.h>
......@@ -38,27 +38,27 @@ uint8_t u8x8_gpio_and_delay_nodemcu(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int,
break;
case U8X8_MSG_DELAY_NANO: // delay arg_int * 1 nano second
ets_delay_us( 1 );
esp_rom_delay_us( 1 );
break;
case U8X8_MSG_DELAY_100NANO: // delay arg_int * 100 nano seconds
temp = arg_int * 100;
temp /= 1000;
ets_delay_us( temp > 0 ? temp : 1 );
esp_rom_delay_us( temp > 0 ? temp : 1 );
break;
case U8X8_MSG_DELAY_10MICRO: // delay arg_int * 10 micro seconds
ets_delay_us( arg_int * 10 );
esp_rom_delay_us( arg_int * 10 );
break;
case U8X8_MSG_DELAY_MILLI: // delay arg_int * 1 milli second
ets_delay_us( arg_int * 1000 );
esp_rom_delay_us( arg_int * 1000 );
break;
case U8X8_MSG_DELAY_I2C: // arg_int is the I2C speed in 100KHz, e.g. 4 = 400 KHz
temp = 5000 / arg_int; // arg_int=1: delay by 5us, arg_int = 4: delay by 1.25us
temp /= 1000;
ets_delay_us( temp > 0 ? temp : 1 );
esp_rom_delay_us( temp > 0 ? temp : 1 );
break;
case U8X8_MSG_GPIO_D0: // D0 or SPI clock pin: Output level in arg_int
......
......@@ -87,7 +87,7 @@ int16_t ucg_com_nodemcu_hw_spi(ucg_t *ucg, int16_t msg, uint16_t arg, uint8_t *d
break;
case UCG_COM_MSG_DELAY:
ets_delay_us(arg);
esp_rom_delay_us(arg);
break;
case UCG_COM_MSG_CHANGE_RESET_LINE:
......
......@@ -7,23 +7,20 @@
#include "platform.h"
#include "esp_task_wdt.h"
int platform_wdt_feed( void )
{
#ifdef CONFIG_TASK_WDT
static uint32_t task_wdt_timeout = CONFIG_TASK_WDT_TIMEOUT_S;
static bool task_wdt_panic =
esp_task_wdt_config_t cfg = {
.timeout_ms = CONFIG_TASK_WDT_TIMEOUT_S * 1000,
.idle_core_mask = (uint32_t)-1,
.trigger_panic =
#ifdef CONFIG_TASK_WDT_PANIC
true;
true,
#else
false;
#endif
false,
#endif
int platform_wdt_feed( void )
{
#ifdef CONFIG_TASK_WDT
return esp_task_wdt_init(task_wdt_timeout, task_wdt_panic) == ESP_OK ? PLATFORM_OK : PLATFORM_ERR;
};
return esp_task_wdt_init(&cfg) == ESP_OK ? PLATFORM_OK : PLATFORM_ERR;
#else
return PLATFORM_OK;
#endif
......
......@@ -30,6 +30,8 @@
#include "driver/gpio.h"
#include "esp_log.h"
#include "soc/periph_defs.h"
#include "rom/gpio.h" // for gpio_matrix_out()
#include "soc/gpio_periph.h"
#undef WS2812_DEBUG
......
......@@ -13,7 +13,7 @@ extern struct {
void rtos_dbg_task_print (const char *file, uint32_t line)
{
printf(">>dbg: %s:%d in RTOS task \"%s\": prio %d\n",
printf(">>dbg: %s:%lu in RTOS task \"%s\": prio %u\n",
file,
line,
pxCurrentTCB->pcTaskName,
......@@ -30,6 +30,6 @@ void rtos_dbg_stack_print (const char *file, uint32_t line)
for (;p < pxCurrentTCB->pxTopOfStack && *p == fill; ++p)
++nwords;
printf(">>dbg: %s:%d in RTOS task \"%s\": %u stack untouched\n",
printf(">>dbg: %s:%lu in RTOS task \"%s\": %lu stack untouched\n",
file, line, pxCurrentTCB->pcTaskName, nwords * 4);
}
......@@ -29,11 +29,11 @@ typedef struct
/*
* Private arrays to hold the 3 event task queues and the dispatch callbacks
*/
static xQueueHandle task_Q[TASK_PRIORITY_COUNT];
static QueueHandle_t task_Q[TASK_PRIORITY_COUNT];
/* Rather than using a QueueSet (which requires queues to be empty when created)
* we use a binary semaphore to unblock the pump whenever something is posted */
static xSemaphoreHandle pending;
static SemaphoreHandle_t pending;
static task_callback_t *task_func;
static int task_count;
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment