添加智能灯固件代码

This commit is contained in:
kerwincui
2021-07-13 17:14:51 +08:00
parent 332f74dd17
commit ecc0b91b8b
2568 changed files with 229441 additions and 0 deletions

View File

@@ -0,0 +1,111 @@
| Supported Targets | ESP32 |
| ----------------- | ----- |
### SDIO Example
## Introduction
These two projects illustrate the SDIO driver (host and slave). The host
example shows how to initialize a SDIO card, respond to a slave interrupt, as
well as reading and writing registers and buffers. The slave is a dedicated
peripheral, providing 8 interrupts, 52 8-bit R/W registers, an input FIFO and
an output FIFO. The example shows how to configure the driver and use these
feature.
The host first tell the slave to write the registers to a specified value,
then reads and prints the value from the slave. Then tell the slave to send 8
interrupts to the host. Then the host start sending data to the slave FIFO
and then reads from the slave FIFO in loops.
## Wiring
The SDIO protocol requires at least 4 lines (one more line than SD memory
protocol): CMD, CLK, DAT0 and DAT1. DAT1 is mandatory for the interrupt. DAT2
is required if 4-bit mode is used. DAT3 is required in 4-bit mode (connected
to host), or required by the slave as mode detect in 1-bit mode (pull up). It
is okay in 1-bit mode to leave DAT3 of host disconnected.
Please run wires between the slave and master to make the example function
(pins are the same for the host and the slave):
| Signal | GPIO NUM |
|--------|----------|
| CLK | GPIO-14 |
| CMD | GPIO-15 |
| DAT0 | GPIO-2 |
| DAT1 | GPIO-4 |
| DAT2 | GPIO-12 |
| DAT3 | GPIO-13 |
| Ground | GND |
CMD and DAT0-3 lines require to be pulled up by 50KOhm resistors even in
1-bit mode. See *Board Compability* below for details. In 1-bit mode, the
host can make use of DAT2 and DAT3, however the slave should leave them alone
but pulled up.
Be aware that the example uses lines normally reserved for JTAG. If you're
using a board with JTAG functions, please remember to remove jumpers
connecting to the JTAG adapter. The SD peripheral works at a high frequency
and uses native pins, there's no way to configure it to other pins through
the GPIO matrix.
Please make sure CMD and DATA lines are pulled up by 50KOhm resistors even in
1-bit mode or SPI mode, which is required by the SD specification.
The 4-bit mode can be configured in the menuconfig. If the 4-bit mode is not
used, the host will not control the DAT3 line, the slave hardware is
responsible to pull-up the line (or the slave may run into the SPI mode and
cause a crash).
The host uses HS mode by default. If the example does not work properly,
please try connecting two boards by short wires, grounding between two boards
better or disabling the HS mode in menuconfig.
## Board compatibility
1. If you're using a board (e.g. WroverKit v2 and before, PICO, DevKitC)
which is not able to drive GPIO2 low on downloading, please remember to
disconnect GPIO2 between two boards when downloading the application.
2. It is suggested to use the official Wrover Kit as the slave. This is
because Wrover Kits have pullups on CMD, DAT0 and DAT1. Otherwise you'll have
to connect the pullups manually (or use the Wrover Kit as the host). However,
due to a PCB issue, Wrover Kits v3 and earlier have pullup v.s. pulldown
conflicts on DAT3 line. You'll have to:
1. Pull up GPIO13 by resistor of 5KOhm or smaller (2KOhm suggested)
in 4-bit mode.
2. Pull up, or tie GPIO13 to VDD3.3 in 1-bit mode.
To help you faster evaluate the SDIO example on devkits without pullups,
you can uncomment the pullup enable flags in the initialization code of
the app_main of host or slave. This enables internal weak pullups on CMD,
DAT0 and DAT1 and DAT3 lines. However please don't rely on internal weak
pullups in your own design.
3. Moreover, if your slave devkit is using code flash of 3.3V, it is required
to pull down DAT2 line to set proper flash voltage. This conflicts with SDIO
pullup requirements. Currently devkits using PICO-D4 and Wroom-32 series
modules have this problem. You can either:
- Use Wrover Kit v3 which integrates a Wrover module
- Still use PICO-D4 or Wroom-32 Series modules as the slave, however:
- Don't connect the DAT2 pin and leave it floating. This means
you have to use 1-bit mode in the host. ``SDIO_DAT2_DISABLED``
option should be enabled in the menuconfig to avoid using of
DAT2. Or:
- Burn the EFUSE to force the module using 3.3V as the flash
voltage. In this way the voltage of flash doesn't depend on MTDI
any more, connect DAT2 to the host and make sure it is pulled up
correctly. See document below.
See docs in the programming guide ``api_reference/peripherals/sdio_slave``
and ``api_reference/peripherals/sd_pullup_requirements`` to see more
descriptions about pullups and MTDI requirements and solutions of official
modules and devkits.
## About `esp_serial_slave_link` component used in this example
`esp_serial_slave_link` component in the IDF is used to communicate to a ESP slave device.
When the `esp_serial_slave_link` device is initialized with an `essl_sdio_config_t` structure,
the `esp_serial_slave_link` can be used to communicate with an ESP32 SDIO slave.

View File

@@ -0,0 +1,6 @@
# The following lines of boilerplate have to be in your project's CMakeLists
# in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(sdio_host)

View File

@@ -0,0 +1,9 @@
#
# This is a project Makefile. It is assumed the directory this Makefile resides in is a
# project subdirectory.
#
PROJECT_NAME := sdio_host
include $(IDF_PATH)/make/project.mk

View File

@@ -0,0 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")

View File

@@ -0,0 +1,65 @@
menu "Example Configuration"
config EXAMPLE_SDIO_OVER_SPI
bool "Host use SPI bus to communicate with slave"
default n
help
If this is set, the host tries using SPI bus to communicate with slave.
Otherwise, the standarad SD bus is used.
config EXAMPLE_SDIO_4BIT
bool "Host tries using 4-bit mode to communicate with slave"
default n
depends on !EXAMPLE_SDIO_OVER_SPI
help
If this is set, the host tries using 4-bit mode to communicate with
slave. If failed, the communication falls back to 1-bit mode.
If this is not set, the host uses 1-bit mode. However, CMD1 is still
mandatory for interrupts.
Note that 4-bit mode is not compatible (by default) if the slave is
using 3.3V flash which requires a pull-down on the MTDI pin.
config EXAMPLE_SDIO_HIGHSPEED
bool "Host tries using HS mode to communicate with slave"
default y
help
If this is set, the host tries using high-speed mode to communicate
with slave. If the slave doesn't support high-speed mode, the
communication falls back to default-speed mode. If this is not set,
the host uses DS mode.
If the example does not work, please try disabling the HS mode.
config EXAMPLE_NO_INTR_LINE
bool "The host is not connected to the interrupt line (DAT1) of slave"
default n
help
If this is set, the host example will not check the interrupt line but poll slave
registers to see whether the slave has interrupts for the host.
Working without the interrupt line may increase the CPU load of the host, and do harm
to the response speed to slave events, though can save 1 GPIO for other purposes in
non-4-bit mode.
choice EXAMPLE_SLAVE
prompt "GPIO to control slave EN in Espressif master-slave board."
default EXAMPLE_SLAVE_NONE
help
If Espressif master-slave board is used, select the correct GPIO to control slave's EN.
config EXAMPLE_SLAVE_NONE
bool "Not using Espressif master-slave board."
config EXAMPLE_SLAVE_B1
bool "Using slave B1"
endchoice
config EXAMPLE_SLAVE_PWR_NEGTIVE_ACTIVE
bool "Slave power control pin is negtive active, otherwise postive active"
depends on !EXAMPLE_SLAVE_NONE
default n
help
Slave power control pin is negtive active, otherwise postive active
endmenu

View File

@@ -0,0 +1,483 @@
/* SDIO example, host (uses sdmmc_host/sdspi_host driver)
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "freertos/queue.h"
#include "soc/sdmmc_periph.h"
#include "soc/sdio_slave_periph.h"
#include "esp_log.h"
#include "esp_attr.h"
#include "esp_serial_slave_link/essl_sdio.h"
#include "sdkconfig.h"
#include "driver/sdmmc_host.h"
#include "driver/sdspi_host.h"
#define TIMEOUT_MAX UINT32_MAX
#define GPIO_B1 21
#if CONFIG_EXAMPLE_SLAVE_B1
#define SLAVE_PWR_GPIO GPIO_B1
#endif
/*
sdio host example.
This example is supposed to work together with the sdio slave example. It uses the pins as follows:
* Host Slave
* IO14 CLK
* IO15 CMD
* IO2 D0
* IO4 D1
* IO12 D2
* IO13 D3
This is the only pins that can be used in standard ESP modules. The other set of pins (6, 11, 7, 8, 9, 10)
are occupied by the spi bus communicating with the flash.
Protocol Above the ESP slave service:
- Interrupts:
0 is used to notify the slave to read the register 0.
- Registers:
- 0 is the register to hold tasks. Bits:
- 0: the slave should reset.
- 1: the slave should send interrupts.
- 2: the slave should write the shared registers acoording to the value in register 1.
- 1 is the register to hold test value.
- other registers will be written by the slave for testing.
- FIFO:
The receving FIFO is size of 256 bytes.
When the host writes something to slave recv FIFO, the slave should return it as is to the sending FIFO.
The example works as following process:
1. reset the slave.
2. tell the slave to write registers and read them back.
3. tell the slave to send interrupts to the host.
4. send data to slave FIFO and read them back.
5. loop step 4.
*/
#define WRITE_BUFFER_LEN 4096
#define READ_BUFFER_LEN 4096
#define SLAVE_BUFFER_SIZE 128
static const char TAG[] = "example_host";
#define SDIO_INTERRUPT_LINE GPIO_NUM_4 //DATA1
#define SLAVE_INTR_NOTIFY 0
#define SLAVE_REG_JOB 0
#define SLAVE_REG_VALUE 1
typedef enum {
JOB_IDLE = 0,
JOB_RESET = 1,
JOB_SEND_INT = 2,
JOB_WRITE_REG = 4,
} example_job_t;
//host use this to inform the slave it should reset its counters
esp_err_t slave_reset(essl_handle_t handle)
{
esp_err_t ret;
ESP_LOGI(TAG, "send reset to slave...");
ret = essl_write_reg(handle, 0, JOB_RESET, NULL, TIMEOUT_MAX);
if (ret != ESP_OK) {
return ret;
}
ret = essl_send_slave_intr(handle, BIT(SLAVE_INTR_NOTIFY), TIMEOUT_MAX);
if (ret != ESP_OK) {
return ret;
}
vTaskDelay(500 / portTICK_RATE_MS);
ret = essl_wait_for_ready(handle, TIMEOUT_MAX);
ESP_LOGI(TAG, "slave io ready");
return ret;
}
#ifdef CONFIG_EXAMPLE_SDIO_OVER_SPI
static void gpio_d2_set_high(void)
{
gpio_config_t d2_config = {
.pin_bit_mask = BIT64(SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_D2),
.mode = GPIO_MODE_OUTPUT,
.pull_up_en = true,
};
gpio_config(&d2_config);
gpio_set_level(SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_D2, 1);
}
#endif
static esp_err_t print_sdio_cis_information(sdmmc_card_t* card)
{
const size_t cis_buffer_size = 256;
uint8_t cis_buffer[cis_buffer_size];
size_t cis_data_len = 1024; //specify maximum searching range to avoid infinite loop
esp_err_t ret = ESP_OK;
ret = sdmmc_io_get_cis_data(card, cis_buffer, cis_buffer_size, &cis_data_len);
if (ret == ESP_ERR_INVALID_SIZE) {
int temp_buf_size = cis_data_len;
uint8_t* temp_buf = malloc(temp_buf_size);
assert(temp_buf);
ESP_LOGW(TAG, "CIS data longer than expected, temporary buffer allocated.");
ret = sdmmc_io_get_cis_data(card, temp_buf, temp_buf_size, &cis_data_len);
ESP_ERROR_CHECK(ret);
sdmmc_io_print_cis_info(temp_buf, cis_data_len, NULL);
free(temp_buf);
} else if (ret == ESP_OK) {
sdmmc_io_print_cis_info(cis_buffer, cis_data_len, NULL);
} else {
//including ESP_ERR_NOT_FOUND
ESP_LOGE(TAG, "failed to get the entire CIS data.");
abort();
}
return ESP_OK;
}
//host use this to initialize the slave card as well as SDIO registers
esp_err_t slave_init(essl_handle_t* handle)
{
esp_err_t err;
/* Probe */
#ifndef CONFIG_EXAMPLE_SDIO_OVER_SPI
sdmmc_host_t config = SDMMC_HOST_DEFAULT();
#ifdef CONFIG_EXAMPLE_SDIO_4BIT
ESP_LOGI(TAG, "Probe using SD 4-bit...\n");
config.flags = SDMMC_HOST_FLAG_4BIT;
#else
ESP_LOGI(TAG, "Probe using SD 1-bit...\n");
config.flags = SDMMC_HOST_FLAG_1BIT;
#endif
#ifdef CONFIG_EXAMPLE_SDIO_HIGHSPEED
config.max_freq_khz = SDMMC_FREQ_HIGHSPEED;
#else
config.max_freq_khz = SDMMC_FREQ_DEFAULT;
#endif
sdmmc_slot_config_t slot_config = SDMMC_SLOT_CONFIG_DEFAULT();
/* Note: For small devkits there may be no pullups on the board.
This enables the internal pullups to help evaluate the driver quickly.
However the internal pullups are not sufficient and not reliable,
please make sure external pullups are connected to the bus in your
real design.
*/
//slot_config.flags = SDMMC_SLOT_FLAG_INTERNAL_PULLUP;
err = sdmmc_host_init();
ESP_ERROR_CHECK(err);
err = sdmmc_host_init_slot(SDMMC_HOST_SLOT_1, &slot_config);
ESP_ERROR_CHECK(err);
#else //over SPI
sdspi_device_config_t dev_config = SDSPI_DEVICE_CONFIG_DEFAULT();
dev_config.gpio_cs = SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_D3;
dev_config.gpio_int = SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_D1;
err = gpio_install_isr_service(0);
ESP_ERROR_CHECK(err);
spi_bus_config_t bus_config = {
.mosi_io_num = SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_CMD,
.miso_io_num = SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_D0,
.sclk_io_num = SDIO_SLAVE_SLOT1_IOMUX_PIN_NUM_CLK,
.quadwp_io_num = -1,
.quadhd_io_num = -1,
.max_transfer_sz = 4000,
};
err = spi_bus_initialize(dev_config.host_id, &bus_config, 1);
ESP_ERROR_CHECK(err);
sdspi_device_handle_t sdspi_handle;
err = sdspi_host_init();
ESP_ERROR_CHECK(err);
err = sdspi_host_init_device(&slot_config, &sdspi_handle);
ESP_ERROR_CHECK(err);
ESP_LOGI(TAG, "Probe using SPI...\n");
sdmmc_host_t config = SDSPI_HOST_DEFAULT();
config.slot = sdspi_handle;
//we have to pull up all the slave pins even when the pin is not used
gpio_d2_set_high();
#endif //over SPI
sdmmc_card_t *card = (sdmmc_card_t *)malloc(sizeof(sdmmc_card_t));
if (card == NULL) {
return ESP_ERR_NO_MEM;
}
for (;;) {
if (sdmmc_card_init(&config, card) == ESP_OK) {
break;
}
ESP_LOGW(TAG, "slave init failed, retry...");
vTaskDelay(1000 / portTICK_PERIOD_MS);
}
sdmmc_card_print_info(stdout, card);
gpio_pullup_en(14);
gpio_pulldown_dis(14);
gpio_pullup_en(15);
gpio_pulldown_dis(15);
gpio_pullup_en(2);
gpio_pulldown_dis(2);
gpio_pullup_en(4);
gpio_pulldown_dis(4);
gpio_pullup_en(12);
gpio_pulldown_dis(12);
gpio_pullup_en(13);
gpio_pulldown_dis(13);
essl_sdio_config_t ser_config = {
.card = card,
.recv_buffer_size = SLAVE_BUFFER_SIZE,
};
err = essl_sdio_init_dev(handle, &ser_config);
ESP_ERROR_CHECK(err);
esp_err_t ret = essl_init(*handle, TIMEOUT_MAX);
ESP_ERROR_CHECK(ret);
ret = print_sdio_cis_information(card);
ESP_ERROR_CHECK(ret);
return ret;
}
void slave_power_on(void)
{
#ifdef SLAVE_PWR_GPIO
int level_active;
#ifdef CONFIG_EXAMPLE_SLAVE_PWR_NEGTIVE_ACTIVE
level_active = 0;
#else
level_active = 1;
#endif
gpio_config_t cfg = {
.pin_bit_mask = BIT64(GPIO_B1),
.mode = GPIO_MODE_DEF_OUTPUT,
.pull_up_en = false,
.pull_down_en = false,
.intr_type = GPIO_INTR_DISABLE,
};
gpio_config(&cfg);
gpio_set_level(GPIO_B1, !level_active);
vTaskDelay(100);
gpio_set_level(SLAVE_PWR_GPIO, level_active);
vTaskDelay(100);
#endif
}
DMA_ATTR uint8_t rcv_buffer[READ_BUFFER_LEN];
static esp_err_t get_intr(essl_handle_t handle, uint32_t* out_raw, uint32_t* out_st)
{
esp_err_t ret = ESP_OK;
#ifndef CONFIG_EXAMPLE_NO_INTR_LINE
ret = essl_wait_int(handle, 0);
if (ret != ESP_OK) {
return ret;
}
#endif
ret = essl_get_intr(handle, out_raw, out_st, TIMEOUT_MAX);
if (ret != ESP_OK) return ret;
ret = essl_clear_intr(handle, *out_raw, TIMEOUT_MAX);
if (ret != ESP_OK) return ret;
ESP_LOGD(TAG, "intr: %08X", *out_raw);
return ESP_OK;
}
//try to get an interrupt from the slave and handle it, return if none.
esp_err_t process_event(essl_handle_t handle)
{
uint32_t intr_raw, intr_st;
esp_err_t ret = get_intr(handle, &intr_raw, &intr_st);
if (ret == ESP_ERR_TIMEOUT) {
return ret;
}
ESP_ERROR_CHECK(ret);
for (int i = 0; i < 8; i++) {
if (intr_raw & BIT(i)) {
ESP_LOGI(TAG, "host int: %d", i);
}
}
const int wait_ms = 50;
if (intr_raw & HOST_SLC0_RX_NEW_PACKET_INT_ST) {
ESP_LOGD(TAG, "new packet coming");
while (1) {
size_t size_read = READ_BUFFER_LEN;
ret = essl_get_packet(handle, rcv_buffer, READ_BUFFER_LEN, &size_read, wait_ms);
if (ret == ESP_ERR_NOT_FOUND) {
ESP_LOGE(TAG, "interrupt but no data can be read");
break;
} else if (ret != ESP_OK && ret != ESP_ERR_NOT_FINISHED) {
ESP_LOGE(TAG, "rx packet error: %08X", ret);
return ret;
}
ESP_LOGI(TAG, "receive data, size: %d", size_read);
ESP_LOG_BUFFER_HEXDUMP(TAG, rcv_buffer, size_read, ESP_LOG_INFO);
if (ret == ESP_OK) {
break;
}
}
}
return ESP_OK;
}
//tell the slave to do a job
static inline esp_err_t slave_inform_job(essl_handle_t handle, example_job_t job)
{
esp_err_t ret;
ret = essl_write_reg(handle, SLAVE_REG_JOB, job, NULL, TIMEOUT_MAX);
ESP_ERROR_CHECK(ret);
ret = essl_send_slave_intr(handle, BIT(SLAVE_INTR_NOTIFY), TIMEOUT_MAX);
ESP_ERROR_CHECK(ret);
return ret;
}
//tell the slave to write registers by write one of them, and read them back
void job_write_reg(essl_handle_t handle, int value)
{
esp_err_t ret;
uint8_t reg_read[60];
ESP_LOGI(TAG, "========JOB: write slave reg========");
ret = essl_write_reg(handle, SLAVE_REG_VALUE, value, NULL, TIMEOUT_MAX);
ESP_ERROR_CHECK(ret);
ret = slave_inform_job(handle, JOB_WRITE_REG);
ESP_ERROR_CHECK(ret);
vTaskDelay(10);
for (int i = 0; i < 60; i++) {
ESP_LOGD(TAG, "reading register %d", i);
ret = essl_read_reg(handle, i, &reg_read[i], TIMEOUT_MAX);
ESP_ERROR_CHECK(ret);
}
ESP_LOGI(TAG, "read registers:");
ESP_LOG_BUFFER_HEXDUMP(TAG, reg_read, 64, ESP_LOG_INFO);
}
//the slave only load 16 buffers a time
//so first 5 packets (use 1+1+8+4+1=15 buffers) are sent, the others (513, 517) failed (timeout)
int packet_len[] = {6, 12, 1024, 512, 3, 513, 517};
//the sending buffer should be word aligned
DMA_ATTR uint8_t send_buffer[READ_BUFFER_LEN];
//send packets to the slave (they will return and be handled by the interrupt handler)
void job_fifo(essl_handle_t handle)
{
for (int i = 0; i < READ_BUFFER_LEN; i++) {
send_buffer[i] = 0x46 + i * 5;
}
esp_err_t ret;
int pointer = 0;
ESP_LOGI(TAG, "========JOB: send fifos========");
/* CAUTION: This example shows that we can send random length of packet to the slave.
* However it takes time of two transactions if the length is not multiples of 4 bytes.
* e.g. sending 6 bytes is done by sending 4 + 2 bytes each transaction.
* Try to avoid unaligned packets if possible to get higher effeciency.
*/
for (int i = 0; i < sizeof(packet_len) / sizeof(int); i++) {
const int wait_ms = 50;
int length = packet_len[i];
ret = essl_send_packet(handle, send_buffer + pointer, length, wait_ms);
if (ret == ESP_ERR_TIMEOUT) {
ESP_LOGD(TAG, "several packets are expected to timeout.");
} else {
ESP_ERROR_CHECK(ret);
ESP_LOGI(TAG, "send packet length: %d", length);
}
pointer += (length + 3) & (~3); //the length can be random, but data should start at the 32-bit boundary.
}
}
//inform the slave to send interrupts to host (the interrupts will be handled in the interrupt handler)
void job_getint(essl_handle_t handle)
{
ESP_LOGI(TAG, "========JOB: get interrupts from slave========");
slave_inform_job(handle, JOB_SEND_INT);
}
void app_main(void)
{
essl_handle_t handle;
esp_err_t err;
//enable the power if on espressif SDIO master-slave board
slave_power_on();
ESP_LOGI(TAG, "host ready, start initializing slave...");
err = slave_init(&handle);
ESP_ERROR_CHECK(err);
err = slave_reset(handle);
ESP_ERROR_CHECK(err);
uint32_t start, end;
job_write_reg(handle, 10);
int times = 2;
while (1) {
job_getint(handle);
start = xTaskGetTickCount();
while (1) {
process_event(handle);
vTaskDelay(1);
end = xTaskGetTickCount();
if ((end - start) * 1000 / CONFIG_FREERTOS_HZ > 5000) {
break;
}
}
if (--times == 0) {
break;
}
};
while (1) {
job_fifo(handle);
start = xTaskGetTickCount();
while (1) {
process_event(handle);
vTaskDelay(1);
end = xTaskGetTickCount();
if ((end - start) * 1000 / CONFIG_FREERTOS_HZ > 2000) {
break;
}
}
}
}

View File

@@ -0,0 +1,8 @@
#
# Main component makefile.
#
# This Makefile can be left empty. By default, it will take the sources in the
# src/ directory, compile them and link them into lib(subdirectory_name).a
# in the build directory. This behaviour is entirely configurable,
# please read the ESP-IDF documents if you need to do this.
#

View File

@@ -0,0 +1 @@
CONFIG_EXAMPLE_SLAVE_B1=y

View File

@@ -0,0 +1,123 @@
# Copyright 2015-2017 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.
from tiny_test_fw import TinyFW
import ttfw_idf
@ttfw_idf.idf_example_test(env_tag="Example_SDIO", ignore=True)
def test_example_sdio_communication(env, extra_data):
"""
Configurations
dut1 = host -> dut2 = slave
should be in the same group of devices, otherwise may meet download issue
group1: (Wroom-32 Series or PICO-D4 modules: PICO-Kit, DevKitC, WroverKit v2 or earlier)
group2: (Wrover module: WroverKit v3)
GPIO14->GPIO14
GPIO15->GPIO15
GPIO2->GPIO2
GPIO4->GPIO4
GND->GND
VDD3.3 -> GPIO13 if dut2 uses WroverKit v3
or use sdio test board, which has two wrover modules connect to a same FT3232
Assume that first dut is host and second is slave
"""
dut1 = env.get_dut("sdio_host", "examples/peripherals/sdio/host", dut_class=ttfw_idf.ESP32DUT)
dut2 = env.get_dut("sdio_slave", "examples/peripherals/sdio/slave", dut_class=ttfw_idf.ESP32DUT)
dut1.start_app()
# wait until the master is ready to setup the slave
dut1.expect("host ready, start initializing slave...")
dut2.start_app()
dut1.expect("0a 0d 10 13 16 19 1c 1f 22 25 28 2b 2e 31 34 37")
dut1.expect("3a 3d 40 43 46 49 4c 4f 52 55 58 5b 00 00 00 00")
dut1.expect("6a 6d 70 73 76 79 7c 7f 82 85 88 8b 8e 91 94 97")
dut1.expect("9a 9d a0 a3 a6 a9 ac af b2 b5 b8 bb be c1 c4 c7")
dut2.expect("================ JOB_WRITE_REG ================")
dut2.expect("0a 0d 10 13 16 19 1c 1f 22 25 28 2b 2e 31 34 37")
dut2.expect("3a 3d 40 43 46 49 4c 4f 52 55 58 5b 00 00 00 00")
dut2.expect("6a 6d 70 73 76 79 7c 7f 82 85 88 8b 8e 91 94 97")
dut2.expect("9a 9d a0 a3 a6 a9 ac af b2 b5 b8 bb be c1 c4 c7")
dut1.expect("host int: 0")
dut1.expect("host int: 1")
dut1.expect("host int: 2")
dut1.expect("host int: 3")
dut1.expect("host int: 4")
dut1.expect("host int: 5")
dut1.expect("host int: 6")
dut1.expect("host int: 7")
dut1.expect("host int: 0")
dut1.expect("host int: 1")
dut1.expect("host int: 2")
dut1.expect("host int: 3")
dut1.expect("host int: 4")
dut1.expect("host int: 5")
dut1.expect("host int: 6")
dut1.expect("host int: 7")
dut2.expect("================ JOB_SEND_INT ================")
dut2.expect("================ JOB_SEND_INT ================")
dut1.expect("send packet length: 3")
dut1.expect("send packet length: 6")
dut1.expect("send packet length: 12")
dut1.expect("send packet length: 128")
dut1.expect("send packet length: 511")
dut1.expect("send packet length: 512")
dut2.expect("recv len: 3")
dut2.expect("recv len: 6")
dut2.expect("recv len: 12")
dut2.expect("recv len: 128")
# 511
dut2.expect("recv len: 128")
dut2.expect("recv len: 128")
dut2.expect("recv len: 128")
dut2.expect("recv len: 127")
# 512
dut2.expect("recv len: 128")
dut2.expect("recv len: 128")
dut2.expect("recv len: 128")
dut2.expect("recv len: 128")
dut1.expect("receive data, size: 3")
dut1.expect("receive data, size: 6")
dut1.expect("receive data, size: 12")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 127")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
dut1.expect("receive data, size: 128")
# the last valid line of one round
dut1.expect("ce d3 d8 dd e2 e7 ec f1 f6 fb 00 05 0a 0f 14 19")
# the first 2 lines of the second round
dut1.expect("46 4b 50")
dut1.expect("5a 5f 64 69 6e 73")
if __name__ == '__main__':
TinyFW.set_default_config(env_config_file="EnvConfigTemplate.yml", dut=ttfw_idf.IDFDUT)
test_example_sdio_communication()

View File

@@ -0,0 +1,6 @@
# The following lines of boilerplate have to be in your project's CMakeLists
# in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(sdio_slave)

View File

@@ -0,0 +1,9 @@
#
# This is a project Makefile. It is assumed the directory this Makefile resides in is a
# project subdirectory.
#
PROJECT_NAME := sdio_slave
include $(IDF_PATH)/make/project.mk

View File

@@ -0,0 +1,2 @@
idf_component_register(SRCS "app_main.c"
INCLUDE_DIRS ".")

View File

@@ -0,0 +1,16 @@
menu "Example Configuration"
config SDIO_DAT2_DISABLED
bool "Disable the DAT2 in SDIO slave"
default n
help
SDIO slave DAT pin is unfortunately the same pin as MTDI, which
controls the flash power voltage. For 3.3v flash devkits / modules /
kits, it conflicts with the DAT2 pullups required by the
specification.
This disables the peripheral input from the DAT2 so that we can work
in 1-bit mode when DAT2 is floating (pulled down). 4-bit mode is
therefore unavailable.
endmenu

View File

@@ -0,0 +1,275 @@
/* SDIO example, slave (uses sdio slave driver)
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include "driver/sdio_slave.h"
#include "esp_log.h"
#include "sys/queue.h"
#include "soc/soc.h"
#include "freertos/task.h"
#include "freertos/ringbuf.h"
#include "sdkconfig.h"
/*
sdio slave example.
This example is supposed to work together with the sdio host example. It uses the pins as follows:
* Host Slave
* IO14 CLK
* IO15 CMD
* IO2 D0
* IO4 D1
* IO12 D2
* IO13 D3
This is the only pins that can be used in standard ESP modules. The other set of pins (6, 11, 7, 8, 9, 10)
are occupied by the spi bus communicating with the flash.
Protocol Above the ESP slave service:
- Interrupts:
0 is used to notify the slave to read the register 0.
- Registers:
- 0 is the register to hold tasks. Bits:
- 0: the slave should reset.
- 1: the slave should send interrupts.
- 2: the slave should write the shared registers acoording to the value in register 1.
- 1 is the register to hold test value.
- other registers will be written by the slave for testing.
- FIFO:
The receving FIFO is size of 256 bytes.
When the host writes something to slave recv FIFO, the slave should return it as is to the sending FIFO.
The host works as following process:
1. reset the slave.
2. tell the slave to write registers and read them back.
3. tell the slave to send interrupts to the host.
4. send data to slave FIFO and read them back.
5. loop step 4.
*/
#define SDIO_SLAVE_QUEUE_SIZE 11
#define BUFFER_SIZE 128
#define BUFFER_NUM 16
#define EV_STR(s) "================ "s" ================"
typedef enum {
JOB_IDLE = 0,
JOB_RESET = 1,
JOB_SEND_INT = 2,
JOB_WRITE_REG = 4,
} example_job_t;
static const char TAG[] = "example_slave";
static int s_job = JOB_IDLE;
DMA_ATTR uint8_t data_to_send[BUFFER_SIZE] = {0x97, 0x84, 0x43, 0x67, 0xc1, 0xdd, 0xff, 0x01, 0x02, 0x03, 0x04, 0x05, 0xff, 0xee, 0xdd, 0xcc, 0xbb, 0xaa, 0x99, 0x88, 0x77, 0x56, 0x55, 0x44, 0x33 ,0x22, 0x11, 0x00 };
DMA_ATTR uint8_t data_to_recv[BUFFER_SIZE] = {0x97, 0x84, 0x43, 0x67, 0xc1, 0xdd, 0xff, 0x01, 0x02, 0x03, 0x04, 0x05, 0xff, 0xee, 0xdd, 0xcc, 0xbb, 0xaa, 0x99, 0x88, 0x77, 0x56, 0x55, 0x44, 0x33 ,0x22, 0x11, 0x00 };
static const char job_desc[][32] = {
"JOB_IDLE",
"JOB_RESET",
"JOB_SEND_INT",
"JOB_WRITE_REG",
};
//reset counters of the slave hardware, and clean the receive buffer (normally they should be sent back to the host)
static esp_err_t slave_reset(void)
{
esp_err_t ret;
sdio_slave_stop();
ret = sdio_slave_reset();
if (ret != ESP_OK) return ret;
ret = sdio_slave_start();
if (ret != ESP_OK) return ret;
//Since the buffer will not be sent any more, we return them back to receving driver
while(1) {
sdio_slave_buf_handle_t handle;
ret = sdio_slave_send_get_finished(&handle, 0);
if (ret != ESP_OK) break;
ret = sdio_slave_recv_load_buf(handle);
ESP_ERROR_CHECK(ret);
}
return ESP_OK;
}
//sent interrupts to the host in turns
static esp_err_t task_hostint(void)
{
for(int i = 0; i < 8; i++) {
ESP_LOGV(TAG, "send intr: %d", i);
sdio_slave_send_host_int(i);
//check reset for quick response to RESET signal
if (s_job & JOB_RESET) break;
vTaskDelay(500/portTICK_RATE_MS);
}
return ESP_OK;
}
//read the value in a specified register set by the host, and set other register according to this.
//the host will read these registers later
static esp_err_t task_write_reg(void)
{
//the host write REG1, the slave should write its registers according to value of REG1
uint8_t read = sdio_slave_read_reg(1);
for (int i = 0; i < 64; i++) {
//skip interrupt regs.
if (i >= 28 && i <= 31) continue;
sdio_slave_write_reg(i, read+3*i);
}
uint8_t reg[64] = {0};
for (int i = 0; i < 64; i++) {
//skip interrupt regs.
if (i >= 28 && i <= 31) continue;
reg[i] = sdio_slave_read_reg(i);
}
ESP_LOGI(TAG, "write regs:");
ESP_LOG_BUFFER_HEXDUMP(TAG, reg, 64, ESP_LOG_INFO);
return ESP_OK;
}
//we use the event callback (in ISR) in this example to get higer responding speed
//note you can't do delay in the ISR
//``sdio_slave_wait_int`` is another way to handle interrupts
static void event_cb(uint8_t pos)
{
ESP_EARLY_LOGD(TAG, "event: %d", pos);
switch(pos) {
case 0:
s_job = sdio_slave_read_reg(0);
sdio_slave_write_reg(0, JOB_IDLE);
break;
}
}
DMA_ATTR uint8_t buffer[BUFFER_NUM][BUFFER_SIZE] = {};
//Main application
void app_main(void)
{
esp_err_t ret;
sdio_slave_config_t config = {
.sending_mode = SDIO_SLAVE_SEND_PACKET,
.send_queue_size = SDIO_SLAVE_QUEUE_SIZE,
.recv_buffer_size = BUFFER_SIZE,
.event_cb = event_cb,
/* Note: For small devkits there may be no pullups on the board.
This enables the internal pullups to help evaluate the driver
quickly. However the internal pullups are not sufficient and not
reliable, please make sure external pullups are connected to the
bus in your real design.
*/
//.flags = SDIO_SLAVE_FLAG_INTERNAL_PULLUP,
};
#ifdef CONFIG_SDIO_DAT2_DISABLED
/* For slave chips with 3.3V flash, DAT2 pullup conflicts with the pulldown
required by strapping pin (MTDI). We can either burn the EFUSE for the
strapping or just disable the DAT2 and work in 1-bit mode.
*/
config.flags |= SDIO_SLAVE_FLAG_DAT2_DISABLED;
#endif
ret = sdio_slave_initialize(&config);
ESP_ERROR_CHECK(ret);
sdio_slave_write_reg(0, JOB_IDLE);
sdio_slave_buf_handle_t handle;
for(int i = 0; i < BUFFER_NUM; i++) {
handle = sdio_slave_recv_register_buf(buffer[i]);
assert(handle != NULL);
ret = sdio_slave_recv_load_buf(handle);
ESP_ERROR_CHECK(ret);
}
sdio_slave_set_host_intena(SDIO_SLAVE_HOSTINT_SEND_NEW_PACKET |
SDIO_SLAVE_HOSTINT_BIT0 |
SDIO_SLAVE_HOSTINT_BIT1 |
SDIO_SLAVE_HOSTINT_BIT2 |
SDIO_SLAVE_HOSTINT_BIT3 |
SDIO_SLAVE_HOSTINT_BIT4 |
SDIO_SLAVE_HOSTINT_BIT5 |
SDIO_SLAVE_HOSTINT_BIT6 |
SDIO_SLAVE_HOSTINT_BIT7
);
sdio_slave_start();
ESP_LOGI(TAG, EV_STR("slave ready"));
for(;;) {
//receive data and send back to host.
size_t length;
uint8_t *ptr;
const TickType_t non_blocking = 0;
ret = sdio_slave_recv(&handle, &ptr, &length, non_blocking);
if (ret == ESP_OK) {
ESP_LOGI(TAG, "handle: %p, recv len: %d, data:", handle, length);
ESP_LOG_BUFFER_HEXDUMP(TAG, ptr, length, ESP_LOG_INFO);
/* If buffer is no longer used, call sdio_slave_recv_load_buf to return it here. Since we wants to show how
* to share large buffers between drivers here (we share between sending and receiving), keep the buffer
* until the buffer is sent by sending driver.
*/
//send the received buffer to host, with the handle as the argument
ret = sdio_slave_send_queue(ptr, length, handle, non_blocking);
if (ret == ESP_ERR_TIMEOUT) {
// send failed, direct return the buffer to rx
ESP_LOGE(TAG, "send_queue full, discard received.");
ret = sdio_slave_recv_load_buf(handle);
}
ESP_ERROR_CHECK(ret);
}
// if there's finished sending desc, return the buffer to receiving driver
for(;;){
sdio_slave_buf_handle_t handle;
ret = sdio_slave_send_get_finished(&handle, 0);
if (ret == ESP_ERR_TIMEOUT) break;
ESP_ERROR_CHECK(ret);
ret = sdio_slave_recv_load_buf(handle);
ESP_ERROR_CHECK(ret);
}
if (s_job != 0) {
for(int i = 0; i < 8; i++) {
if (s_job & BIT(i)) {
ESP_LOGI(TAG, EV_STR("%s"), job_desc[i+1]);
s_job &= ~BIT(i);
switch(BIT(i)) {
case JOB_SEND_INT:
ret = task_hostint();
ESP_ERROR_CHECK(ret);
break;
case JOB_RESET:
ret = slave_reset();
ESP_ERROR_CHECK(ret);
break;
case JOB_WRITE_REG:
ret = task_write_reg();
ESP_ERROR_CHECK(ret);
break;
}
}
}
}
vTaskDelay(1);
}
}

View File

@@ -0,0 +1,8 @@
#
# Main component makefile.
#
# This Makefile can be left empty. By default, it will take the sources in the
# src/ directory, compile them and link them into lib(subdirectory_name).a
# in the build directory. This behaviour is entirely configurable,
# please read the ESP-IDF documents if you need to do this.
#