提交 8b96b1a5 编写于 作者: M me-no-dev

update IDF libs and esptool.py

adds autoreset after firmware upload
上级 d84d9129
......@@ -347,7 +347,7 @@ i2c_err_t i2cSetFrequency(i2c_t * i2c, uint32_t clk_speed)
I2C_MUTEX_LOCK();
//the clock num during SCL is low level
i2c->dev->scl_low_period.scl_low_period = period;
i2c->dev->scl_low_period.period = period;
//the clock num during SCL is high level
i2c->dev->scl_high_period.period = period;
......@@ -375,7 +375,7 @@ uint32_t i2cGetFrequency(i2c_t * i2c)
return 0;
}
return APB_CLK_FREQ/(i2c->dev->scl_low_period.scl_low_period+i2c->dev->scl_high_period.period);
return APB_CLK_FREQ/(i2c->dev->scl_low_period.period+i2c->dev->scl_high_period.period);
}
/*
......
此差异已折叠。
......@@ -24,12 +24,14 @@
#define CONFIG_EMAC_TASK_PRIORITY 20
#define CONFIG_ULP_COPROC_RESERVE_MEM 512
#define CONFIG_ESPTOOLPY_BAUD 921600
#define CONFIG_ESPTOOLPY_AFTER_RESET 1
#define CONFIG_TOOLPREFIX "xtensa-esp32-elf-"
#define CONFIG_CONSOLE_UART_NUM 0
#define CONFIG_ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC 1
#define CONFIG_LWIP_THREAD_LOCAL_STORAGE_INDEX 0
#define CONFIG_CONSOLE_UART_DEFAULT 1
#define CONFIG_MBEDTLS_SSL_MAX_CONTENT_LEN 16384
#define CONFIG_ESPTOOLPY_FLASHSIZE_DETECT 1
#define CONFIG_AUTOSTART_ARDUINO 1
#define CONFIG_ESP32_ENABLE_STACK_WIFI 1
#define CONFIG_LOG_DEFAULT_LEVEL_ERROR 1
......@@ -37,6 +39,7 @@
#define CONFIG_MAIN_TASK_STACK_SIZE 4096
#define CONFIG_ESPTOOLPY_FLASHMODE "dio"
#define CONFIG_BTC_TASK_STACK_SIZE 2048
#define CONFIG_ESPTOOLPY_BEFORE "default_reset"
#define CONFIG_LOG_DEFAULT_LEVEL 1
#define CONFIG_ULP_COPROC_ENABLED 1
#define CONFIG_DMA_RX_BUF_NUM 10
......@@ -59,8 +62,11 @@
#define CONFIG_FREERTOS_ASSERT_FAIL_ABORT 1
#define CONFIG_MONITOR_BAUD_115200B 1
#define CONFIG_LOG_BOOTLOADER_LEVEL 1
#define CONFIG_ESPTOOLPY_BEFORE_RESET 1
#define CONFIG_ESPTOOLPY_BAUD_OTHER_VAL 115200
#define CONFIG_ENABLE_ARDUINO_DEPENDS 1
#define CONFIG_ESP32_DEFAULT_CPU_FREQ_240 1
#define CONFIG_ESPTOOLPY_AFTER "hard_reset"
#define CONFIG_LWIP_SO_REUSE 1
#define CONFIG_DMA_TX_BUF_NUM 10
#define CONFIG_BT_ENABLED 1
......@@ -74,6 +80,7 @@
#define CONFIG_ESPTOOLPY_BAUD_921600B 1
#define CONFIG_APP_OFFSET 0x10000
#define CONFIG_MEMMAP_SMP 1
#define CONFIG_LWIP_SO_RCVBUF 1
#define CONFIG_MBEDTLS_HARDWARE_MPI 1
#define CONFIG_MONITOR_BAUD_OTHER_VAL 115200
#define CONFIG_ESPTOOLPY_PORT "/dev/tty.SLAB_USBtoUART"
......
// Copyright 2015-2016 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.
#ifndef _DRIVER_I2C_H_
#define _DRIVER_I2C_H_
#ifdef __cplusplus
extern "C" {
#endif
#include <esp_types.h>
#include "esp_err.h"
#include "esp_intr_alloc.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/xtensa_api.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/ringbuf.h"
#include "driver/gpio.h"
#define I2C_APB_CLK_FREQ APB_CLK_FREQ /*!< I2C source clock is APB clock, 80MHz */
#define I2C_FIFO_LEN (32) /*!< I2C hardware fifo length */
typedef enum{
I2C_MODE_SLAVE = 0, /*!< I2C slave mode */
I2C_MODE_MASTER, /*!< I2C master mode */
I2C_MODE_MAX,
}i2c_mode_t;
typedef enum {
I2C_MASTER_WRITE = 0, /*!< I2C write data */
I2C_MASTER_READ, /*!< I2C read data */
} i2c_rw_t;
typedef enum {
I2C_DATA_MODE_MSB_FIRST = 0, /*!< I2C data msb first */
I2C_DATA_MODE_LSB_FIRST = 1, /*!< I2C data lsb first */
I2C_DATA_MODE_MAX
} i2c_trans_mode_t;
typedef enum{
I2C_CMD_RESTART = 0, /*!<I2C restart command */
I2C_CMD_WRITE, /*!<I2C write command */
I2C_CMD_READ, /*!<I2C read command */
I2C_CMD_STOP, /*!<I2C stop command */
I2C_CMD_END /*!<I2C end command */
}i2c_opmode_t;
typedef enum{
I2C_NUM_0 = 0, /*!< I2C port 0 */
I2C_NUM_1 , /*!< I2C port 1 */
I2C_NUM_MAX
} i2c_port_t;
typedef enum {
I2C_ADDR_BIT_7 = 0, /*!< I2C 7bit address for slave mode */
I2C_ADDR_BIT_10, /*!< I2C 10bit address for slave mode */
I2C_ADDR_BIT_MAX,
} i2c_addr_mode_t;
/**
* @brief I2C initialization parameters
*/
typedef struct{
i2c_mode_t mode; /*!< I2C mode */
gpio_num_t sda_io_num; /*!< GPIO number for I2C sda signal */
gpio_pullup_t sda_pullup_en; /*!< Internal GPIO pull mode for I2C sda signal*/
gpio_num_t scl_io_num; /*!< GPIO number for I2C scl signal */
gpio_pullup_t scl_pullup_en; /*!< Internal GPIO pull mode for I2C scl signal*/
union {
struct {
uint32_t clk_speed; /*!< I2C clock frequency for master mode, (no higher than 1MHz for now) */
} master;
struct {
uint8_t addr_10bit_en; /*!< I2C 10bit address mode enable for slave mode */
uint16_t slave_addr; /*!< I2C address for slave mode */
} slave;
};
}i2c_config_t;
typedef void* i2c_cmd_handle_t; /*!< I2C command handle */
/**
* @brief I2C driver install
*
* @param i2c_num I2C port number
* @param mode I2C mode( master or slave )
* @param slv_rx_buf_len receiving buffer size for slave mode
* @note
* Only slave mode will use this value, driver will ignore this value in master mode.
* @param slv_tx_buf_len sending buffer size for slave mode
* @note
* Only slave mode will use this value, driver will ignore this value in master mode.
* @param intr_alloc_flags Flags used to allocate the interrupt. One or multiple (ORred)
* ESP_INTR_FLAG_* values. See esp_intr_alloc.h for more info.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_FAIL Driver install error
*/
esp_err_t i2c_driver_install(i2c_port_t i2c_num, i2c_mode_t mode, size_t slv_rx_buf_len, size_t slv_tx_buf_len, int intr_alloc_flags);
/**
* @brief I2C driver delete
*
* @param i2c_num I2C port number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_driver_delete(i2c_port_t i2c_num);
/**
* @brief I2C parameter initialization
*
* @param i2c_num I2C port number
* @param i2c_conf pointer to I2C parameter settings
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_param_config(i2c_port_t i2c_num, i2c_config_t* i2c_conf);
/**
* @brief reset I2C tx hardware fifo
*
* @param i2c_num I2C port number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_reset_tx_fifo(i2c_port_t i2c_num);
/**
* @brief reset I2C rx fifo
*
* @param i2c_num I2C port number
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_reset_rx_fifo(i2c_port_t i2c_num);
/**
* @brief I2C isr handler register
*
* @param i2c_num I2C port number
* @param fn isr handler function
* @param arg parameter for isr handler function
* @param intr_alloc_flags Flags used to allocate the interrupt. One or multiple (ORred)
* ESP_INTR_FLAG_* values. See esp_intr_alloc.h for more info.
* @param handle handle return from esp_intr_alloc.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_isr_register(i2c_port_t i2c_num, void (*fn)(void*), void * arg, int intr_alloc_flags, intr_handle_t *handle);
/**
* @brief to delete and free I2C isr.
*
* @param handle handle of isr.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_isr_free(intr_handle_t handle);
/**
* @brief Configure GPIO signal for I2C sck and sda
*
* @param i2c_num I2C port number
* @param sda_io_num GPIO number for I2C sda signal
* @param scl_io_num GPIO number for I2C scl signal
* @param sda_pullup_en Whether to enable the internal pullup for sda pin
* @param scl_pullup_en Whether to enable the internal pullup for scl pin
* @param mode I2C mode
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_pin(i2c_port_t i2c_num, gpio_num_t sda_io_num, gpio_num_t scl_io_num,
gpio_pullup_t sda_pullup_en, gpio_pullup_t scl_pullup_en, i2c_mode_t mode);
/**
* @brief Create and init I2C command link
* @note
* Before we build I2C command link, we need to call i2c_cmd_link_create() to create
* a command link.
* After we finish sending the commands, we need to call i2c_cmd_link_delete() to
* release and return the resources.
*
* @return i2c command link handler
*/
i2c_cmd_handle_t i2c_cmd_link_create();
/**
* @brief Free I2C command link
* @note
* Before we build I2C command link, we need to call i2c_cmd_link_create() to create
* a command link.
* After we finish sending the commands, we need to call i2c_cmd_link_delete() to
* release and return the resources.
*
* @param cmd_handle I2C command handle
*/
void i2c_cmd_link_delete(i2c_cmd_handle_t cmd_handle);
/**
* @brief Queue command for I2C master to generate a start signal
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_start(i2c_cmd_handle_t cmd_handle);
/**
* @brief Queue command for I2C master to write one byte to I2C bus
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
* @param data I2C one byte command to write to bus
* @param ack_en enable ack check for master
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_write_byte(i2c_cmd_handle_t cmd_handle, uint8_t data, bool ack_en);
/**
* @brief Queue command for I2C master to write buffer to I2C bus
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
* @param data data to send
* @param data_len data length
* @param ack_en enable ack check for master
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_write(i2c_cmd_handle_t cmd_handle, uint8_t* data, size_t data_len, bool ack_en);
/**
* @brief Queue command for I2C master to read one byte from I2C bus
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
* @param data pointer accept the data byte
* @param ack ack value for read command
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_read_byte(i2c_cmd_handle_t cmd_handle, uint8_t* data, int ack);
/**
* @brief Queue command for I2C master to read data from I2C bus
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
* @param data data buffer to accept the data from bus
* @param data_len read data length
* @param ack ack value for read command
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_read(i2c_cmd_handle_t cmd_handle, uint8_t* data, size_t data_len, int ack);
/**
* @brief Queue command for I2C master to generate a stop signal
* @note
* Only call this function in I2C master mode
* Call i2c_master_cmd_begin() to send all queued commands
*
* @param cmd_handle I2C cmd link
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_master_stop(i2c_cmd_handle_t cmd_handle);
/**
* @brief I2C master send queued commands.
* This function will trigger sending all queued commands.
* The task will be blocked until all the commands have been sent out.
* The I2C APIs are not thread-safe, if you want to use one I2C port in different tasks,
* you need to take care of the multi-thread issue.
* @note
* Only call this function in I2C master mode
*
* @param i2c_num I2C port number
* @param cmd_handle I2C command handler
* @param ticks_to_wait maximum wait ticks.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
* - ESP_FAIL Sending command error, slave doesn't ACK the transfer.
* - ESP_ERR_INVALID_STATE I2C driver not installed or not in master mode.
* - ESP_ERR_TIMEOUT Operation timeout because the bus is busy.
*/
esp_err_t i2c_master_cmd_begin(i2c_port_t i2c_num, i2c_cmd_handle_t cmd_handle, portBASE_TYPE ticks_to_wait);
/**
* @brief I2C slave write data to internal ringbuffer, when tx fifo empty, isr will fill the hardware
* fifo from the internal ringbuffer
* @note
* Only call this function in I2C slave mode
*
* @param i2c_num I2C port number
* @param data data pointer to write into internal buffer
* @param size data size
* @param ticks_to_wait Maximum waiting ticks
*
* @return
* - ESP_FAIL(-1) Parameter error
* - Others(>=0) The number of data bytes that pushed to the I2C slave buffer.
*/
int i2c_slave_write_buffer(i2c_port_t i2c_num, uint8_t* data, int size, portBASE_TYPE ticks_to_wait);
/**
* @brief I2C slave read data from internal buffer. When I2C slave receive data, isr will copy received data
* from hardware rx fifo to internal ringbuffer. Then users can read from internal ringbuffer.
* @note
* Only call this function in I2C slave mode
*
* @param i2c_num I2C port number
* @param data data pointer to write into internal buffer
* @param max_size Maximum data size to read
* @param ticks_to_wait Maximum waiting ticks
*
* @return
* - ESP_FAIL(-1) Parameter error
* - Others(>=0) The number of data bytes that read from I2C slave buffer.
*/
int i2c_slave_read_buffer(i2c_port_t i2c_num, uint8_t* data, size_t max_size, portBASE_TYPE ticks_to_wait);
/**
* @brief set I2C master clock period
*
* @param i2c_num I2C port number
* @param high_period clock cycle number during SCL is high level, high_period is a 14 bit value
* @param low_period clock cycle number during SCL is low level, low_period is a 14 bit value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_period(i2c_port_t i2c_num, int high_period, int low_period);
/**
* @brief get I2C master clock period
*
* @param i2c_num I2C port number
* @param high_period pointer to get clock cycle number during SCL is high level, will get a 14 bit value
* @param low_period pointer to get clock cycle number during SCL is low level, will get a 14 bit value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2s_get_period(i2c_port_t i2c_num, int* high_period, int* low_period);
/**
* @brief set I2C master start signal timing
*
* @param i2c_num I2C port number
* @param setup_time clock number between the falling-edge of SDA and rising-edge of SCL for start mark, it's a 10-bit value.
* @param hold_time clock num between the falling-edge of SDA and falling-edge of SCL for start mark, it's a 10-bit value.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_start_timing(i2c_port_t i2c_num, int setup_time, int hold_time);
/**
* @brief get I2C master start signal timing
*
* @param i2c_num I2C port number
* @param setup_time pointer to get setup time
* @param hold_time pointer to get hold time
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_get_start_timing(i2c_port_t i2c_num, int* setup_time, int* hold_time);
/**
* @brief set I2C master stop signal timing
*
* @param i2c_num I2C port number
* @param setup_time clock num between the rising-edge of SCL and the rising-edge of SDA, it's a 10-bit value.
* @param hold_time clock number after the STOP bit's rising-edge, it's a 14-bit value.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_stop_timing(i2c_port_t i2c_num, int setup_time, int hold_time);
/**
* @brief get I2C master stop signal timing
*
* @param i2c_num I2C port number
* @param setup_time pointer to get setup time.
* @param hold_time pointer to get hold time.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_get_stop_timing(i2c_port_t i2c_num, int* setup_time, int* hold_time);
/**
* @brief set I2C data signal timing
*
* @param i2c_num I2C port number
* @param sample_time clock number I2C used to sample data on SDA after the rising-edge of SCL, it's a 10-bit value
* @param hold_time clock number I2C used to hold the data after the falling-edge of SCL, it's a 10-bit value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_data_timing(i2c_port_t i2c_num, int sample_time, int hold_time);
/**
* @brief get I2C data signal timing
*
* @param i2c_num I2C port number
* @param sample_time pointer to get sample time
* @param hold_time pointer to get hold time
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_get_data_timing(i2c_port_t i2c_num, int* sample_time, int* hold_time);
/**
* @brief set I2C data transfer mode
*
* @param i2c_num I2C port number
* @param tx_trans_mode I2C sending data mode
* @param rx_trans_mode I2C receving data mode
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_set_data_mode(i2c_port_t i2c_num, i2c_trans_mode_t tx_trans_mode, i2c_trans_mode_t rx_trans_mode);
/**
* @brief get I2C data transfer mode
*
* @param i2c_num I2C port number
* @param tx_trans_mode pointer to get I2C sending data mode
* @param rx_trans_mode pointer to get I2C receiving data mode
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t i2c_get_data_mode(i2c_port_t i2c_num, i2c_trans_mode_t *tx_trans_mode, i2c_trans_mode_t *rx_trans_mode);
#ifdef __cplusplus
}
#endif
#endif /*_DRIVER_I2C_H_*/
// Copyright 2015-2016 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.
#ifndef _DRIVER_I2S_H_
#define _DRIVER_I2S_H_
#include "esp_err.h"
#include <esp_types.h>
#include "soc/gpio_reg.h"
#include "soc/soc.h"
#include "soc/i2s_struct.h"
#include "soc/i2s_reg.h"
#include "soc/rtc_io_reg.h"
#include "soc/io_mux_reg.h"
#include "rom/gpio.h"
#include "esp_attr.h"
#include "esp_intr_alloc.h"
#include "driver/periph_ctrl.h"
#include "freertos/semphr.h"
#ifdef __cplusplus
extern "C" {
#endif
#define I2S_PIN_NO_CHANGE (-1)
/**
* @brief I2S bit width per sample.
*
*/
typedef enum {
I2S_BITS_PER_SAMPLE_8BIT = 8, /*!< I2S bits per sample: 8-bits*/
I2S_BITS_PER_SAMPLE_16BIT = 16, /*!< I2S bits per sample: 16-bits*/
I2S_BITS_PER_SAMPLE_24BIT = 24, /*!< I2S bits per sample: 24-bits*/
I2S_BITS_PER_SAMPLE_32BIT = 32, /*!< I2S bits per sample: 32-bits*/
} i2s_bits_per_sample_t;
/**
* @brief I2S communication standard format
*
*/
typedef enum {
I2S_COMM_FORMAT_I2S = 0x01, /*!< I2S communication format I2S*/
I2S_COMM_FORMAT_I2S_MSB = 0x02, /*!< I2S format MSB*/
I2S_COMM_FORMAT_I2S_LSB = 0x04, /*!< I2S format LSB*/
I2S_COMM_FORMAT_PCM = 0x08, /*!< I2S communication format PCM*/
I2S_COMM_FORMAT_PCM_SHORT = 0x10, /*!< PCM Short*/
I2S_COMM_FORMAT_PCM_LONG = 0x20, /*!< PCM Long*/
} i2s_comm_format_t;
/**
* @brief I2S channel format type
*/
typedef enum {
I2S_CHANNEL_FMT_RIGHT_LEFT = 0x00,
I2S_CHANNEL_FMT_ALL_RIGHT,
I2S_CHANNEL_FMT_ALL_LEFT,
I2S_CHANNEL_FMT_ONLY_RIGHT,
I2S_CHANNEL_FMT_ONLY_LEFT,
} i2s_channel_fmt_t;
/**
* @brief PDM sample rate ratio, measured in Hz.
*
*/
typedef enum {
PDM_SAMPLE_RATE_RATIO_64,
PDM_SAMPLE_RATE_RATIO_128,
} pdm_sample_rate_ratio_t;
/**
* @brief PDM PCM convter enable/disable.
*
*/
typedef enum {
PDM_PCM_CONV_ENABLE,
PDM_PCM_CONV_DISABLE,
} pdm_pcm_conv_t;
/**
* @brief I2S Peripheral, 0 & 1.
*
*/
typedef enum {
I2S_NUM_0 = 0x0, /*!< I2S 0*/
I2S_NUM_1 = 0x1, /*!< I2S 1*/
I2S_NUM_MAX,
} i2s_port_t;
/**
* @brief I2S Mode, defaut is I2S_MODE_MASTER | I2S_MODE_TX
*
*/
typedef enum {
I2S_MODE_MASTER = 1,
I2S_MODE_SLAVE = 2,
I2S_MODE_TX = 4,
I2S_MODE_RX = 8,
I2S_MODE_DAC_BUILT_IN = 16
} i2s_mode_t;
/**
* @brief I2S configuration parameters for i2s_param_config function
*
*/
typedef struct {
i2s_mode_t mode; /*!< I2S work mode*/
int sample_rate; /*!< I2S sample rate*/
i2s_bits_per_sample_t bits_per_sample; /*!< I2S bits per sample*/
i2s_channel_fmt_t channel_format; /*!< I2S channel format */
i2s_comm_format_t communication_format; /*!< I2S communication format */
int intr_alloc_flags; /*!< Flags used to allocate the interrupt. One or multiple (ORred) ESP_INTR_FLAG_* values. See esp_intr_alloc.h for more info */
int dma_buf_count; /*!< I2S DMA Buffer Count */
int dma_buf_len; /*!< I2S DMA Buffer Length */
} i2s_config_t;
/**
* @brief I2S event types
*
*/
typedef enum {
I2S_EVENT_DMA_ERROR,
I2S_EVENT_TX_DONE, /*!< I2S DMA finish sent 1 buffer*/
I2S_EVENT_RX_DONE, /*!< I2S DMA finish received 1 buffer*/
I2S_EVENT_MAX, /*!< I2S event max index*/
} i2s_event_type_t;
/**
* @brief Event structure used in I2S event queue
*
*/
typedef struct {
i2s_event_type_t type; /*!< I2S event type */
size_t size; /*!< I2S data size for I2S_DATA event*/
} i2s_event_t;
/**
* @brief I2S pin number for i2s_set_pin
*
*/
typedef struct {
int bck_io_num; /*!< BCK in out pin*/
int ws_io_num; /*!< WS in out pin*/
int data_out_num; /*!< DATA out pin*/
int data_in_num; /*!< DATA in pin*/
} i2s_pin_config_t;
typedef intr_handle_t i2s_isr_handle_t;
/**
* @brief Set I2S pin number
*
* @note
* Internal signal can be output to multiple GPIO pads
* Only one GPIO pad can connect with input signal
*
* @param i2s_num I2S_NUM_0 or I2S_NUM_1
*
* @param pin I2S Pin struct, or NULL for 2-channels, 8-bits DAC pin configuration (GPIO25 & GPIO26)
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_set_pin(i2s_port_t i2s_num, const i2s_pin_config_t *pin);
/**
* @brief i2s install and start driver
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param i2s_config I2S configurations - see i2s_config_t struct
*
* @param queue_size I2S event queue size/depth.
*
* @param i2s_queue I2S event queue handle, if set NULL, driver will not use an event queue.
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_driver_install(i2s_port_t i2s_num, const i2s_config_t *i2s_config, int queue_size, void* i2s_queue);
/**
* @brief Uninstall I2S driver.
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_driver_uninstall(i2s_port_t i2s_num);
/**
* @brief i2s read data buffer to i2s dma buffer
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param src source address to write
*
* @param size size of data (size in bytes)
*
* @param ticks_to_wait Write timeout
*
* @return number of written bytes
*/
int i2s_write_bytes(i2s_port_t i2s_num, const char *src, size_t size, TickType_t ticks_to_wait);
/**
* @brief i2s write data buffer to i2s dma buffer
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param dest destination address to read
*
* @param size size of data (size in bytes)
*
* @param ticks_to_wait Read timeout
*
* @return number of read bytes
*/
int i2s_read_bytes(i2s_port_t i2s_num, char* dest, size_t size, TickType_t ticks_to_wait);
/**
* @brief i2s push 1 sample to i2s dma buffer, with the size parameter equal to one sample's size in bytes = bits_per_sample/8.
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param sample destination address to write (depend on bits_per_sample, size of sample (in bytes) = 2*bits_per_sample/8)
*
* @param ticks_to_wait Push timeout
*
* @return number of push bytes
*/
int i2s_push_sample(i2s_port_t i2s_num, const char *sample, TickType_t ticks_to_wait);
/**
* @brief Pop 1 sample to i2s dma buffer, with the size parameter equal to one sample's size in bytes = bits_per_sample/8.
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param sample destination address to write (depend on bits_per_sample, size of sample (in bytes) = 2*bits_per_sample/8)
*
* @param ticks_to_wait Pop timeout
*
* @return number of pop bytes
*/
int i2s_pop_sample(i2s_port_t i2s_num, char *sample, TickType_t ticks_to_wait);
/**
* @brief Set clock rate used for I2S RX and TX
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @param rate I2S clock (ex: 8000, 44100...)
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_set_sample_rates(i2s_port_t i2s_num, uint32_t rate);
/**
* @brief Start driver
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_start(i2s_port_t i2s_num);
/**
* @brief Stop driver
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_stop(i2s_port_t i2s_num);
/**
* @brief Set the TX DMA buffer contents to all zeroes
*
* @param i2s_num I2S_NUM_0, I2S_NUM_1
*
* @return
* - ESP_OK Success
* - ESP_FAIL Parameter error
*/
esp_err_t i2s_zero_dma_buffer(i2s_port_t i2s_num);
/***************************EXAMPLE**********************************
*
*
* ----------------EXAMPLE OF I2S SETTING ---------------------
* @code{c}
*
* #include "freertos/queue.h"
* #define I2S_INTR_NUM 17 //choose one interrupt number from soc.h
* int i2s_num = 0; //i2s port number
* i2s_config_t i2s_config = {
* .mode = I2S_MODE_MASTER | I2S_MODE_TX,
* .sample_rate = 44100,
* .bits_per_sample = 16, //16, 32
* .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT, //format LEFT_RIGHT
* .communication_format = I2S_COMM_FORMAT_I2S | I2S_COMM_FORMAT_I2S_MSB,
* .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1,
* .dma_buf_count = 8,
* .dma_buf_len = 64
* };
*
* i2s_pin_config_t pin_config = {
* .bck_io_num = 26,
* .ws_io_num = 25,
* .data_out_num = 22,
* .data_in_num = I2S_PIN_NO_CHANGE
* };
*
* i2s_driver_install(i2s_num, &i2s_config, 0, NULL); //install and start i2s driver
*
* i2s_set_pin(i2s_num, &pin_config);
*
* i2s_set_sample_rates(i2s_num, 22050); //set sample rates
*
*
* i2s_driver_uninstall(i2s_num); //stop & destroy i2s driver
*@endcode
*
* ----------------EXAMPLE USING I2S WITH DAC ---------------------
* @code{c}
*
* #include "freertos/queue.h"
* #define I2S_INTR_NUM 17 //choose one interrupt number from soc.h
* int i2s_num = 0; //i2s port number
* i2s_config_t i2s_config = {
* .mode = I2S_MODE_MASTER | I2S_MODE_TX | I2S_MODE_DAC_BUILT_IN,
* .sample_rate = 44100,
* .bits_per_sample = 8, // Only 8-bit DAC support
* .channel_format = I2S_CHANNEL_FMT_RIGHT_LEFT, //
* .communication_format = I2S_COMM_FORMAT_I2S_MSB,
* .intr_alloc_flags = ESP_INTR_FLAG_LEVEL1,
* .dma_buf_count = 8,
* .dma_buf_len = 64
* };
*
*
* i2s_driver_install(i2s_num, &i2s_config, 0, NULL); //install and start i2s driver
*
* i2s_set_pin(i2s_num, NULL); //for internal DAC
*
* i2s_set_sample_rates(i2s_num, 22050); //set sample rates
*
* i2s_driver_uninstall(i2s_num); //stop & destroy i2s driver
*@endcode
*-----------------------------------------------------------------------------*
***************************END OF EXAMPLE**********************************/
#ifdef __cplusplus
}
#endif
#endif /* _DRIVER_I2S_H_ */
......@@ -104,4 +104,13 @@ void esp_cpu_stall(int cpu_id);
*/
void esp_cpu_unstall(int cpu_id);
/**
* @brief Returns true if a JTAG debugger is attached to CPU
* OCD (on chip debug) port.
*
* @note If "Make exception and panic handlers JTAG/OCD aware"
* is disabled, this function always returns false.
*/
bool esp_cpu_in_ocd_debug_mode();
#endif
......@@ -261,6 +261,8 @@
#define I2C_RXFIFO_FULL_THRHD_V 0x1F
#define I2C_RXFIFO_FULL_THRHD_S 0
#define I2C_DATA_APB_REG(i) (0x60013000 + (i) * 0x14000 + 0x001c)
#define I2C_DATA_REG(i) (REG_I2C_BASE(i) + 0x001c)
/* I2C_FIFO_RDATA : RO ;bitpos:[7:0] ;default: 8'b0 ; */
/*description: The register represent the byte data read from rxfifo when use apb fifo access*/
......
......@@ -16,7 +16,7 @@
typedef volatile struct {
union {
struct {
uint32_t scl_low_period:14; /*This register is used to configure the low level width of SCL clock.*/
uint32_t period:14; /*This register is used to configure the low level width of SCL clock.*/
uint32_t reserved14: 18;
};
uint32_t val;
......@@ -58,7 +58,7 @@ typedef volatile struct {
} status_reg;
union {
struct {
uint32_t tout: 20; /*This register is used to configure the max clock number of receiving a data.*/
uint32_t tout: 20; /*This register is used to configure the max clock number of receiving a data, unit: APB clock cycle.*/
uint32_t reserved20:12;
};
uint32_t val;
......@@ -282,7 +282,7 @@ typedef volatile struct {
uint32_t reserved_f4;
uint32_t date; /**/
uint32_t reserved_fc;
uint32_t fifo_start_addr; /*This the start address for ram when use apb nonfifo access.*/
uint32_t ram_data[32]; /*This the start address for ram when use apb nonfifo access.*/
} i2c_dev_t;
extern i2c_dev_t I2C0;
extern i2c_dev_t I2C1;
......
......@@ -440,7 +440,7 @@
/**
* LWIP_SO_RCVBUF==1: Enable SO_RCVBUF processing.
*/
#define LWIP_SO_RCVBUF 1
#define LWIP_SO_RCVBUF CONFIG_LWIP_SO_RCVBUF
/**
* SO_REUSE==1: Enable SO_REUSEADDR option.
......
......@@ -440,7 +440,7 @@
/**
* LWIP_SO_RCVBUF==1: Enable SO_RCVBUF processing.
*/
#define LWIP_SO_RCVBUF 1
#define LWIP_SO_RCVBUF CONFIG_LWIP_SO_RCVBUF
/**
* SO_REUSE==1: Enable SO_REUSEADDR option.
......
......@@ -99,7 +99,7 @@ SECTIONS
*(.sbss2.*)
*(.gnu.linkonce.sb2.*)
*(.dynbss)
KEEP(*(.bss))
*(.bss)
*(.bss.*)
*(.share.mem)
*(.gnu.linkonce.b.*)
......@@ -111,17 +111,17 @@ SECTIONS
.dram0.data :
{
_data_start = ABSOLUTE(.);
KEEP(*(.data))
KEEP(*(.data.*))
KEEP(*(.gnu.linkonce.d.*))
KEEP(*(.data1))
KEEP(*(.sdata))
KEEP(*(.sdata.*))
KEEP(*(.gnu.linkonce.s.*))
KEEP(*(.sdata2))
KEEP(*(.sdata2.*))
KEEP(*(.gnu.linkonce.s2.*))
KEEP(*(.jcr))
*(.data)
*(.data.*)
*(.gnu.linkonce.d.*)
*(.data1)
*(.sdata)
*(.sdata.*)
*(.gnu.linkonce.s.*)
*(.sdata2)
*(.sdata2.*)
*(.gnu.linkonce.s2.*)
*(.jcr)
*(.dram1 .dram1.*)
*libesp32.a:panic.o(.rodata .rodata.*)
_data_end = ABSOLUTE(.);
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册