Merge branch 'master' of ssh://gitlab.espressif.cn:27227/idf/esp-idf into feature/throughput_optimization_phrase_1

This commit is contained in:
Liu Zhi Fu 2017-01-05 11:37:56 +08:00
commit be994740b4
27 changed files with 2242 additions and 90 deletions

View file

@ -36,6 +36,16 @@ This will flash the entire project (app, bootloader and partition table) to a ne
You don't need to run `make all` before running `make flash`, `make flash` will automatically rebuild anything which needs it.
# Viewing Serial Output
The `make monitor` target will use the already-installed [miniterm](http://pyserial.readthedocs.io/en/latest/tools.html#module-serial.tools.miniterm) (a part of pyserial) to display serial output from the ESP32 on the terminal console.
Exit miniterm by typing Ctrl-].
To flash and monitor output in one pass, you can run:
`make flash monitor`
# Compiling & Flashing Just the App
After the initial flash, you may just want to build and flash just your app, not the bootloader and partition table:
@ -47,6 +57,16 @@ After the initial flash, you may just want to build and flash just your app, not
(There's no downside to reflashing the bootloader and partition table each time, if they haven't changed.)
# Parallel Builds
esp-idf supports compiling multiple files in parallel, so all of the above commands can be run as `make -jN` where `N` is the number of parallel make processes to run (generally N should be equal to or one more than the number of CPU cores in your system.)
Multiple make functions can be combined into one. For example: to build the app & bootloader using 5 jobs in parallel, then flash everything, and then display serial output from the ESP32 run:
```
make -j5 flash monitor
```
# The Partition Table
Once you've compiled your project, the "build" directory will contain a binary file with a name like "my_app.bin". This is an ESP32 image binary that can be loaded by the bootloader.

View file

@ -50,11 +50,14 @@ else ifdef CONFIG_SECURE_BOOTLOADER_ONE_TIME_FLASH
# One time flashing requires user to run esptool.py command themselves,
# and warning is printed about inability to reflash.
#
# The flashing command is deliberately printed without an auto-reset
# step, so the device doesn't immediately reset to flash itself.
bootloader: $(BOOTLOADER_BIN)
@echo $(SEPARATOR)
@echo "Bootloader built. One-time flash command is:"
@echo "$(ESPTOOLPY_WRITE_FLASH) $(BOOTLOADER_OFFSET) $(BOOTLOADER_BIN)"
@echo "$(subst hard_reset,no_reset,$(ESPTOOLPY_WRITE_FLASH)) $(BOOTLOADER_OFFSET) $(BOOTLOADER_BIN)"
@echo $(SEPARATOR)
@echo "* IMPORTANT: After first boot, BOOTLOADER CANNOT BE RE-FLASHED on same device"

View file

@ -40,6 +40,7 @@
#include "esp_image_format.h"
#include "esp_secure_boot.h"
#include "esp_flash_encrypt.h"
#include "esp_flash_partitions.h"
#include "bootloader_flash.h"
#include "bootloader_config.h"
@ -116,16 +117,14 @@ bool load_partition_table(bootloader_state_t* bs)
{
const esp_partition_info_t *partitions;
const int ESP_PARTITION_TABLE_DATA_LEN = 0xC00; /* length of actual data (signature is appended to this) */
const int MAX_PARTITIONS = ESP_PARTITION_TABLE_DATA_LEN / sizeof(esp_partition_info_t);
char *partition_usage;
ESP_LOGI(TAG, "Partition Table:");
ESP_LOGI(TAG, "## Label Usage Type ST Offset Length");
esp_err_t err;
int num_partitions;
#ifdef CONFIG_SECURE_BOOT_ENABLED
if(esp_secure_boot_enabled()) {
ESP_LOGI(TAG, "Verifying partition table signature...");
esp_err_t err = esp_secure_boot_verify_signature(ESP_PARTITION_TABLE_ADDR, ESP_PARTITION_TABLE_DATA_LEN);
err = esp_secure_boot_verify_signature(ESP_PARTITION_TABLE_ADDR, ESP_PARTITION_TABLE_DATA_LEN);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to verify partition table signature.");
return false;
@ -141,17 +140,21 @@ bool load_partition_table(bootloader_state_t* bs)
}
ESP_LOGD(TAG, "mapped partition table 0x%x at 0x%x", ESP_PARTITION_TABLE_ADDR, (intptr_t)partitions);
for(int i = 0; i < MAX_PARTITIONS; i++) {
err = esp_partition_table_basic_verify(partitions, true, &num_partitions);
if (err != ESP_OK) {
ESP_LOGE(TAG, "Failed to verify partition table");
return false;
}
ESP_LOGI(TAG, "Partition Table:");
ESP_LOGI(TAG, "## Label Usage Type ST Offset Length");
for(int i = 0; i < num_partitions; i++) {
const esp_partition_info_t *partition = &partitions[i];
ESP_LOGD(TAG, "load partition table entry 0x%x", (intptr_t)partition);
ESP_LOGD(TAG, "type=%x subtype=%x", partition->type, partition->subtype);
partition_usage = "unknown";
if (partition->magic != ESP_PARTITION_MAGIC) {
/* invalid partition definition indicates end-of-table */
break;
}
/* valid partition table */
switch(partition->type) {
case PART_TYPE_APP: /* app partition */

View file

@ -13,32 +13,43 @@
// limitations under the License.
#include "esp_flash_partitions.h"
#include "esp_log.h"
#include "rom/spi_flash.h"
static const char *TAG = "flash_parts";
esp_err_t esp_partition_table_basic_verify(const esp_partition_info_t *partition_table, bool log_errors, int *num_partitions)
{
int num_parts;
uint32_t chip_size = g_rom_flashchip.chip_size;
*num_partitions = 0;
for(num_parts = 0; num_parts < ESP_PARTITION_TABLE_MAX_ENTRIES; num_parts++) {
const esp_partition_info_t *part = &partition_table[num_parts];
if(part->magic == 0xFFFF
&& part->type == PART_TYPE_END
&& part->subtype == PART_SUBTYPE_END) {
if (part->magic == 0xFFFF
&& part->type == PART_TYPE_END
&& part->subtype == PART_SUBTYPE_END) {
/* TODO: check md5 */
ESP_LOGD(TAG, "partition table verified, %d entries", num_parts);
*num_partitions = num_parts;
return ESP_OK;
}
if(part->magic != ESP_PARTITION_MAGIC) {
if (part->magic != ESP_PARTITION_MAGIC) {
if (log_errors) {
ESP_LOGE(TAG, "partition %d invalid magic number 0x%x", num_parts, part->magic);
}
return ESP_ERR_INVALID_STATE;
}
const esp_partition_pos_t *pos = &part->pos;
if (pos->offset > chip_size || pos->offset + pos->size > chip_size) {
if (log_errors) {
ESP_LOGE(TAG, "partition %d invalid - offset 0x%x size 0x%x exceeds flash chip size 0x%x",
num_parts, pos->offset, pos->size, chip_size);
}
return ESP_ERR_INVALID_SIZE;
}
}
if (log_errors) {

1037
components/driver/i2c.c Normal file

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,514 @@
// 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_*/

View file

@ -42,3 +42,15 @@ void IRAM_ATTR esp_cpu_unstall(int cpu_id)
CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_SW_STALL_PROCPU_C0_M);
}
}
bool IRAM_ATTR esp_cpu_in_ocd_debug_mode()
{
#if CONFIG_ESP32_DEBUG_OCDAWARE
int dcr;
int reg=0x10200C; //DSRSET register
asm("rer %0,%1":"=r"(dcr):"r"(reg));
return (dcr&0x1);
#else
return false; // Always return false if "OCD aware" is disabled
#endif
}

View file

@ -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

View file

@ -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*/

View file

@ -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;

View file

@ -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(.);

View file

@ -36,7 +36,7 @@
/*
Panic handlers; these get called when an unhandled exception occurs or the assembly-level
task switching / interrupt code runs into an unrecoverable error. The default task stack
overflow handler also is in here.
overflow handler and abort handler are also in here.
*/
/*
@ -95,15 +95,29 @@ inline static void panicPutHex(int a) { }
inline static void panicPutDec(int a) { }
#endif
void __attribute__((weak)) vApplicationStackOverflowHook( TaskHandle_t xTask, signed char *pcTaskName )
{
panicPutStr("***ERROR*** A stack overflow in task ");
panicPutStr((char *)pcTaskName);
panicPutStr(" has been detected.\r\n");
configASSERT(0);
abort();
}
static bool abort_called;
void abort()
{
#if !CONFIG_ESP32_PANIC_SILENT_REBOOT
ets_printf("abort() was called at PC 0x%08x\n", (intptr_t)__builtin_return_address(0) - 3);
#endif
abort_called = true;
while(1) {
__asm__ ("break 0,0");
*((int*) 0) = 0;
}
}
static const char *edesc[] = {
"IllegalInstruction", "Syscall", "InstructionFetchError", "LoadStoreError",
"Level1Interrupt", "Alloca", "IntegerDivideByZero", "PCValue",
@ -118,7 +132,7 @@ static const char *edesc[] = {
};
void commonErrorHandler(XtExcFrame *frame);
static void commonErrorHandler(XtExcFrame *frame);
//The fact that we've panic'ed probably means the other CPU is now running wild, possibly
//messing up the serial output, so we stall it here.
@ -127,19 +141,6 @@ static void haltOtherCore()
esp_cpu_stall( xPortGetCoreID() == 0 ? 1 : 0 );
}
//Returns true when a debugger is attached using JTAG.
static int inOCDMode()
{
#if CONFIG_ESP32_DEBUG_OCDAWARE
int dcr;
int reg = 0x10200C; //DSRSET register
asm("rer %0,%1":"=r"(dcr):"r"(reg));
return (dcr & 0x1);
#else
return 0; //Always return no debugger is attached.
#endif
}
void panicHandler(XtExcFrame *frame)
{
int *regs = (int *)frame;
@ -165,7 +166,7 @@ void panicHandler(XtExcFrame *frame)
panicPutStr(reason);
panicPutStr(")\r\n");
if (inOCDMode()) {
if (esp_cpu_in_ocd_debug_mode()) {
asm("break.n 1");
}
commonErrorHandler(frame);
@ -197,7 +198,7 @@ void xt_unhandled_exception(XtExcFrame *frame)
}
panicPutStr(" occurred on core ");
panicPutDec(xPortGetCoreID());
if (inOCDMode()) {
if (esp_cpu_in_ocd_debug_mode()) {
panicPutStr(" at pc=");
panicPutHex(regs[1]);
panicPutStr(". Setting bp and returning..\r\n");
@ -255,6 +256,7 @@ static inline bool stackPointerIsSane(uint32_t sp)
{
return !(sp < 0x3ffae010 || sp > 0x3ffffff0 || ((sp & 0xf) != 0));
}
static void putEntry(uint32_t pc, uint32_t sp)
{
if (pc & 0x80000000) {
@ -265,7 +267,8 @@ static void putEntry(uint32_t pc, uint32_t sp)
panicPutStr(":0x");
panicPutHex(sp);
}
void doBacktrace(XtExcFrame *frame)
static void doBacktrace(XtExcFrame *frame)
{
uint32_t i = 0, pc = frame->pc, sp = frame->a1;
panicPutStr("\nBacktrace:");
@ -291,7 +294,7 @@ void doBacktrace(XtExcFrame *frame)
We arrive here after a panic or unhandled exception, when no OCD is detected. Dump the registers to the
serial port and either jump to the gdb stub, halt the CPU or reboot.
*/
void commonErrorHandler(XtExcFrame *frame)
static void commonErrorHandler(XtExcFrame *frame)
{
int *regs = (int *)frame;
int x, y;
@ -304,21 +307,28 @@ void commonErrorHandler(XtExcFrame *frame)
//Feed the watchdogs, so they will give us time to print out debug info
reconfigureAllWdts();
panicPutStr("Register dump:\r\n");
/* only dump registers for 'real' crashes, if crashing via abort()
the register window is no longer useful.
*/
if (!abort_called) {
panicPutStr("Register dump:\r\n");
for (x = 0; x < 24; x += 4) {
for (y = 0; y < 4; y++) {
if (sdesc[x + y][0] != 0) {
panicPutStr(sdesc[x + y]);
panicPutStr(": 0x");
panicPutHex(regs[x + y + 1]);
panicPutStr(" ");
for (x = 0; x < 24; x += 4) {
for (y = 0; y < 4; y++) {
if (sdesc[x + y][0] != 0) {
panicPutStr(sdesc[x + y]);
panicPutStr(": 0x");
panicPutHex(regs[x + y + 1]);
panicPutStr(" ");
}
}
panicPutStr("\r\n");
}
panicPutStr("\r\n");
}
/* With windowed ABI backtracing is easy, let's do it. */
doBacktrace(frame);
#if CONFIG_ESP32_PANIC_GDBSTUB
disableAllWdts();
panicPutStr("Entering gdb stub now.\r\n");
@ -339,8 +349,7 @@ void commonErrorHandler(XtExcFrame *frame)
void esp_set_breakpoint_if_jtag(void *fn)
{
if (!inOCDMode()) {
return;
if (esp_cpu_in_ocd_debug_mode()) {
setFirstBreakpoint((uint32_t)fn);
}
setFirstBreakpoint((uint32_t)fn);
}

View file

@ -121,4 +121,101 @@ config ESPTOOLPY_FLASHSIZE
default "8MB" if ESPTOOLPY_FLASHSIZE_8MB
default "16MB" if ESPTOOLPY_FLASHSIZE_16MB
config ESPTOOLPY_FLASHSIZE_DETECT
bool "Detect flash size when flashing bootloader"
default y
help
If this option is set, 'make flash' targets will automatically detect
the flash size and update the bootloader image when flashing.
choice ESPTOOLPY_BEFORE
prompt "Before flashing"
default ESPTOOLPY_BEFORE_RESET
help
Configure whether esptool.py should reset the ESP32 before flashing.
Automatic resetting depends on the RTS & DTR signals being
wired from the serial port to the ESP32. Most USB development
boards do this internally.
The "Reset with ESP32R0 Windows workaround" option works
around an automatic reset bug in hardware, when using Windows
with some development boards. This fix only works if you're
using a silicon revision 0 ESP32.
config ESPTOOLPY_BEFORE_RESET
bool "Reset to bootloader"
config ESPTOOLPY_BEFORE_NORESET
bool "No reset"
config ESPTOOLPY_BEFORE_ESP32R0
bool "Reset with ESP32R0 Windows workaround"
endchoice
config ESPTOOLPY_BEFORE
string
default "default_reset" if ESPTOOLPY_BEFORE_RESET
default "no_reset" if ESPTOOLPY_BEFORE_NORESET
default "esp32r0" if ESPTOOLPY_BEFORE_ESP32R0
choice ESPTOOLPY_AFTER
prompt "After flashing"
default ESPTOOLPY_AFTER_RESET
help
Configure whether esptool.py should reset the ESP32 after flashing.
Automatic resetting depends on the RTS & DTR signals being
wired from the serial port to the ESP32. Most USB development
boards do this internally.
config ESPTOOLPY_AFTER_RESET
bool "Reset after flashing"
config ESPTOOLPY_AFTER_NORESET
bool "Stay in bootloader"
endchoice
config ESPTOOLPY_AFTER
string
default "hard_reset" if ESPTOOLPY_AFTER_RESET
default "no_reset" if ESPTOOLPY_AFTER_NORESET
choice MONITOR_BAUD
prompt "'make monitor' baud rate"
default MONITOR_BAUD_115200B
help
Baud rate to use when running 'make monitor' to view serial output
from a running chip.
Can override by setting the MONITORBAUD environment variable.
config MONITOR_BAUD_9600B
bool "9600 bps"
config MONITOR_BAUD_57600B
bool "57600 bps"
config MONITOR_BAUD_115200B
bool "115200 bps"
config MONITOR_BAUD_230400B
bool "230400 bps"
config MONITOR_BAUD_921600B
bool "921600 bps"
config MONITOR_BAUD_2MB
bool "2 Mbps"
config MONITOR_BAUD_OTHER
bool "Custom baud rate"
endchoice
config MONITOR_BAUD_OTHER_VAL
int "Custom baud rate value" if MONITOR_BAUD_OTHER
default 115200
config MONITOR_BAUD
int
default 9600 if MONITOR_BAUD_9600B
default 57600 if MONITOR_BAUD_57600B
default 115200 if MONITOR_BAUD_115200B
default 230400 if MONITOR_BAUD_230400B
default 921600 if MONITOR_BAUD_921600B
default 2000000 if MONITOR_BAUD_2MB
default MONITOR_BAUD_OTHER_VAL if MONITOR_BAUD_OTHER
endmenu

View file

@ -13,7 +13,7 @@ PYTHON ?= $(call dequote,$(CONFIG_PYTHON))
#
ESPTOOLPY_SRC := $(COMPONENT_PATH)/esptool/esptool.py
ESPTOOLPY := $(PYTHON) $(ESPTOOLPY_SRC) --chip esp32
ESPTOOLPY_SERIAL := $(ESPTOOLPY) --port $(ESPPORT) --baud $(ESPBAUD)
ESPTOOLPY_SERIAL := $(ESPTOOLPY) --port $(ESPPORT) --baud $(ESPBAUD) --before $(CONFIG_ESPTOOLPY_BEFORE) --after $(CONFIG_ESPTOOLPY_AFTER)
# Supporting esptool command line tools
ESPEFUSEPY := $(PYTHON) $(COMPONENT_PATH)/esptool/espefuse.py
@ -21,10 +21,15 @@ ESPSECUREPY := $(PYTHON) $(COMPONENT_PATH)/esptool/espsecure.py
export ESPSECUREPY # is used in bootloader_support component
ESPTOOL_FLASH_OPTIONS := --flash_mode $(ESPFLASHMODE) --flash_freq $(ESPFLASHFREQ) --flash_size $(ESPFLASHSIZE)
ifdef CONFIG_ESPTOOLPY_FLASHSIZE_DETECT
ESPTOOL_WRITE_FLASH_OPTIONS := --flash_mode $(ESPFLASHMODE) --flash_freq $(ESPFLASHFREQ) --flash_size detect
else
ESPTOOL_WRITE_FLASH_OPTIONS := $(ESPTOOL_FLASH_OPTIONS)
endif
ESPTOOL_ELF2IMAGE_OPTIONS :=
ESPTOOLPY_WRITE_FLASH=$(ESPTOOLPY_SERIAL) write_flash $(if $(CONFIG_ESPTOOLPY_COMPRESSED),-z) $(ESPTOOL_FLASH_OPTIONS)
ESPTOOLPY_WRITE_FLASH=$(ESPTOOLPY_SERIAL) write_flash $(if $(CONFIG_ESPTOOLPY_COMPRESSED),-z) $(ESPTOOL_WRITE_FLASH_OPTIONS)
ESPTOOL_ALL_FLASH_ARGS += $(CONFIG_APP_OFFSET) $(APP_BIN)
@ -62,4 +67,12 @@ erase_flash:
@echo "Erasing entire flash..."
$(ESPTOOLPY_SERIAL) erase_flash
MONITORBAUD ?= $(CONFIG_MONITOR_BAUD)
# note: if you want to run miniterm from command line, can simply run
# miniterm.py on the console. The '$(PYTHON) -m serial.tools.miniterm'
# is to allow for the $(PYTHON) variable overriding the python path.
monitor: $(call prereq_if_explicit,%flash)
$(PYTHON) -m serial.tools.miniterm --rts 0 --dtr 0 --raw $(ESPPORT) $(MONITORBAUD)
.PHONY: erase_flash

@ -1 +1 @@
Subproject commit adc914b91ac6d2cfd1ace56307b4374eb9439e14
Subproject commit fe69994270e2a450aad3e94a409b58460b1a214f

View file

@ -22,15 +22,6 @@
#include "esp_attr.h"
#include "freertos/FreeRTOS.h"
void IRAM_ATTR abort()
{
do
{
__asm__ ("break 0,0");
*((int*) 0) = 0;
} while(true);
}
void* IRAM_ATTR _malloc_r(struct _reent *r, size_t size)
{
return pvPortMalloc(size);

82
docs/api/i2c.rst Normal file
View file

@ -0,0 +1,82 @@
I2C
===========
Overview
--------
ESP32 has two I2C controllers which can be set as master mode or slave mode.
Application Example
-------------------
I2C master and slave example: `examples/18_i2c <https://github.com/espressif/esp-idf/tree/master/examples/18_i2c>`_.
API Reference
-------------
Header Files
^^^^^^^^^^^^
* `driver/include/driver/i2c.h <https://github.com/espressif/esp-idf/blob/master/components/driver/include/driver/i2c.h>`_
Macros
^^^^^^
.. doxygendefine:: I2C_APB_CLK_FREQ
.. doxygendefine:: I2C_FIFO_LEN
Type Definitions
^^^^^^^^^^^^^^^^
.. doxygentypedef:: i2c_cmd_handle_t
Enumerations
^^^^^^^^^^^^
.. doxygenenum:: i2c_mode_t
.. doxygenenum:: i2c_rw_t
.. doxygenenum:: i2c_trans_mode_t
.. doxygenenum:: i2c_opmode_t
.. doxygenenum:: i2c_port_t
.. doxygenenum:: i2c_addr_mode_t
Structures
^^^^^^^^^^
.. doxygenstruct:: i2c_config_t
:members:
Functions
^^^^^^^^^
.. doxygenfunction:: i2c_driver_install
.. doxygenfunction:: i2c_driver_delete
.. doxygenfunction:: i2c_param_config
.. doxygenfunction:: i2c_reset_tx_fifo
.. doxygenfunction:: i2c_reset_rx_fifo
.. doxygenfunction:: i2c_isr_register
.. doxygenfunction:: i2c_isr_free
.. doxygenfunction:: i2c_set_pin
.. doxygenfunction:: i2c_master_start
.. doxygenfunction:: i2c_master_write_byte
.. doxygenfunction:: i2c_master_write
.. doxygenfunction:: i2c_master_read_byte
.. doxygenfunction:: i2c_master_read
.. doxygenfunction:: i2c_master_stop
.. doxygenfunction:: i2c_master_cmd_begin
.. doxygenfunction:: i2c_slave_write_buffer
.. doxygenfunction:: i2c_slave_read
.. doxygenfunction:: i2c_set_period
.. doxygenfunction:: i2s_get_period
.. doxygenfunction:: i2c_set_start_timing
.. doxygenfunction:: i2c_get_start_timing
.. doxygenfunction:: i2c_set_stop_timing
.. doxygenfunction:: i2c_get_stop_timing
.. doxygenfunction:: i2c_set_data_timing
.. doxygenfunction:: i2c_get_data_timing
.. doxygenfunction:: i2c_set_data_mode
.. doxygenfunction:: i2c_get_data_mode
.. doxygenfunction:: i2c_cmd_link_create
.. doxygenfunction:: i2c_cmd_link_delete

View file

@ -107,6 +107,7 @@ Contents:
LED Control <api/ledc>
Remote Control <api/rmt>
Timer <api/timer>
I2C <api/i2c>
Pulse Counter <api/pcnt>
Sigma-delta Modulation <api/sigmadelta>
SPI Flash and Partition APIs <api/spi_flash>

View file

@ -30,6 +30,7 @@
#include "bt_trace.h"
#include "bt_types.h"
#include "bta_api.h"
#include "blufi.h"

View file

@ -46,15 +46,15 @@ const int CONNECTED_BIT = BIT0;
static wifi_config_t sta_config;
static char tmp_ssid[33];
static char tmp_passwd[33];
static char tmp_passwd[65];
static bool confirm = false;
void wifi_set_blue_config(char *ssid, char *passwd)
{
memset(tmp_ssid, 0, 33);
memset(tmp_passwd, 0, 33);
strcpy(tmp_ssid, ssid);
strcpy(tmp_passwd, passwd);
memset(tmp_ssid, 0, sizeof(tmp_ssid));
memset(tmp_passwd, 0, sizeof(tmp_passwd));
strlcpy(tmp_ssid, ssid, sizeof(tmp_ssid));
strlcpy(tmp_passwd, passwd, sizeof(tmp_passwd));
confirm = true;
LOG_DEBUG("confirm true\n");
}
@ -105,8 +105,8 @@ void wifiTestTask(void *pvParameters)
if (confirm) {
confirm = false;
strcpy(sta_config.sta.ssid, tmp_ssid);
strcpy(sta_config.sta.password, tmp_passwd);
memcpy(sta_config.sta.ssid, tmp_ssid, sizeof(sta_config.sta.ssid));
memcpy(sta_config.sta.password, tmp_passwd, sizeof(sta_config.sta.password));
sta_config.sta.bssid_set = 0;
ret = esp_wifi_disconnect();

9
examples/18_i2c/Makefile Normal file
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 := i2c
include $(IDF_PATH)/make/project.mk

29
examples/18_i2c/README.md Normal file
View file

@ -0,0 +1,29 @@
# I2C Example
* This example will show you how to use I2C module by running two tasks on i2c bus:
* read external i2c sensor, here we use a BH1750 light sensor(GY-30 module) for instance.
* Use one I2C port(master mode) to read or write the other I2C port(slave mode) on one ESP32 chip.
* Pin assignment:
* slave :
* GPIO25 is assigned as the data signal of i2c slave port
* GPIO26 is assigned as the clock signal of i2c slave port
* master:
* GPIO18 is assigned as the data signal of i2c master port
* GPIO19 is assigned as the clock signal of i2c master port
* Connection:
* connect GPIO18 with GPIO25
* connect GPIO19 with GPIO26
* connect sda/scl of sensor with GPIO18/GPIO19
* no need to add external pull-up resistors, driver will enable internal pull-up resistors.
* Test items:
* read the sensor data, if connected.
* i2c master(ESP32) will write data to i2c slave(ESP32).
* i2c master(ESP32) will read data from i2c slave(ESP32).

View file

@ -0,0 +1,3 @@
#
# Main Makefile. This is basically the same as a component makefile.
#

View file

@ -0,0 +1,303 @@
/* i2c - Example
For other examples please check:
https://github.com/espressif/esp-idf/tree/master/examples
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 "driver/i2c.h"
/**
* TEST CODE BRIEF
*
* This example will show you how to use I2C module by running two tasks on i2c bus:
*
* - read external i2c sensor, here we use a BH1750 light sensor(GY-30 module) for instance.
* - Use one I2C port(master mode) to read or write the other I2C port(slave mode) on one ESP32 chip.
*
* Pin assignment:
*
* - slave :
* GPIO25 is assigned as the data signal of i2c slave port
* GPIO26 is assigned as the clock signal of i2c slave port
* - master:
* GPIO18 is assigned as the data signal of i2c master port
* GPIO19 is assigned as the clock signal of i2c master port
*
* Connection:
*
* - connect GPIO18 with GPIO25
* - connect GPIO19 with GPIO26
* - connect sda/scl of sensor with GPIO18/GPIO19
* - no need to add external pull-up resistors, driver will enable internal pull-up resistors.
*
* Test items:
*
* - read the sensor data, if connected.
* - i2c master(ESP32) will write data to i2c slave(ESP32).
* - i2c master(ESP32) will read data from i2c slave(ESP32).
*/
#define DATA_LENGTH 512 /*!<Data buffer length for test buffer*/
#define RW_TEST_LENGTH 129 /*!<Data length for r/w test, any value from 0-DATA_LENGTH*/
#define DELAY_TIME_BETWEEN_ITEMS_MS 1234 /*!< delay time between different test items */
#define I2C_SLAVE_SCL_IO 26 /*!<gpio number for i2c slave clock */
#define I2C_SLAVE_SDA_IO 25 /*!<gpio number for i2c slave data */
#define I2C_SLAVE_NUM I2C_NUM_0 /*!<I2C port number for slave dev */
#define I2C_SLAVE_TX_BUF_LEN (2*DATA_LENGTH) /*!<I2C slave tx buffer size */
#define I2C_SLAVE_RX_BUF_LEN (2*DATA_LENGTH) /*!<I2C slave rx buffer size */
#define I2C_MASTER_SCL_IO 19 /*!< gpio number for I2C master clock */
#define I2C_MASTER_SDA_IO 18 /*!< gpio number for I2C master data */
#define I2C_MASTER_NUM I2C_NUM_1 /*!< I2C port number for master dev */
#define I2C_MASTER_TX_BUF_DISABLE 0 /*!< I2C master do not need buffer */
#define I2C_MASTER_RX_BUF_DISABLE 0 /*!< I2C master do not need buffer */
#define I2C_MASTER_FREQ_HZ 100000 /*!< I2C master clock frequency */
#define BH1750_SENSOR_ADDR 0x23 /*!< slave address for BH1750 sensor */
#define BH1750_CMD_START 0x23 /*!< Command to set measure mode */
#define ESP_SLAVE_ADDR 0x28 /*!< ESP32 slave address, you can set any 7bit value */
#define WRITE_BIT I2C_MASTER_WRITE /*!< I2C master write */
#define READ_BIT I2C_MASTER_READ /*!< I2C master read */
#define ACK_CHECK_EN 0x1 /*!< I2C master will check ack from slave*/
#define ACK_CHECK_DIS 0x0 /*!< I2C master will not check ack from slave */
#define ACK_VAL 0x0 /*!< I2C ack value */
#define NACK_VAL 0x1 /*!< I2C nack value */
xSemaphoreHandle print_mux;
/**
* @brief test code to read esp-i2c-slave
* We need to fill the buffer of esp slave device, then master can read them out.
*
* _______________________________________________________________________________________
* | start | slave_addr + rd_bit +ack | read n-1 bytes + ack | read 1 byte + nack | stop |
* --------|--------------------------|----------------------|--------------------|------|
*
*/
esp_err_t i2c_master_read_slave(i2c_port_t i2c_num, uint8_t* data_rd, size_t size)
{
if (size == 0) {
return ESP_OK;
}
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, ( ESP_SLAVE_ADDR << 1 ) | READ_BIT, ACK_CHECK_EN);
if (size > 1) {
i2c_master_read(cmd, data_rd, size - 1, ACK_VAL);
}
i2c_master_read_byte(cmd, data_rd + size - 1, NACK_VAL);
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
return ret;
}
/**
* @brief Test code to write esp-i2c-slave
* Master device write data to slave(both esp32),
* the data will be stored in slave buffer.
* We can read them out from slave buffer.
*
* ___________________________________________________________________
* | start | slave_addr + wr_bit + ack | write n bytes + ack | stop |
* --------|---------------------------|----------------------|------|
*
*/
esp_err_t i2c_master_write_slave(i2c_port_t i2c_num, uint8_t* data_wr, size_t size)
{
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, ( ESP_SLAVE_ADDR << 1 ) | WRITE_BIT, ACK_CHECK_EN);
i2c_master_write(cmd, data_wr, size, ACK_CHECK_EN);
i2c_master_stop(cmd);
esp_err_t ret = i2c_master_cmd_begin(i2c_num, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
return ret;
}
/**
* @brief test code to write esp-i2c-slave
*
* 1. set mode
* _________________________________________________________________
* | start | slave_addr + wr_bit + ack | write 1 byte + ack | stop |
* --------|---------------------------|---------------------|------|
* 2. wait more than 24 ms
* 3. read data
* ______________________________________________________________________________________
* | start | slave_addr + rd_bit + ack | read 1 byte + ack | read 1 byte + nack | stop |
* --------|---------------------------|--------------------|--------------------|------|
*/
esp_err_t i2c_master_sensor_test(i2c_port_t i2c_num, uint8_t* data_h, uint8_t* data_l)
{
i2c_cmd_handle_t cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, BH1750_SENSOR_ADDR << 1 | WRITE_BIT, ACK_CHECK_EN);
i2c_master_write_byte(cmd, BH1750_CMD_START, ACK_CHECK_EN);
i2c_master_stop(cmd);
int ret = i2c_master_cmd_begin(i2c_num, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
if (ret == ESP_FAIL) {
return ret;
}
vTaskDelay(30 / portTICK_RATE_MS);
cmd = i2c_cmd_link_create();
i2c_master_start(cmd);
i2c_master_write_byte(cmd, BH1750_SENSOR_ADDR << 1 | READ_BIT, ACK_CHECK_EN);
i2c_master_read_byte(cmd, data_h, ACK_VAL);
i2c_master_read_byte(cmd, data_l, NACK_VAL);
i2c_master_stop(cmd);
ret = i2c_master_cmd_begin(i2c_num, cmd, 1000 / portTICK_RATE_MS);
i2c_cmd_link_delete(cmd);
if (ret == ESP_FAIL) {
return ESP_FAIL;
}
return ESP_OK;
}
/**
* @brief i2c master initialization
*/
void i2c_master_init()
{
int i2c_master_port = I2C_MASTER_NUM;
i2c_config_t conf;
conf.mode = I2C_MODE_MASTER;
conf.sda_io_num = I2C_MASTER_SDA_IO;
conf.sda_pullup_en = GPIO_PULLUP_ENABLE;
conf.scl_io_num = I2C_MASTER_SCL_IO;
conf.scl_pullup_en = GPIO_PULLUP_ENABLE;
conf.master.clk_speed = I2C_MASTER_FREQ_HZ;
i2c_param_config(i2c_master_port, &conf);
i2c_driver_install(i2c_master_port, conf.mode, I2C_MASTER_RX_BUF_DISABLE, I2C_MASTER_TX_BUF_DISABLE, 0);
}
/**
* @brief i2c slave initialization
*/
void i2c_slave_init()
{
int i2c_slave_port = I2C_SLAVE_NUM;
i2c_config_t conf_slave;
conf_slave.sda_io_num = I2C_SLAVE_SDA_IO;
conf_slave.sda_pullup_en = GPIO_PULLUP_ENABLE;
conf_slave.scl_io_num = I2C_SLAVE_SCL_IO;
conf_slave.scl_pullup_en = GPIO_PULLUP_ENABLE;
conf_slave.mode = I2C_MODE_SLAVE;
conf_slave.slave.addr_10bit_en = 0;
conf_slave.slave.slave_addr = ESP_SLAVE_ADDR;
i2c_param_config(i2c_slave_port, &conf_slave);
i2c_driver_install(i2c_slave_port, conf_slave.mode, I2C_SLAVE_RX_BUF_LEN, I2C_SLAVE_TX_BUF_LEN, 0);
}
/**
* @brief test function to show buffer
*/
void disp_buf(uint8_t* buf, int len)
{
int i;
for (i = 0; i < len; i++) {
printf("%02x ", buf[i]);
if (( i + 1 ) % 16 == 0) {
printf("\n");
}
}
printf("\n");
}
void i2c_test_task(void* arg)
{
int i = 0;
int ret;
uint32_t task_idx = (uint32_t) arg;
uint8_t* data = (uint8_t*) malloc(DATA_LENGTH);
uint8_t* data_wr = (uint8_t*) malloc(DATA_LENGTH);
uint8_t* data_rd = (uint8_t*) malloc(DATA_LENGTH);
uint8_t sensor_data_h, sensor_data_l;
while (1) {
ret = i2c_master_sensor_test( I2C_MASTER_NUM, &sensor_data_h, &sensor_data_l);
xSemaphoreTake(print_mux, portMAX_DELAY);
printf("*******************\n");
printf("TASK[%d] MASTER READ SENSOR( BH1750 )\n", task_idx);
printf("*******************\n");
if (ret == ESP_OK) {
printf("data_h: %02x\n", sensor_data_h);
printf("data_l: %02x\n", sensor_data_l);
printf("sensor val: %f\n", ( sensor_data_h << 8 | sensor_data_l ) / 1.2);
} else {
printf("No ack, sensor not connected...skip...\n");
}
xSemaphoreGive(print_mux);
vTaskDelay(( DELAY_TIME_BETWEEN_ITEMS_MS * ( task_idx + 1 ) ) / portTICK_RATE_MS);
//---------------------------------------------------
for (i = 0; i < DATA_LENGTH; i++) {
data[i] = i;
}
size_t d_size = i2c_slave_write_buffer(I2C_SLAVE_NUM, data, RW_TEST_LENGTH, 1000 / portTICK_RATE_MS);
if (d_size == 0) {
printf("i2c slave tx buffer full\n");
ret = i2c_master_read_slave(I2C_MASTER_NUM, data_rd, DATA_LENGTH);
} else {
ret = i2c_master_read_slave(I2C_MASTER_NUM, data_rd, RW_TEST_LENGTH);
}
xSemaphoreTake(print_mux, portMAX_DELAY);
printf("*******************\n");
printf("TASK[%d] MASTER READ FROM SLAVE\n", task_idx);
printf("*******************\n");
printf("====TASK[%d] Slave buffer data ====\n", task_idx);
disp_buf(data, d_size);
if (ret == ESP_OK) {
printf("====TASK[%d] Master read ====\n", task_idx);
disp_buf(data_rd, d_size);
} else {
printf("Master read slave error, IO not connected...\n");
}
xSemaphoreGive(print_mux);
vTaskDelay(( DELAY_TIME_BETWEEN_ITEMS_MS * ( task_idx + 1 ) ) / portTICK_RATE_MS);
//---------------------------------------------------
int size;
for (i = 0; i < DATA_LENGTH; i++) {
data_wr[i] = i + 10;
}
//we need to fill the slave buffer so that master can read later
ret = i2c_master_write_slave( I2C_MASTER_NUM, data_wr, RW_TEST_LENGTH);
if (ret == ESP_OK) {
size = i2c_slave_read_buffer( I2C_SLAVE_NUM, data, RW_TEST_LENGTH, 1000 / portTICK_RATE_MS);
}
xSemaphoreTake(print_mux, portMAX_DELAY);
printf("*******************\n");
printf("TASK[%d] MASTER WRITE TO SLAVE\n", task_idx);
printf("*******************\n");
printf("----TASK[%d] Master write ----\n", task_idx);
disp_buf(data_wr, RW_TEST_LENGTH);
if (ret == ESP_OK) {
printf("----TASK[%d] Slave read: [%d] bytes ----\n", task_idx, size);
disp_buf(data, size);
} else {
printf("TASK[%d] Master write slave error, IO not connected....\n", task_idx);
}
xSemaphoreGive(print_mux);
vTaskDelay(( DELAY_TIME_BETWEEN_ITEMS_MS * ( task_idx + 1 ) ) / portTICK_RATE_MS);
}
}
void app_main()
{
print_mux = xSemaphoreCreateMutex();
i2c_slave_init();
i2c_master_init();
xTaskCreate(i2c_test_task, "i2c_test_task_0", 1024 * 2, (void* ) 0, 10, NULL);
xTaskCreate(i2c_test_task, "i2c_test_task_1", 1024 * 2, (void* ) 1, 10, NULL);
}

View file

@ -11,11 +11,10 @@
EXAMPLE_NUM=1
RESULT=0
FAILED_EXAMPLES=""
RESULT_WARNINGS=22 # magic number result code for "warnings found"
set -e
for example in ${IDF_PATH}/examples/*; do
[ -f ${example}/Makefile ] || continue
echo "Building ${example} as ${EXAMPLE_NUM}..."
@ -30,16 +29,17 @@ for example in ${IDF_PATH}/examples/*; do
# build non-verbose first
BUILDLOG=$(mktemp -t examplebuild.XXXX.log)
(
set -o pipefail # so result of make all isn't lost when piping to tee
set -e
make clean defconfig
make all 2>&1 | tee $BUILDLOG
) || (RESULT=$?; make V=1) # only build verbose if there's an error
make $* all 2>&1 | tee $BUILDLOG
) || { RESULT=$?; FAILED_EXAMPLES+=" ${example}"; make V=1; } # only build verbose if there's an error
popd
EXAMPLE_NUM=$(( $EXAMPLE_NUM + 1 ))
if [ $RESULT -eq 0 ] && grep -q ": warning:" $BUILDLOG; then
echo "Build will fail, due to warnings in this example"
RESULT=$RESULT_WARNINGS
if grep -q ": warning:" $BUILDLOG; then
[ $RESULT -eq 0 ] && RESULT=$RESULT_WARNINGS
FAILED_EXAMPLES+=" ${example} (warnings)"
fi
rm -f $BUILDLOG
@ -49,5 +49,7 @@ if [ $RESULT -eq $RESULT_WARNINGS ]; then
echo "Build would have passed, except for warnings."
fi
[ $RESULT -eq 0 ] || echo "Failed examples: $FAILED_EXAMPLES"
exit $RESULT

View file

@ -30,6 +30,7 @@ help:
@echo "make clean - Remove all build output"
@echo "make size - Display the memory footprint of the app"
@echo "make erase_flash - Erase entire flash contents"
@echo "make monitor - Display serial output on terminal console"
@echo ""
@echo "make app - Build just the app"
@echo "make app-flash - Flash just the app"