IDF master c13afea63 (#5214)

esp-dsp: master 7cc5073
esp-face: master 420fc7e
esp-rainmaker: f1b82c7
esp32-camera: master 6f8489e
esp_littlefs: master b58f00c
This commit is contained in:
Me No Dev
2021-05-31 16:32:51 +03:00
committed by GitHub
parent 0db9e2f45b
commit a618fc1361
616 changed files with 11842 additions and 4932 deletions

View File

@ -15,7 +15,7 @@
#include <stdint.h>
#include "soc/cpu_caps.h"
#include "soc/soc_caps.h"
#include "esp_bit_defs.h"
#include "soc/assist_debug_reg.h"
#include "esp_attr.h"

View File

@ -24,7 +24,7 @@
#include <string.h>
#include "soc/hwcrypto_reg.h"
#include "soc/ds_caps.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
@ -69,7 +69,7 @@ static inline ds_key_check_t ds_ll_key_error_source(void)
*/
static inline void ds_ll_configure_iv(const uint32_t *iv)
{
for (size_t i = 0; i < (DS_KEY_PARAM_MD_IV_LENGTH / sizeof(uint32_t)); i++) {
for (size_t i = 0; i < (SOC_DS_KEY_PARAM_MD_IV_LENGTH / sizeof(uint32_t)); i++) {
REG_WRITE(DS_IV_BASE + (i * 4) , iv[i]);
}
}
@ -99,9 +99,9 @@ static inline void ds_ll_write_private_key_params(const uint8_t *encrypted_key_p
*/
typedef struct { uint32_t addr; size_t len; } frag_t;
const frag_t frags[] = {
{DS_C_Y_BASE, DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_M_BASE, DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_RB_BASE, DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_Y_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_M_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_RB_BASE, SOC_DS_SIGNATURE_MAX_BIT_LEN / 8},
{DS_C_BOX_BASE, DS_IV_BASE - DS_C_BOX_BASE},
};
const size_t NUM_FRAGS = sizeof(frags)/sizeof(frag_t);

View File

@ -17,7 +17,6 @@
#include <stdbool.h>
#include "soc/gdma_struct.h"
#include "soc/gdma_reg.h"
#include "soc/gdma_caps.h"
#ifdef __cplusplus
extern "C" {
@ -25,6 +24,9 @@ extern "C" {
#define GDMA_LL_GET_HW(id) (((id) == 0) ? (&GDMA) : NULL)
#define GDMA_LL_RX_EVENT_MASK (0x06A7)
#define GDMA_LL_TX_EVENT_MASK (0x1958)
#define GDMA_LL_EVENT_TX_FIFO_UDF (1<<12)
#define GDMA_LL_EVENT_TX_FIFO_OVF (1<<11)
#define GDMA_LL_EVENT_RX_FIFO_UDF (1<<10)
@ -47,40 +49,12 @@ static inline void gdma_ll_enable_m2m_mode(gdma_dev_t *dev, uint32_t channel, bo
{
dev->channel[channel].in.in_conf0.mem_trans_en = enable;
if (enable) {
// only have to give it a valid value
// to enable m2m mode, the tx chan has to be the same to rx chan, and set to a valid value
dev->channel[channel].in.in_peri_sel.sel = 0;
dev->channel[channel].out.out_peri_sel.sel = 0;
}
}
/**
* @brief Get DMA interrupt status word
*/
static inline uint32_t gdma_ll_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val;
}
/**
* @brief Enable DMA interrupt
*/
static inline void gdma_ll_enable_interrupt(gdma_dev_t *dev, uint32_t channel, uint32_t mask, bool enable)
{
if (enable) {
dev->intr[channel].ena.val |= mask;
} else {
dev->intr[channel].ena.val &= ~mask;
}
}
/**
* @brief Clear DMA interrupt
*/
static inline void gdma_ll_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = mask;
}
/**
* @brief Enable DMA clock gating
*/
@ -90,6 +64,42 @@ static inline void gdma_ll_enable_clock(gdma_dev_t *dev, bool enable)
}
///////////////////////////////////// RX /////////////////////////////////////////
/**
* @brief Get DMA RX channel interrupt status word
*/
static inline uint32_t gdma_ll_rx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_RX_EVENT_MASK;
}
/**
* @brief Enable DMA RX channel interrupt
*/
static inline void gdma_ll_rx_enable_interrupt(gdma_dev_t *dev, uint32_t channel, uint32_t mask, bool enable)
{
if (enable) {
dev->intr[channel].ena.val |= (mask & GDMA_LL_RX_EVENT_MASK);
} else {
dev->intr[channel].ena.val &= ~(mask & GDMA_LL_RX_EVENT_MASK);
}
}
/**
* @brief Clear DMA RX channel interrupt
*/
static inline void gdma_ll_rx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_RX_EVENT_MASK);
}
/**
* @brief Get DMA RX channel interrupt status register address
*/
static inline volatile void *gdma_ll_rx_get_interrupt_status_reg(gdma_dev_t *dev, uint32_t channel)
{
return (volatile void *)(&dev->intr[channel].st);
}
/**
* @brief Enable DMA RX channel to check the owner bit in the descriptor, disabled by default
*/
@ -248,6 +258,42 @@ static inline void gdma_ll_rx_connect_to_periph(gdma_dev_t *dev, uint32_t channe
}
///////////////////////////////////// TX /////////////////////////////////////////
/**
* @brief Get DMA TX channel interrupt status word
*/
static inline uint32_t gdma_ll_tx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_TX_EVENT_MASK;
}
/**
* @brief Enable DMA TX channel interrupt
*/
static inline void gdma_ll_tx_enable_interrupt(gdma_dev_t *dev, uint32_t channel, uint32_t mask, bool enable)
{
if (enable) {
dev->intr[channel].ena.val |= (mask & GDMA_LL_TX_EVENT_MASK);
} else {
dev->intr[channel].ena.val &= ~(mask & GDMA_LL_TX_EVENT_MASK);
}
}
/**
* @brief Clear DMA TX channel interrupt
*/
static inline void gdma_ll_tx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_TX_EVENT_MASK);
}
/**
* @brief Get DMA TX channel interrupt status register address
*/
static inline volatile void *gdma_ll_tx_get_interrupt_status_reg(gdma_dev_t *dev, uint32_t channel)
{
return (volatile void *)(&dev->intr[channel].st);
}
/**
* @brief Enable DMA TX channel to check the owner bit in the descriptor, disabled by default
*/

View File

@ -49,6 +49,16 @@ static inline void intr_cntrl_ll_disable_interrupts(uint32_t mask)
RV_SET_CSR(mstatus, old_mstatus & MSTATUS_MIE);
}
/**
* @brief Read the current interrupt mask of the CPU running this code.
*
* @return The current interrupt bitmask.
*/
static inline uint32_t intr_cntrl_ll_read_interrupt_mask(void)
{
return REG_READ(INTERRUPT_CORE0_CPU_INT_ENABLE_REG);
}
/**
* @brief checks if given interrupt number has a valid handler
*
@ -85,36 +95,6 @@ static inline void *intr_cntrl_ll_get_int_handler_arg(uint8_t intr)
return intr_handler_get_arg(intr);
}
/**
* @brief Disables interrupts that are not located in iram
*
* @param newmask mask of interrupts TO KEEP ENABLED (note: this is probably a bug, see IDF-2308)
* @return oldmask previous interrupt mask value
*/
static inline uint32_t intr_cntrl_ll_disable_int_mask(uint32_t newmask)
{
// Disable interrupts in order to atomically update the interrupt enable register
unsigned old_mstatus = RV_CLEAR_CSR(mstatus, MSTATUS_MIE);
uint32_t old_int_enable = REG_READ(INTERRUPT_CORE0_CPU_INT_ENABLE_REG);
REG_WRITE(INTERRUPT_CORE0_CPU_INT_ENABLE_REG, old_int_enable & newmask);
RV_SET_CSR(mstatus, old_mstatus & MSTATUS_MIE);
return old_int_enable;
}
/**
* @brief Enables interrupts that are not located in iram
*
* @param newmask mask of interrupts needs to be enabled
*/
static inline void intr_cntrl_ll_enable_int_mask(uint32_t newmask)
{
unsigned old_mstatus = RV_CLEAR_CSR(mstatus, MSTATUS_MIE);
esprv_intc_int_enable(newmask);
RV_SET_CSR(mstatus, old_mstatus & MSTATUS_MIE);
}
/**
* @brief Acknowledge an edge-trigger interrupt by clearing its pending flag
*

View File

@ -14,7 +14,7 @@
#include <stdint.h>
#include "soc/mpu_caps.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
@ -22,7 +22,7 @@ extern "C" {
/* This LL is currently unused for ESP32-C3 - cleanup is TODO ESP32-C3 IDF-2375 */
static inline uint32_t mpu_ll_id_to_addr(int id)
static inline uint32_t mpu_ll_id_to_addr(unsigned id)
{
abort();
}

View File

@ -0,0 +1,157 @@
// Copyright 2015-2021 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for SPI Flash Encryption.
#include "soc/system_reg.h"
#include "soc/hwcrypto_reg.h"
#include "soc/soc.h"
#include "string.h"
#include "assert.h"
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
/// Choose type of chip you want to encrypt manully
typedef enum
{
FLASH_ENCRYPTION_MANU = 0, ///!< Manually encrypt the flash chip.
PSRAM_ENCRYPTION_MANU = 1 ///!< Manually encrypt the psram chip.
} flash_encrypt_ll_type_t;
/**
* Enable the flash encryption function under spi boot mode and download boot mode.
*/
static inline void spi_flash_encrypt_ll_enable(void)
{
REG_SET_BIT(SYSTEM_EXTERNAL_DEVICE_ENCRYPT_DECRYPT_CONTROL_REG,
SYSTEM_ENABLE_DOWNLOAD_MANUAL_ENCRYPT |
SYSTEM_ENABLE_SPI_MANUAL_ENCRYPT);
}
/*
* Disable the flash encryption mode.
*/
static inline void spi_flash_encrypt_ll_disable(void)
{
REG_CLR_BIT(SYSTEM_EXTERNAL_DEVICE_ENCRYPT_DECRYPT_CONTROL_REG,
SYSTEM_ENABLE_SPI_MANUAL_ENCRYPT);
}
/**
* Choose type of chip you want to encrypt manully
*
* @param type The type of chip to be encrypted
*
* @note The hardware currently support flash encryption.
*/
static inline void spi_flash_encrypt_ll_type(flash_encrypt_ll_type_t type)
{
// Our hardware only support flash encryption
assert(type == FLASH_ENCRYPTION_MANU);
REG_WRITE(AES_XTS_DESTINATION_REG, type);
}
/**
* Configure the data size of a single encryption.
*
* @param block_size Size of the desired block.
*/
static inline void spi_flash_encrypt_ll_buffer_length(uint32_t size)
{
// Desired block should not be larger than the block size.
REG_WRITE(AES_XTS_SIZE_REG, size >> 5);
}
/**
* Save 32-bit piece of plaintext.
*
* @param address the address of written flash partition.
* @param buffer Buffer to store the input data.
* @param size Buffer size.
*
*/
static inline void spi_flash_encrypt_ll_plaintext_save(uint32_t address, const uint32_t* buffer, uint32_t size)
{
uint32_t plaintext_offs = (address % 64);
memcpy((void *)(AES_XTS_PLAIN_BASE + plaintext_offs), buffer, size);
}
/**
* Copy the flash address to XTS_AES physical address
*
* @param flash_addr flash address to write.
*/
static inline void spi_flash_encrypt_ll_address_save(uint32_t flash_addr)
{
REG_WRITE(AES_XTS_PHYSICAL_ADDR_REG, flash_addr);
}
/**
* Start flash encryption
*/
static inline void spi_flash_encrypt_ll_calculate_start(void)
{
REG_WRITE(AES_XTS_TRIGGER_REG, 1);
}
/**
* Wait for flash encryption termination
*/
static inline void spi_flash_encrypt_ll_calculate_wait_idle(void)
{
while(REG_READ(AES_XTS_STATE_REG) == 0x1) {
}
}
/**
* Finish the flash encryption and make encrypted result accessible to SPI.
*/
static inline void spi_flash_encrypt_ll_done(void)
{
REG_WRITE(AES_XTS_RELEASE_REG, 1);
while(REG_READ(AES_XTS_STATE_REG) != 0x3) {
}
}
/**
* Set to destroy encrypted result
*/
static inline void spi_flash_encrypt_ll_destroy(void)
{
REG_WRITE(AES_XTS_DESTROY_REG, 1);
}
/**
* Check if is qualified to encrypt the buffer
*
* @param address the address of written flash partition.
* @param length Buffer size.
*/
static inline bool spi_flash_encrypt_ll_check(uint32_t address, uint32_t length)
{
return ((address % length) == 0) ? true : false;
}
#ifdef __cplusplus
}
#endif

View File

@ -1005,7 +1005,7 @@ static inline void spi_ll_set_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
static inline void spi_ll_clear_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define CLR_INTR(intr_bit, _, __, clr_op) if (intr_mask & (intr_bit)) hw->clr_op;
#define CLR_INTR(intr_bit, _, __, clr_reg) if (intr_mask & (intr_bit)) hw->clr_reg;
FOR_EACH_ITEM(CLR_INTR, INTR_LIST);
#undef CLR_INTR
}

View File

@ -13,139 +13,150 @@
// limitations under the License.
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
#include "soc/systimer_struct.h"
#define SYSTIMER_LL_COUNTER_CLOCK (0) // Counter used for "wallclock" time
#define SYSTIMER_LL_COUNTER_OS_TICK (1) // Counter used for OS tick
#define SYSTIMER_LL_ALARM_OS_TICK_CORE0 (0) // Alarm used for OS tick of CPU core 0
#define SYSTIMER_LL_ALARM_CLOCK (2) // Alarm used for "wallclock" time
#define SYSTIMER_LL_TICKS_PER_US (16) // 16 systimer ticks == 1us
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "soc/soc.h"
#include "soc/systimer_reg.h"
// All these functions get invoked either from ISR or HAL that linked to IRAM.
// Always inline these functions even no gcc optimization is applied.
/*******************counter*************************/
/******************* Clock *************************/
__attribute__((always_inline)) static inline void systimer_ll_enable_clock(void)
__attribute__((always_inline)) static inline void systimer_ll_enable_clock(systimer_dev_t *dev, bool en)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_CONF_REG, SYS_TIMER_CLK_EN);
dev->conf.clk_en = en;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_counter(uint32_t counter_id)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_CONF_REG, 1 << (30 - counter_id));
}
/******************* Counter *************************/
__attribute__((always_inline)) static inline void systimer_ll_counter_can_stall_by_cpu(uint32_t counter_id, uint32_t cpu_id, bool can)
__attribute__((always_inline)) static inline void systimer_ll_enable_counter(systimer_dev_t *dev, uint32_t counter_id, bool en)
{
if (can) {
REG_SET_BIT(SYS_TIMER_SYSTIMER_CONF_REG, 1 << ((28 - counter_id * 2) - cpu_id));
if (en) {
dev->conf.val |= 1 << (30 - counter_id);
} else {
REG_CLR_BIT(SYS_TIMER_SYSTIMER_CONF_REG, 1 << ((28 - counter_id * 2) - cpu_id));
dev->conf.val &= ~(1 << (30 - counter_id));
}
}
__attribute__((always_inline)) static inline void systimer_ll_counter_snapshot(uint32_t counter_id)
__attribute__((always_inline)) static inline void systimer_ll_counter_can_stall_by_cpu(systimer_dev_t *dev, uint32_t counter_id, uint32_t cpu_id, bool can)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_UNIT0_OP_REG + 4 * counter_id, 1 << 30);
if (can) {
dev->conf.val |= 1 << ((28 - counter_id * 2) - cpu_id);
} else {
dev->conf.val &= ~(1 << ((28 - counter_id * 2) - cpu_id));
}
}
__attribute__((always_inline)) static inline bool systimer_ll_is_counter_value_valid(uint32_t counter_id)
__attribute__((always_inline)) static inline void systimer_ll_counter_snapshot(systimer_dev_t *dev, uint32_t counter_id)
{
return REG_GET_BIT(SYS_TIMER_SYSTIMER_UNIT0_OP_REG + 4 * counter_id, 1 << 29);
dev->unit_op[counter_id].timer_unit_update = 1;
}
__attribute__((always_inline)) static inline void systimer_ll_set_counter_value(uint32_t counter_id, uint64_t value)
__attribute__((always_inline)) static inline bool systimer_ll_is_counter_value_valid(systimer_dev_t *dev, uint32_t counter_id)
{
REG_WRITE(SYS_TIMER_SYSTIMER_UNIT0_LOAD_LO_REG + 8 * counter_id, value & 0xFFFFFFFF);
REG_WRITE(SYS_TIMER_SYSTIMER_UNIT0_LOAD_HI_REG, (value >> 32) & 0xFFFFF);
return dev->unit_op[counter_id].timer_unit_value_valid;
}
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_low(uint32_t counter_id)
__attribute__((always_inline)) static inline void systimer_ll_set_counter_value(systimer_dev_t *dev, uint32_t counter_id, uint64_t value)
{
return REG_READ(SYS_TIMER_SYSTIMER_UNIT0_VALUE_LO_REG + 8 * counter_id);
dev->unit_load_val[counter_id].hi.timer_unit_load_hi = value >> 32;
dev->unit_load_val[counter_id].lo.timer_unit_load_lo = value & 0xFFFFFFFF;
}
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_high(uint32_t counter_id)
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_low(systimer_dev_t *dev, uint32_t counter_id)
{
return REG_READ(SYS_TIMER_SYSTIMER_UNIT0_VALUE_HI_REG + 8 * counter_id);
return dev->unit_val[counter_id].lo.timer_unit_value_lo;
}
__attribute__((always_inline)) static inline void systimer_ll_apply_counter_value(uint32_t counter_id)
__attribute__((always_inline)) static inline uint32_t systimer_ll_get_counter_value_high(systimer_dev_t *dev, uint32_t counter_id)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_UNIT0_LOAD_REG + 4 * counter_id, SYS_TIMER_TIMER_UNIT0_LOAD);
return dev->unit_val[counter_id].hi.timer_unit_value_hi;
}
/*******************alarm*************************/
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_target(uint32_t alarm_id, uint64_t value)
__attribute__((always_inline)) static inline void systimer_ll_apply_counter_value(systimer_dev_t *dev, uint32_t counter_id)
{
REG_WRITE(SYS_TIMER_SYSTIMER_TARGET0_LO_REG + alarm_id * 8, value & 0xFFFFFFFF);
REG_WRITE(SYS_TIMER_SYSTIMER_TARGET0_HI_REG + alarm_id * 8, (value >> 32) & 0xFFFFF);
dev->unit_load[counter_id].val = 0x01;
}
__attribute__((always_inline)) static inline uint64_t systimer_ll_get_alarm_target(uint32_t alarm_id)
/******************* Alarm *************************/
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_target(systimer_dev_t *dev, uint32_t alarm_id, uint64_t value)
{
return ((uint64_t) REG_READ(SYS_TIMER_SYSTIMER_TARGET0_HI_REG + alarm_id * 8) << 32) \
| REG_READ(SYS_TIMER_SYSTIMER_TARGET0_LO_REG + alarm_id * 8);
dev->target_val[alarm_id].hi.timer_target_hi = value >> 32;
dev->target_val[alarm_id].lo.timer_target_lo = value & 0xFFFFFFFF;
}
__attribute__((always_inline)) static inline void systimer_ll_connect_alarm_counter(uint32_t alarm_id, uint32_t counter_id)
__attribute__((always_inline)) static inline uint64_t systimer_ll_get_alarm_target(systimer_dev_t *dev, uint32_t alarm_id)
{
REG_SET_FIELD(SYS_TIMER_SYSTIMER_TARGET0_CONF_REG + 4 * alarm_id, SYS_TIMER_TARGET0_TIMER_UNIT_SEL, counter_id);
return ((uint64_t)(dev->target_val[alarm_id].hi.timer_target_hi) << 32) | dev->target_val[alarm_id].lo.timer_target_lo;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_oneshot(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_connect_alarm_counter(systimer_dev_t *dev, uint32_t alarm_id, uint32_t counter_id)
{
REG_CLR_BIT(SYS_TIMER_SYSTIMER_TARGET0_CONF_REG + alarm_id * 4, SYS_TIMER_TARGET0_PERIOD_MODE);
dev->target_conf[alarm_id].target_timer_unit_sel = counter_id;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_period(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_oneshot(systimer_dev_t *dev, uint32_t alarm_id)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_TARGET0_CONF_REG + alarm_id * 4, SYS_TIMER_TARGET0_PERIOD_MODE);
dev->target_conf[alarm_id].target_period_mode = 0;
}
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_period(uint32_t alarm_id, uint32_t period)
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_period(systimer_dev_t *dev, uint32_t alarm_id)
{
REG_SET_FIELD(SYS_TIMER_SYSTIMER_TARGET0_CONF_REG + alarm_id * 4, SYS_TIMER_TARGET0_PERIOD, period);
dev->target_conf[alarm_id].target_period_mode = 1;
}
__attribute__((always_inline)) static inline void systimer_ll_apply_alarm_value(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_set_alarm_period(systimer_dev_t *dev, uint32_t alarm_id, uint32_t period)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_COMP0_LOAD_REG + alarm_id * 4, SYS_TIMER_TIMER_COMP0_LOAD);
assert(period < (1 << 26));
dev->target_conf[alarm_id].target_period = period;
}
__attribute__((always_inline)) static inline void systimer_ll_disable_alarm(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_apply_alarm_value(systimer_dev_t *dev, uint32_t alarm_id)
{
REG_CLR_BIT(SYS_TIMER_SYSTIMER_CONF_REG, 1 << (24 - alarm_id));
dev->comp_load[alarm_id].val = 0x01;
}
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm(systimer_dev_t *dev, uint32_t alarm_id, bool en)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_CONF_REG, 1 << (24 - alarm_id));
if (en) {
dev->conf.val |= 1 << (24 - alarm_id);
} else {
dev->conf.val &= ~(1 << (24 - alarm_id));
}
}
/*******************interrupt*************************/
/******************* Interrupt *************************/
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_int(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_enable_alarm_int(systimer_dev_t *dev, uint32_t alarm_id, bool en)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_INT_ENA_REG, 1 << alarm_id);
if (en) {
dev->int_ena.val |= 1 << alarm_id;
} else {
dev->int_ena.val &= ~(1 << alarm_id);
}
}
__attribute__((always_inline)) static inline void systimer_ll_disable_alarm_int(uint32_t alarm_id)
__attribute__((always_inline)) static inline bool systimer_ll_is_alarm_int_fired(systimer_dev_t *dev, uint32_t alarm_id)
{
REG_CLR_BIT(SYS_TIMER_SYSTIMER_INT_ENA_REG, 1 << alarm_id);
return dev->int_st.val & (1 << alarm_id);
}
__attribute__((always_inline)) static inline bool systimer_ll_is_alarm_int_fired(uint32_t alarm_id)
__attribute__((always_inline)) static inline void systimer_ll_clear_alarm_int(systimer_dev_t *dev, uint32_t alarm_id)
{
return REG_GET_BIT(SYS_TIMER_SYSTIMER_INT_RAW_REG, 1 << alarm_id);
}
__attribute__((always_inline)) static inline void systimer_ll_clear_alarm_int(uint32_t alarm_id)
{
REG_SET_BIT(SYS_TIMER_SYSTIMER_INT_CLR_REG, 1 << alarm_id);
dev->int_clr.val |= 1 << alarm_id;
}
#ifdef __cplusplus

View File

@ -32,6 +32,9 @@ extern "C" {
#define UART_LL_MIN_WAKEUP_THRESH (2)
#define UART_LL_INTR_MASK (0x7ffff) //All interrupt mask
#define UART_LL_FSM_IDLE (0x0)
#define UART_LL_FSM_TX_WAIT_SEND (0xf)
// Define UART interrupts
typedef enum {
UART_INTR_RXFIFO_FULL = (0x1 << 0),

View File

@ -20,12 +20,16 @@
#include <stdio.h>
#include "uhci_types.h"
#include "soc/uhci_struct.h"
#include "soc/gdma_struct.h"
#define UHCI_DMA_INDEX 0
#define UHCI_LL_GET_HW(num) (((num) == 0) ? (&UHCI0) : (NULL))
typedef enum {
UHCI_RX_BREAK_CHR_EOF = 0x1,
UHCI_RX_IDLE_EOF = 0x2,
UHCI_RX_LEN_EOF = 0x4,
UHCI_RX_EOF_MAX = 0x7,
} uhci_rxeof_cfg_t;
static inline void uhci_ll_init(uhci_dev_t *hw)
{
typeof(hw->conf0) conf0_reg;
@ -38,7 +42,8 @@ static inline void uhci_ll_init(uhci_dev_t *hw)
static inline void uhci_ll_attach_uart_port(uhci_dev_t *hw, int uart_num)
{
abort(); // TODO ESP32-C3 IDF-2117
hw->conf0.uart0_ce = (uart_num == 0)? 1: 0;
hw->conf0.uart1_ce = (uart_num == 1)? 1: 0;
}
static inline void uhci_ll_set_seper_chr(uhci_dev_t *hw, uhci_seper_chr_t *seper_char)
@ -90,20 +95,6 @@ static inline void uhci_ll_set_swflow_ctrl_sub_chr(uhci_dev_t *hw, uhci_swflow_c
hw->escape_conf.val = escape_conf_reg.val;
}
static inline void uhci_ll_dma_in_reset(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].in.in_conf0.in_rst = 1;
GDMA.channel[UHCI_DMA_INDEX].in.in_conf0.in_rst = 0;
}
static inline void uhci_ll_dma_out_reset(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].out.out_conf0.out_rst = 1;
GDMA.channel[UHCI_DMA_INDEX].out.out_conf0.out_rst = 0;
}
static inline void uhci_ll_enable_intr(uhci_dev_t *hw, uint32_t intr_mask)
{
hw->int_ena.val |= intr_mask;
@ -124,41 +115,6 @@ static inline uint32_t uhci_ll_get_intr(uhci_dev_t *hw)
return hw->int_st.val;
}
static inline void uhci_ll_set_rx_dma(uhci_dev_t *hw, uint32_t addr)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].in.in_link.addr = addr;
}
static inline void uhci_ll_set_tx_dma(uhci_dev_t *hw, uint32_t addr)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].out.out_link.addr = addr;
}
static inline void uhci_ll_rx_dma_start(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].in.in_link.start = 1;
}
static inline void uhci_ll_tx_dma_start(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].out.out_link.start = 1;
}
static inline void uhci_ll_rx_dma_stop(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].in.in_link.stop = 1;
}
static inline void uhci_ll_tx_dma_stop(uhci_dev_t *hw)
{
(void)hw;
GDMA.channel[UHCI_DMA_INDEX].out.out_link.stop = 1;
}
static inline void uhci_ll_set_eof_mode(uhci_dev_t *hw, uint32_t eof_mode)
{

View File

@ -0,0 +1,54 @@
// Copyright 2015-2019 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.
// Though the UHCI driver hasn't been published, some types are defined here
// for users to develop over the HAL. See example: controller_hci_uart_esp32c3
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
/**
* @brief UHCI escape sequence
*/
typedef struct {
uint8_t seper_chr; /*!< escape sequence character */
uint8_t sub_chr1; /*!< escape sequence sub-character 1 */
uint8_t sub_chr2; /*!< escape sequence sub-character 2 */
bool sub_chr_en; /*!< enable use of sub-chaacter of escape sequence */
} uhci_seper_chr_t;
/**
* @brief UHCI software flow control
*/
typedef struct {
uint8_t xon_chr; /*!< character for XON */
uint8_t xon_sub1; /*!< sub-character 1 for XON */
uint8_t xon_sub2; /*!< sub-character 2 for XON */
uint8_t xoff_chr; /*!< character 2 for XOFF */
uint8_t xoff_sub1; /*!< sub-character 1 for XOFF */
uint8_t xoff_sub2; /*!< sub-character 2 for XOFF */
uint8_t flow_en; /*!< enable use of software flow control */
} uhci_swflow_ctrl_sub_chr_t;
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,169 @@
// Copyright 2021 Espressif Systems (Shanghai)
//
// 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.
// The LL layer of the USB-serial-jtag controller
#pragma once
#include "soc/usb_serial_jtag_reg.h"
#include "soc/usb_serial_jtag_struct.h"
#ifdef __cplusplus
extern "C" {
#endif
//The in and out endpoints are this long.
#define USB_SERIAL_JTAG_PACKET_SZ_BYTES 64
#define USB_SERIAL_JTAG_LL_INTR_MASK (0x7ffff) //All interrupt mask
// Define USB_SERIAL_JTAG interrupts
// Note the hardware has more interrupts, but they're only useful for debugging
// the hardware.
typedef enum {
USB_SERIAL_JTAG_INTR_SOF = (1 << 1),
USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT = (1 << 2),
USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY = (1 << 3),
USB_SERIAL_JTAG_INTR_TOKEN_REC_IN_EP1 = (1 << 8),
USB_SERIAL_JTAG_INTR_BUS_RESET = (1 << 9),
USB_SERIAL_JTAG_INTR_EP1_ZERO_PAYLOAD = (1 << 10),
} usb_serial_jtag_intr_t;
/**
* @brief Enable the USB_SERIAL_JTAG interrupt based on the given mask.
*
* @param mask The bitmap of the interrupts need to be enabled.
*
* @return None
*/
static inline void usb_serial_jtag_ll_ena_intr_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_ena.val |= mask;
}
/**
* @brief Disable the USB_SERIAL_JTAG interrupt based on the given mask.
*
* @param mask The bitmap of the interrupts need to be disabled.
*
* @return None
*/
static inline void usb_serial_jtag_ll_disable_intr_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_ena.val &= (~mask);
}
/**
* @brief Get the USB_SERIAL_JTAG interrupt status.
*
* @return The USB_SERIAL_JTAG interrupt status.
*/
static inline uint32_t usb_serial_jtag_ll_get_intsts_mask(void)
{
return USB_SERIAL_JTAG.int_st.val;
}
/**
* @brief Clear the USB_SERIAL_JTAG interrupt status based on the given mask.
*
* @param mask The bitmap of the interrupts need to be cleared.
*
* @return None
*/
static inline void usb_serial_jtag_ll_clr_intsts_mask(uint32_t mask)
{
USB_SERIAL_JTAG.int_clr.val = mask;
}
/**
* @brief Get status of enabled interrupt.
*
* @return interrupt enable value
*/
static inline uint32_t usb_serial_jtag_ll_get_intr_ena_status(void)
{
return USB_SERIAL_JTAG.int_ena.val;
}
/**
* @brief Read the bytes from the USB_SERIAL_JTAG rxfifo.
*
* @param buf The data buffer.
* @param rd_len The data length needs to be read.
*
* @return amount of bytes read
*/
static inline int usb_serial_jtag_ll_read_rxfifo(uint8_t *buf, uint32_t rd_len)
{
int i;
for (i = 0; i < (int)rd_len; i++) {
if (!USB_SERIAL_JTAG.ep1_conf.serial_out_ep_data_avail) break;
buf[i] = USB_SERIAL_JTAG.ep1.rdwr_byte;
}
return i;
}
/**
* @brief Write byte to the USB_SERIAL_JTAG txfifo. Only writes bytes as long / if there
* is room in the buffer.
*
* @param buf The data buffer.
* @param wr_len The data length needs to be writen.
*
* @return Amount of bytes actually written. May be less than wr_len.
*/
static inline int usb_serial_jtag_ll_write_txfifo(const uint8_t *buf, uint32_t wr_len)
{
int i;
for (i = 0; i < (int)wr_len; i++) {
if (!USB_SERIAL_JTAG.ep1_conf.serial_in_ep_data_free) break;
USB_SERIAL_JTAG.ep1.rdwr_byte = buf[i];
}
return i;
}
/**
* @brief Returns 1 if the USB_SERIAL_JTAG rxfifo has data available.
*
* @return 0 if no data available, 1 if data available
*/
static inline int usb_serial_jtag_ll_rxfifo_data_available(void)
{
return USB_SERIAL_JTAG.ep1_conf.serial_out_ep_data_avail;
}
/**
* @brief Returns 1 if the USB_SERIAL_JTAG txfifo has room.
*
* @return 0 if no data available, 1 if data available
*/
static inline int usb_serial_jtag_ll_txfifo_writable(void)
{
return USB_SERIAL_JTAG.ep1_conf.serial_in_ep_data_free;
}
/**
* @brief Flushes the TX buffer, that is, make it available for the
* host to pick up.
*
* @return na
*/
static inline void usb_serial_jtag_ll_txfifo_flush(void)
{
USB_SERIAL_JTAG.ep1_conf.wr_done=1;
}
#ifdef __cplusplus
}
#endif

View File

@ -60,11 +60,6 @@ void ds_hal_start(void);
*/
void ds_hal_finish(void);
/**
* @brief Check whether the key input (HMAC on ESP32-C3) is correct.
*/
ds_key_check_t ds_hal_check_decryption_key(void);
/**
* @brief Write the initialization vector.
*/

View File

@ -76,6 +76,9 @@ typedef enum {
#define GPIO_SEL_44 ((uint64_t)(((uint64_t)1)<<44)) /*!< Pin 44 selected */
#define GPIO_SEL_45 ((uint64_t)(((uint64_t)1)<<45)) /*!< Pin 45 selected */
#define GPIO_SEL_46 ((uint64_t)(((uint64_t)1)<<46)) /*!< Pin 46 selected */
#if CONFIG_IDF_TARGET_ESP32S3
#define GPIO_SEL_47 ((uint64_t)(((uint64_t)1)<<47)) /*!< Pin 47 selected */
#endif
#endif
#define GPIO_PIN_REG_0 IO_MUX_GPIO0_REG
@ -125,6 +128,7 @@ typedef enum {
#define GPIO_PIN_REG_44 IO_MUX_GPIO44_REG
#define GPIO_PIN_REG_45 IO_MUX_GPIO45_REG
#define GPIO_PIN_REG_46 IO_MUX_GPIO46_REG
#define GPIO_PIN_REG_47 IO_MUX_GPIO47_REG
#if CONFIG_IDF_TARGET_ESP32
typedef enum {

View File

@ -135,6 +135,16 @@ static inline void interrupt_controller_hal_disable_interrupts(uint32_t mask)
intr_cntrl_ll_disable_interrupts(mask);
}
/**
* @brief Read the current interrupt mask.
*
* @return The bitmask of current interrupts
*/
static inline uint32_t interrupt_controller_hal_read_interrupt_mask(void)
{
return intr_cntrl_ll_read_interrupt_mask();
}
/**
* @brief checks if given interrupt number has a valid handler
*
@ -171,27 +181,6 @@ static inline void * interrupt_controller_hal_get_int_handler_arg(uint8_t intr)
return intr_cntrl_ll_get_int_handler_arg(intr);
}
/**
* @brief Disables interrupts that are not located in iram
*
* @param newmask mask of interrupts needs to be disabled
* @return oldmask where to store old interrupts state
*/
static inline uint32_t interrupt_controller_hal_disable_int_mask(uint32_t newmask)
{
return intr_cntrl_ll_disable_int_mask(newmask);
}
/**
* @brief Enables interrupts that are not located in iram
*
* @param newmask mask of interrupts needs to be disabled
*/
static inline void interrupt_controller_hal_enable_int_mask(uint32_t newmask)
{
intr_cntrl_ll_enable_int_mask(newmask);
}
/**
* @brief Acknowledge an edge-trigger interrupt by clearing its pending flag
*

View File

@ -134,6 +134,10 @@ typedef struct {
ledc_timer_t timer_sel; /*!< Select the timer source of channel (0 - 3) */
uint32_t duty; /*!< LEDC channel duty, the range of duty setting is [0, (2**duty_resolution)] */
int hpoint; /*!< LEDC channel hpoint value, the max value is 0xfffff */
struct {
unsigned int output_invert: 1;/*!< Enable (1) or disable (0) gpio output invert */
} flags; /*!< LEDC flags */
} ledc_channel_config_t;
/**

View File

@ -0,0 +1,62 @@
// Copyright 2021 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.
/*******************************************************************************
* NOTICE
* The HAL is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The HAL layer for SPI Flash Encryption
#include "hal/spi_flash_encrypted_ll.h"
/**
* @brief Enable the flash encryption
*/
void spi_flash_encryption_hal_enable(void);
/**
* @brief Disable the flash encryption
*/
void spi_flash_encryption_hal_disable(void);
/**
* Prepare flash encryption before operation.
*
* @param address The destination address in flash for the write operation.
* @param buffer Data for programming
* @param size Size to program.
*
* @note address and buffer must be 8-word aligned.
*/
void spi_flash_encryption_hal_prepare(uint32_t address, const uint32_t* buffer, uint32_t size);
/**
* @brief flash data encryption operation is done.
*/
void spi_flash_encryption_hal_done(void);
/**
* Destroy encrypted result
*/
void spi_flash_encryption_hal_destroy(void);
/**
* Check if is qualified to encrypt the buffer
*
* @param address the address of written flash partition.
* @param length Buffer size.
*/
bool spi_flash_encryption_hal_check(uint32_t address, uint32_t length);

View File

@ -86,6 +86,44 @@ typedef struct {
};
} spi_flash_sus_cmd_conf;
/// Structure for flash encryption operations.
typedef struct
{
/**
* @brief Enable the flash encryption
*/
void (*flash_encryption_enable)(void);
/**
* @brief Disable the flash encryption
*/
void (*flash_encryption_disable)(void);
/**
* Prepare flash encryption before operation.
*
* @param address The destination address in flash for the write operation.
* @param buffer Data for programming
* @param size Size to program.
*
* @note address and buffer must be 8-word aligned.
*/
void (*flash_encryption_data_prepare)(uint32_t address, const uint32_t* buffer, uint32_t size);
/**
* @brief flash data encryption operation is done.
*/
void (*flash_encryption_done)(void);
/**
* Destroy encrypted result
*/
void (*flash_encryption_destroy)(void);
/**
* Check if is qualified to encrypt the buffer
*
* @param address the address of written flash partition.
* @param length Buffer size.
*/
bool (*flash_encryption_check)(uint32_t address, uint32_t length);
} spi_flash_encryption_t;
///Slowest io mode supported by ESP32, currently SlowRd
#define SPI_FLASH_READ_MODE_MIN SPI_FLASH_SLOWRD

View File

@ -31,13 +31,17 @@ typedef enum {
/// SPI Events
typedef enum {
SPI_EV_BUF_TX = BIT(0), ///< The buffer has sent data to master, Slave HD only
SPI_EV_BUF_RX = BIT(1), ///< The buffer has received data from master, Slave HD only
SPI_EV_SEND = BIT(2), ///< Slave has loaded some data to DMA, and master has received certain number of the data, the number is determined by master. Slave HD only
SPI_EV_RECV = BIT(3), ///< Slave has received certain number of data from master, the number is determined by master. Slave HD only.
SPI_EV_CMD9 = BIT(4), ///< Received CMD9 from master, Slave HD only
SPI_EV_CMDA = BIT(5), ///< Received CMDA from master, Slave HD only
SPI_EV_TRANS = BIT(6), ///< A transaction has done
/* Slave HD Only */
SPI_EV_BUF_TX = BIT(0), ///< The buffer has sent data to master.
SPI_EV_BUF_RX = BIT(1), ///< The buffer has received data from master.
SPI_EV_SEND_DMA_READY = BIT(2), ///< Slave has loaded its TX data buffer to the hardware (DMA).
SPI_EV_SEND = BIT(3), ///< Master has received certain number of the data, the number is determined by Master.
SPI_EV_RECV_DMA_READY = BIT(4), ///< Slave has loaded its RX data buffer to the hardware (DMA).
SPI_EV_RECV = BIT(5), ///< Slave has received certain number of data from master, the number is determined by Master.
SPI_EV_CMD9 = BIT(6), ///< Received CMD9 from master.
SPI_EV_CMDA = BIT(7), ///< Received CMDA from master.
/* Common Event */
SPI_EV_TRANS = BIT(8), ///< A transaction has done
} spi_event_t;
FLAG_ATTR(spi_event_t)

View File

@ -14,78 +14,91 @@
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include "soc/soc_caps.h"
#include "soc/systimer_struct.h"
#include "hal/systimer_types.h"
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "hal/systimer_types.h"
/**
* @brief enable systimer counter
*/
void systimer_hal_enable_counter(systimer_counter_id_t counter_id);
/**
* @brief get current counter value
*/
uint64_t systimer_hal_get_counter_value(systimer_counter_id_t counter_id);
/**
* @brief get current time (in microseconds)
*/
uint64_t systimer_hal_get_time(systimer_counter_id_t counter_id);
/*
* @brief set alarm target value (used in one-shot mode)
*/
void systimer_hal_set_alarm_target(systimer_alarm_id_t alarm_id, uint64_t target);
/**
* @brief set alarm period value (used in period mode)
*/
void systimer_hal_set_alarm_period(systimer_alarm_id_t alarm_id, uint32_t period);
/**
* @brief get alarm time
*/
uint64_t systimer_hal_get_alarm_value(systimer_alarm_id_t alarm_id);
/**
* @brief enable alarm interrupt
*/
void systimer_hal_enable_alarm_int(systimer_alarm_id_t alarm_id);
/**
* @brief select alarm mode
*/
void systimer_hal_select_alarm_mode(systimer_alarm_id_t alarm_id, systimer_alarm_mode_t mode);
/**
* @brief update systimer step when apb clock gets changed
*/
void systimer_hal_on_apb_freq_update(uint32_t apb_ticks_per_us);
/**
* @brief move systimer counter value forward or backward
*/
void systimer_hal_counter_value_advance(systimer_counter_id_t counter_id, int64_t time_us);
typedef struct {
systimer_dev_t *dev;
} systimer_hal_context_t;
/**
* @brief initialize systimer in HAL layer
*/
void systimer_hal_init(void);
void systimer_hal_init(systimer_hal_context_t *hal);
/**
* @brief enable systimer counter
*/
void systimer_hal_enable_counter(systimer_hal_context_t *hal, uint32_t counter_id);
/**
* @brief get current counter value
*/
uint64_t systimer_hal_get_counter_value(systimer_hal_context_t *hal, uint32_t counter_id);
/**
* @brief get current time (in microseconds)
*/
uint64_t systimer_hal_get_time(systimer_hal_context_t *hal, uint32_t counter_id);
/*
* @brief set alarm target value (used in one-shot mode)
*/
void systimer_hal_set_alarm_target(systimer_hal_context_t *hal, uint32_t alarm_id, uint64_t target);
/**
* @brief set alarm period value (used in period mode)
*/
void systimer_hal_set_alarm_period(systimer_hal_context_t *hal, uint32_t alarm_id, uint32_t period);
/**
* @brief get alarm time
*/
uint64_t systimer_hal_get_alarm_value(systimer_hal_context_t *hal, uint32_t alarm_id);
/**
* @brief enable alarm interrupt
*/
void systimer_hal_enable_alarm_int(systimer_hal_context_t *hal, uint32_t alarm_id);
/**
* @brief select alarm mode
*/
void systimer_hal_select_alarm_mode(systimer_hal_context_t *hal, uint32_t alarm_id, systimer_alarm_mode_t mode);
/**
* @brief update systimer step when apb clock gets changed
*/
void systimer_hal_on_apb_freq_update(systimer_hal_context_t *hal, uint32_t apb_ticks_per_us);
/**
* @brief move systimer counter value forward or backward
*/
void systimer_hal_counter_value_advance(systimer_hal_context_t *hal, uint32_t counter_id, int64_t time_us);
/**
* @brief connect alarm unit to selected counter
*/
void systimer_hal_connect_alarm_counter(systimer_alarm_id_t alarm_id, systimer_counter_id_t counter_id);
void systimer_hal_connect_alarm_counter(systimer_hal_context_t *hal, uint32_t alarm_id, uint32_t counter_id);
/**
* @brief set if a counter should be stalled when CPU is halted by the debugger
*/
void systimer_hal_counter_can_stall_by_cpu(uint32_t counter_id, uint32_t cpu_id, bool can);
void systimer_hal_counter_can_stall_by_cpu(systimer_hal_context_t *hal, uint32_t counter_id, uint32_t cpu_id, bool can);
#if !SOC_SYSTIMER_FIXED_TICKS_US
/**
* @brief set increase steps for systimer counter on different clock source
*/
void systimer_hal_set_steps_per_tick(systimer_hal_context_t *hal, int clock_source, uint32_t steps);
#endif
#ifdef __cplusplus
}

View File

@ -14,13 +14,13 @@
#pragma once
#include <stdint.h>
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include "soc/soc_caps.h"
/*
* @brief The structure of the counter value in systimer
*
@ -39,27 +39,6 @@ typedef struct {
_Static_assert(sizeof(systimer_counter_value_t) == 8, "systimer_counter_value_t should occupy 8 bytes in memory");
/** @endcond */
/**
* @brief systimer counter ID
*
*/
typedef enum {
SYSTIMER_COUNTER_0, /*!< systimer counter 0 */
#if SOC_SYSTIMER_COUNTER_NUM > 1
SYSTIMER_COUNTER_1, /*!< systimer counter 1 */
#endif
} systimer_counter_id_t;
/**
* @brief systimer alarm ID
*
*/
typedef enum {
SYSTIMER_ALARM_0, /*!< systimer alarm 0 */
SYSTIMER_ALARM_1, /*!< systimer alarm 1 */
SYSTIMER_ALARM_2, /*!< systimer alarm 2 */
} systimer_alarm_id_t;
/**
* @brief systimer alarm mode
*

View File

@ -1,452 +0,0 @@
// Copyright 2015-2020 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.
#pragma once
#ifdef __cplusplus
extern "C"
{
#endif
#include <stdint.h>
#define USB_CTRL_REQ_ATTR __attribute__((packed))
#define USB_DESC_ATTR __attribute__((packed))
/* -----------------------------------------------------------------------------
------------------------------- Common USB Types -------------------------------
----------------------------------------------------------------------------- */
// ----------------------------- Device Related --------------------------------
/**
* @brief Enumeration of USB PHY type
*/
typedef enum {
USB_PHY_INTERNAL = 0, /**< Use the chip's internal USB PHY */
USB_PHY_EXTERNAL, /**< Use an external USB PHY */
} usb_phy_t;
// ------------------------------ Bus Related ----------------------------------
/**
* @brief USB Standard Speeds
*/
typedef enum {
USB_SPEED_LOW = 0, /**< USB Low Speed (1.5 Mbit/s) */
USB_SPEED_FULL, /**< USB Full Speed (12 Mbit/s) */
} usb_speed_t;
// ---------------------------- Transfer Related -------------------------------
/**
* @brief The type of USB transfer
*
* @note The enum values need to match the bmAttributes field of an EP descriptor
*/
typedef enum {
USB_XFER_TYPE_CTRL = 0,
USB_XFER_TYPE_ISOCHRONOUS,
USB_XFER_TYPE_BULK,
USB_XFER_TYPE_INTR,
} usb_xfer_type_t;
/**
* @brief The status of a particular transfer
*/
typedef enum {
USB_TRANSFER_STATUS_COMPLETED, /**< The transfer was successful (but may be short) */
USB_TRANSFER_STATUS_ERROR, /**< The transfer failed because due to excessive errors (e.g. no response or CRC error) */
USB_TRANSFER_STATUS_TIMED_OUT, /**< The transfer failed due to to a time out */
USB_TRANSFER_STATUS_CANCELLED, /**< The transfer was cancelled */
USB_TRANSFER_STATUS_STALL, /**< The transfer was stalled */
USB_TRANSFER_STATUS_NO_DEVICE, /**< The transfer failed because the device is no longer valid (e.g., disconencted */
USB_TRANSFER_STATUS_OVERFLOW, /**< The transfer as more data was sent than was requested */
} usb_transfer_status_t;
/**
* @brief Isochronous packet descriptor
*
* If the number of bytes in an IRP transfer is larger than the MPS of the
* endpoint, the IRP is split over multiple packets (one packet per bInterval
* of the endpoint). An array of Isochronous packet descriptos describes how
* an IRP should be split over multiple packets.
*/
typedef struct {
int length; /**< Number of bytes to transmit/receive in the packet */
int actual_length; /**< Actual number of bytes transmitted/received in the packet */
usb_transfer_status_t status; /**< Status of the packet */
} usb_iso_packet_desc_t;
/**
* @brief USB IRP (I/O Request Packet). See USB2.0 Spec
*
* An identifiable request by a software client to move data between itself (on the
* host) and an endpoint of a device in an appropriate direction.
*
* This structure represents the barebones of the request. Different layers of
* USB drivers will wrap their own objects around this.
*
* See 10.5.3.1 os USB2.0 specification
* Bulk: Represnts a single bulk transfer which a pipe will transparently split
* into multiple MPS transactions (until the last)
* Control: Represents a single contorl transfer with the setup packet at the
* first 8 bytes of the buffer.
* Interrupt: Represnts a single interrupt transaction
* Isochronous: Represnts a buffer of a stream of bytes which the pipe will transparently
* transfer the stream of bytes one or more service periods
*/
typedef struct {
int num_bytes; /**< Number of bytes in IRP. Control should exclude size of setup. IN should be integer multiple of MPS */
int actual_num_bytes; /**< Actual number of bytes transmitted/receives in the IRP */
uint8_t *data_buffer; /**< Pointer to data buffer. Must be DMA capable memory */
usb_transfer_status_t status; /**< Status of the transfer */
int num_iso_packets; /**< Only relevant to isochronous. Number of service periods to transfer data buffer over. Set to 0 for non-iso transfers */
usb_iso_packet_desc_t iso_packet_desc[0]; /**< Descriptors for each ISO packet */
} usb_irp_t;
/* -----------------------------------------------------------------------------
----------------------------------- Chapter 9 ----------------------------------
----------------------------------------------------------------------------- */
// ------------------------------ Control Request ------------------------------
/**
* @brief Size of a USB control transfer setup packet in bytes
*/
#define USB_CTRL_REQ_SIZE 8
/**
* @brief Structure representing a USB control transfer setup packet
*/
typedef union {
struct {
uint8_t bRequestType;
uint8_t bRequest;
uint16_t wValue;
uint16_t wIndex;
uint16_t wLength;
} USB_CTRL_REQ_ATTR;
uint8_t val[USB_CTRL_REQ_SIZE];
} usb_ctrl_req_t;
_Static_assert(sizeof(usb_ctrl_req_t) == USB_CTRL_REQ_SIZE, "Size of usb_ctrl_req_t incorrect");
/**
* @brief Bit masks pertaining to the bRequestType field of a setup packet
*/
#define USB_B_REQUEST_TYPE_DIR_OUT (0X00 << 7)
#define USB_B_REQUEST_TYPE_DIR_IN (0x01 << 7)
#define USB_B_REQUEST_TYPE_TYPE_STANDARD (0x00 << 5)
#define USB_B_REQUEST_TYPE_TYPE_CLASS (0x01 << 5)
#define USB_B_REQUEST_TYPE_TYPE_VENDOR (0x02 << 5)
#define USB_B_REQUEST_TYPE_TYPE_RESERVED (0x03 << 5)
#define USB_B_REQUEST_TYPE_TYPE_MASK (0x03 << 5)
#define USB_B_REQUEST_TYPE_RECIP_DEVICE (0x00 << 0)
#define USB_B_REQUEST_TYPE_RECIP_INTERFACE (0x01 << 0)
#define USB_B_REQUEST_TYPE_RECIP_ENDPOINT (0x02 << 0)
#define USB_B_REQUEST_TYPE_RECIP_OTHER (0x03 << 0)
#define USB_B_REQUEST_TYPE_RECIP_MASK (0x1f << 0)
/**
* @brief Bit masks pertaining to the bRequest field of a setup packet
*/
#define USB_B_REQUEST_GET_STATUS 0x00
#define USB_B_REQUEST_CLEAR_FEATURE 0x01
#define USB_B_REQUEST_SET_FEATURE 0x03
#define USB_B_REQUEST_SET_ADDRESS 0x05
#define USB_B_REQUEST_GET_DESCRIPTOR 0x06
#define USB_B_REQUEST_SET_DESCRIPTOR 0x07
#define USB_B_REQUEST_GET_CONFIGURATION 0x08
#define USB_B_REQUEST_SET_CONFIGURATION 0x09
#define USB_B_REQUEST_GET_INTERFACE 0x0A
#define USB_B_REQUEST_SET_INTERFACE 0x0B
#define USB_B_REQUEST_SYNCH_FRAME 0x0C
/**
* @brief Bit masks pertaining to the wValue field of a setup packet
*/
#define USB_W_VALUE_DT_DEVICE 0x01
#define USB_W_VALUE_DT_CONFIG 0x02
#define USB_W_VALUE_DT_STRING 0x03
#define USB_W_VALUE_DT_INTERFACE 0x04
#define USB_W_VALUE_DT_ENDPOINT 0x05
#define USB_W_VALUE_DT_DEVICE_QUALIFIER 0x06
#define USB_W_VALUE_DT_OTHER_SPEED_CONFIG 0x07
#define USB_W_VALUE_DT_INTERFACE_POWER 0x08
/**
* @brief Initializer for a SET_ADDRESS request
*
* Sets the address of a connected device
*/
#define USB_CTRL_REQ_INIT_SET_ADDR(ctrl_req_ptr, addr) ({ \
(ctrl_req_ptr)->bRequestType = USB_B_REQUEST_TYPE_DIR_OUT | USB_B_REQUEST_TYPE_TYPE_STANDARD |USB_B_REQUEST_TYPE_RECIP_DEVICE; \
(ctrl_req_ptr)->bRequest = USB_B_REQUEST_SET_ADDRESS; \
(ctrl_req_ptr)->wValue = (addr); \
(ctrl_req_ptr)->wIndex = 0; \
(ctrl_req_ptr)->wLength = 0; \
})
/**
* @brief Initializer for a request to get a device's device descriptor
*/
#define USB_CTRL_REQ_INIT_GET_DEVC_DESC(ctrl_req_ptr) ({ \
(ctrl_req_ptr)->bRequestType = USB_B_REQUEST_TYPE_DIR_IN | USB_B_REQUEST_TYPE_TYPE_STANDARD | USB_B_REQUEST_TYPE_RECIP_DEVICE; \
(ctrl_req_ptr)->bRequest = USB_B_REQUEST_GET_DESCRIPTOR; \
(ctrl_req_ptr)->wValue = (USB_W_VALUE_DT_DEVICE << 8); \
(ctrl_req_ptr)->wIndex = 0; \
(ctrl_req_ptr)->wLength = 18; \
})
/**
* @brief Initializer for a request to get a device's current configuration number
*/
#define USB_CTRL_REQ_INIT_GET_CONFIG(ctrl_req_ptr) ({ \
(ctrl_req_ptr)->bRequestType = USB_B_REQUEST_TYPE_DIR_IN | USB_B_REQUEST_TYPE_TYPE_STANDARD | USB_B_REQUEST_TYPE_RECIP_DEVICE; \
(ctrl_req_ptr)->bRequest = USB_B_REQUEST_GET_CONFIGURATION; \
(ctrl_req_ptr)->wValue = 0; \
(ctrl_req_ptr)->wIndex = 0; \
(ctrl_req_ptr)->wLength = 1; \
})
/**
* @brief Initializer for a request to get one of the device's current configuration descriptor
*
* - desc_index indicates the configuration's index number
* - Number of bytes of the configuration descriptor to get
*/
#define USB_CTRL_REQ_INIT_GET_CFG_DESC(ctrl_req_ptr, desc_index, desc_len) ({ \
(ctrl_req_ptr)->bRequestType = USB_B_REQUEST_TYPE_DIR_IN | USB_B_REQUEST_TYPE_TYPE_STANDARD | USB_B_REQUEST_TYPE_RECIP_DEVICE; \
(ctrl_req_ptr)->bRequest = USB_B_REQUEST_GET_DESCRIPTOR; \
(ctrl_req_ptr)->wValue = (USB_W_VALUE_DT_CONFIG << 8) | ((desc_index) & 0xFF); \
(ctrl_req_ptr)->wIndex = 0; \
(ctrl_req_ptr)->wLength = (desc_len); \
})
/**
* @brief Initializer for a request to set a device's current configuration number
*/
#define USB_CTRL_REQ_INIT_SET_CONFIG(ctrl_req_ptr, config_num) ({ \
(ctrl_req_ptr)->bRequestType = USB_B_REQUEST_TYPE_DIR_OUT | USB_B_REQUEST_TYPE_TYPE_STANDARD | USB_B_REQUEST_TYPE_RECIP_DEVICE; \
(ctrl_req_ptr)->bRequest = USB_B_REQUEST_SET_CONFIGURATION; \
(ctrl_req_ptr)->wValue = (config_num); \
(ctrl_req_ptr)->wIndex = 0; \
(ctrl_req_ptr)->wLength = 0; \
})
// ---------------------------- Device Descriptor ------------------------------
/**
* @brief Size of a USB device descriptor in bytes
*/
#define USB_DESC_DEV_SIZE 18
/**
* @brief Structure representing a USB device descriptor
*/
typedef union {
struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t bcdUSB;
uint8_t bDeviceClass;
uint8_t bDeviceSubClass;
uint8_t bDeviceProtocol;
uint8_t bMaxPacketSize0;
uint16_t idVendor;
uint16_t idProduct;
uint16_t bcdDevice;
uint8_t iManufacturer;
uint8_t iProduct;
uint8_t iSerialNumber;
uint8_t bNumConfigurations;
} USB_DESC_ATTR;
uint8_t val[USB_DESC_DEV_SIZE];
} usb_desc_devc_t;
_Static_assert(sizeof(usb_desc_devc_t) == USB_DESC_DEV_SIZE, "Size of usb_desc_devc_t incorrect");
/**
* @brief Possible base class values of the bDeviceClass field of a USB device descriptor
*/
#define USB_CLASS_PER_INTERFACE 0x00
#define USB_CLASS_AUDIO 0x01
#define USB_CLASS_COMM 0x02
#define USB_CLASS_HID 0x03
#define USB_CLASS_PHYSICAL 0x05
#define USB_CLASS_STILL_IMAGE 0x06
#define USB_CLASS_PRINTER 0x07
#define USB_CLASS_MASS_STORAGE 0x08
#define USB_CLASS_HUB 0x09
#define USB_CLASS_CDC_DATA 0x0a
#define USB_CLASS_CSCID 0x0b
#define USB_CLASS_CONTENT_SEC 0x0d
#define USB_CLASS_VIDEO 0x0e
#define USB_CLASS_WIRELESS_CONTROLLER 0xe0
#define USB_CLASS_PERSONAL_HEALTHCARE 0x0f
#define USB_CLASS_AUDIO_VIDEO 0x10
#define USB_CLASS_BILLBOARD 0x11
#define USB_CLASS_USB_TYPE_C_BRIDGE 0x12
#define USB_CLASS_MISC 0xef
#define USB_CLASS_APP_SPEC 0xfe
#define USB_CLASS_VENDOR_SPEC 0xff
/**
* @brief Vendor specific subclass code
*/
#define USB_SUBCLASS_VENDOR_SPEC 0xff
// ----------------------- Configuration Descriptor ----------------------------
/**
* @brief Size of a short USB configuration descriptor in bytes
*
* @note The size of a full USB configuration includes all the interface and endpoint
* descriptors of that configuration.
*/
#define USB_DESC_CFG_SIZE 9
/**
* @brief Structure representing a short USB configuration descriptor
*
* @note The full USB configuration includes all the interface and endpoint
* descriptors of that configuration.
*/
typedef union {
struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wTotalLength;
uint8_t bNumInterfaces;
uint8_t bConfigurationValue;
uint8_t iConfiguration;
uint8_t bmAttributes;
uint8_t bMaxPower;
} USB_DESC_ATTR;
uint8_t val[USB_DESC_CFG_SIZE];
} usb_desc_cfg_t;
_Static_assert(sizeof(usb_desc_cfg_t) == USB_DESC_CFG_SIZE, "Size of usb_desc_cfg_t incorrect");
/**
* @brief Bit masks pertaining to the bmAttributes field of a configuration descriptor
*/
#define USB_BM_ATTRIBUTES_ONE (1 << 7) //Must be set
#define USB_BM_ATTRIBUTES_SELFPOWER (1 << 6) //Self powered
#define USB_BM_ATTRIBUTES_WAKEUP (1 << 5) //Can wakeup
#define USB_BM_ATTRIBUTES_BATTERY (1 << 4) //Battery powered
// ------------------------- Interface Descriptor ------------------------------
/**
* @brief Size of a USB interface descriptor in bytes
*/
#define USB_DESC_INTF_SIZE 9
/**
* @brief Structure representing a USB interface descriptor
*/
typedef union {
struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bInterfaceNumber;
uint8_t bAlternateSetting;
uint8_t bNumEndpoints;
uint8_t bInterfaceClass;
uint8_t bInterfaceSubClass;
uint8_t bInterfaceProtocol;
uint8_t iInterface;
} USB_DESC_ATTR;
uint8_t val[USB_DESC_INTF_SIZE];
} usb_desc_intf_t;
_Static_assert(sizeof(usb_desc_intf_t) == USB_DESC_INTF_SIZE, "Size of usb_desc_intf_t incorrect");
// ------------------------- Endpoint Descriptor -------------------------------
/**
* @brief Size of a USB endpoint descriptor in bytes
*/
#define USB_DESC_EP_SIZE 7
/**
* @brief Structure representing a USB endp;oint descriptor
*/
typedef union {
struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint8_t bEndpointAddress;
uint8_t bmAttributes;
uint16_t wMaxPacketSize;
uint8_t bInterval;
} USB_DESC_ATTR;
uint8_t val[USB_DESC_EP_SIZE];
} usb_desc_ep_t;
_Static_assert(sizeof(usb_desc_ep_t) == USB_DESC_EP_SIZE, "Size of usb_desc_ep_t incorrect");
/**
* @brief Bit masks pertaining to the bEndpointAddress field of an endpoint descriptor
*/
#define USB_B_ENDPOINT_ADDRESS_EP_NUM_MASK 0x0f
#define USB_B_ENDPOINT_ADDRESS_EP_DIR_MASK 0x80
/**
* @brief Bit masks pertaining to the bmAttributes field of an endpoint descriptor
*/
#define USB_BM_ATTRIBUTES_XFERTYPE_MASK 0x03
#define USB_BM_ATTRIBUTES_XFER_CONTROL (0 << 0)
#define USB_BM_ATTRIBUTES_XFER_ISOC (1 << 0)
#define USB_BM_ATTRIBUTES_XFER_BULK (2 << 0)
#define USB_BM_ATTRIBUTES_XFER_INT (3 << 0)
#define USB_BM_ATTRIBUTES_SYNCTYPE_MASK 0x0C /* in bmAttributes */
#define USB_BM_ATTRIBUTES_SYNC_NONE (0 << 2)
#define USB_BM_ATTRIBUTES_SYNC_ASYNC (1 << 2)
#define USB_BM_ATTRIBUTES_SYNC_ADAPTIVE (2 << 2)
#define USB_BM_ATTRIBUTES_SYNC_SYNC (3 << 2)
#define USB_BM_ATTRIBUTES_USAGETYPE_MASK 0x30
#define USB_BM_ATTRIBUTES_USAGE_DATA (0 << 4)
#define USB_BM_ATTRIBUTES_USAGE_FEEDBACK (1 << 4)
#define USB_BM_ATTRIBUTES_USAGE_IMPLICIT_FB (2 << 4)
/**
* @brief Macro helpers to get information about an endpoint from its descriptor
*/
#define USB_DESC_EP_GET_XFERTYPE(desc_ptr) ((usb_xfer_type_t) ((desc_ptr)->bmAttributes & USB_BM_ATTRIBUTES_XFERTYPE_MASK))
#define USB_DESC_EP_GET_EP_NUM(desc_ptr) ((desc_ptr)->bEndpointAddress & USB_B_ENDPOINT_ADDRESS_EP_NUM_MASK)
#define USB_DESC_EP_GET_EP_DIR(desc_ptr) (((desc_ptr)->bEndpointAddress & USB_B_ENDPOINT_ADDRESS_EP_DIR_MASK) ? 1 : 0)
#define USB_DESC_EP_GET_MPS(desc_ptr) ((desc_ptr)->wMaxPacketSize & 0x7FF)
// --------------------------- String Descriptor -------------------------------
/**
* @brief Size of a short USB string descriptor in bytes
*/
#define USB_DESC_STR_SIZE 4
/**
* @brief Structure representing a USB string descriptor
*/
typedef union {
struct {
uint8_t bLength;
uint8_t bDescriptorType;
uint16_t wData[1]; /* UTF-16LE encoded */
} USB_DESC_ATTR;
uint8_t val[USB_DESC_STR_SIZE];
} usb_desc_str_t;
_Static_assert(sizeof(usb_desc_str_t) == USB_DESC_STR_SIZE, "Size of usb_desc_str_t incorrect");
#ifdef __cplusplus
}
#endif