mirror of
https://github.com/espressif/esp-idf.git
synced 2024-10-05 20:47:46 -04:00
soc: updates caps usage
We should define caps as 1 if true. When use the caps macros, #if and #if ! should be used instead of #ifdef/#ifndef.
This commit is contained in:
parent
647dea9395
commit
1966f00f0b
@ -36,8 +36,14 @@ static const char *GPIO_TAG = "gpio";
|
||||
ESP_LOGE(GPIO_TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
|
||||
return (ret_val); \
|
||||
}
|
||||
|
||||
#define GPIO_ISR_CORE_ID_UNINIT (3)
|
||||
|
||||
//default value for SOC_GPIO_SUPPORT_RTC_INDEPENDENT is 0
|
||||
#ifndef SOC_GPIO_SUPPORT_RTC_INDEPENDENT
|
||||
#define SOC_GPIO_SUPPORT_RTC_INDEPENDENT 0
|
||||
#endif
|
||||
|
||||
typedef struct {
|
||||
gpio_isr_t fn; /*!< isr function */
|
||||
void *args; /*!< isr function args */
|
||||
|
@ -12,13 +12,10 @@
|
||||
// See the License for the specific language governing permissions and
|
||||
// limitations under the License.
|
||||
|
||||
#ifndef _DRIVER_MCPWM_H_
|
||||
#define _DRIVER_MCPWM_H_
|
||||
#pragma once
|
||||
|
||||
#include "soc/soc_caps.h"
|
||||
#ifndef SOC_MCPWM_SUPPORTED
|
||||
#error MCPWM is not supported in this chip target
|
||||
#endif
|
||||
#if SOC_MCPWM_SUPPORTED
|
||||
|
||||
#include "esp_err.h"
|
||||
#include "soc/soc.h"
|
||||
@ -664,4 +661,5 @@ esp_err_t mcpwm_isr_register(mcpwm_unit_t mcpwm_num, void (*fn)(void *), void *a
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /*_DRIVER_MCPWM_H_*/
|
||||
#endif //SOC_MCPWM_SUPPORTED
|
||||
|
||||
|
@ -15,9 +15,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "soc/soc_caps.h"
|
||||
#ifndef SOC_SDMMC_HOST_SUPPORTED
|
||||
#error SDMMC host is not supported in this chip target
|
||||
#endif
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
@ -245,3 +243,5 @@ esp_err_t sdmmc_host_pullup_en(int slot, int width);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif //SOC_SDMMC_HOST_SUPPORTED
|
@ -19,9 +19,7 @@ extern "C" {
|
||||
#endif
|
||||
|
||||
#include "soc/soc_caps.h"
|
||||
#ifndef SOC_TWAI_SUPPORTED
|
||||
#error TWAI is not supported in this chip target
|
||||
#endif
|
||||
#if SOC_TWAI_SUPPORTED
|
||||
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "esp_types.h"
|
||||
@ -346,3 +344,5 @@ esp_err_t twai_clear_receive_queue(void);
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif //SOC_TWAI_SUPPORTED
|
@ -410,7 +410,7 @@ esp_err_t spi_bus_add_device(spi_host_device_t host_id, const spi_device_interfa
|
||||
hal_dev->tx_lsbfirst = dev_config->flags & SPI_DEVICE_TXBIT_LSBFIRST ? 1 : 0;
|
||||
hal_dev->rx_lsbfirst = dev_config->flags & SPI_DEVICE_RXBIT_LSBFIRST ? 1 : 0;
|
||||
hal_dev->no_compensate = dev_config->flags & SPI_DEVICE_NO_DUMMY ? 1 : 0;
|
||||
#ifdef SOC_SPI_SUPPORT_AS_CS
|
||||
#if SOC_SPI_SUPPORT_AS_CS
|
||||
hal_dev->as_cs = dev_config->flags& SPI_DEVICE_CLK_AS_CS ? 1 : 0;
|
||||
#endif
|
||||
hal_dev->positive_cs = dev_config->flags & SPI_DEVICE_POSITIVE_CS ? 1 : 0;
|
||||
|
@ -27,7 +27,7 @@
|
||||
|
||||
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S3)
|
||||
|
||||
#ifdef SOC_MCPWM_SUPPORTED
|
||||
#if SOC_MCPWM_SUPPORTED
|
||||
#include "soc/mcpwm_periph.h"
|
||||
#include "driver/mcpwm.h"
|
||||
|
||||
|
@ -24,7 +24,7 @@
|
||||
|
||||
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S3)
|
||||
|
||||
#if defined(SOC_SDMMC_HOST_SUPPORTED) && defined(SOC_SDIO_SLAVE_SUPPORTED)
|
||||
#if SOC_SDMMC_HOST_SUPPORTED && SOC_SDIO_SLAVE_SUPPORTED
|
||||
#include "driver/sdio_slave.h"
|
||||
#include "driver/sdmmc_host.h"
|
||||
|
||||
@ -807,6 +807,6 @@ ptest_func_t tohost_slave = {
|
||||
|
||||
TEST_MASTER_SLAVE(SDIO_TOHOST, test_cfg_array, "[sdio][timeout=180][test_env=UT_SDIO]", &tohost_master, &tohost_slave);
|
||||
|
||||
#endif
|
||||
#endif //SOC_SDMMC_HOST_SUPPORTED && SOC_SDIO_SLAVE_SUPPORTED
|
||||
|
||||
#endif
|
||||
|
@ -35,7 +35,7 @@
|
||||
#define BROWNOUT_DET_LVL 0
|
||||
#endif
|
||||
|
||||
#ifdef SOC_BROWNOUT_RESET_SUPPORTED
|
||||
#if SOC_BROWNOUT_RESET_SUPPORTED
|
||||
#define BROWNOUT_RESET_EN true
|
||||
#else
|
||||
#define BROWNOUT_RESET_EN false
|
||||
|
@ -103,7 +103,7 @@ void esp_timer_impl_advance(int64_t time_us)
|
||||
esp_err_t esp_timer_impl_init(intr_handler_t alarm_handler)
|
||||
{
|
||||
s_alarm_handler = alarm_handler;
|
||||
#ifdef SOC_SYSTIMER_INT_LEVEL
|
||||
#if SOC_SYSTIMER_INT_LEVEL
|
||||
int int_type = 0;
|
||||
#else
|
||||
int int_type = ESP_INTR_FLAG_EDGE;
|
||||
|
@ -16,14 +16,14 @@
|
||||
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S2)
|
||||
|
||||
//Function just extern, need not test
|
||||
#ifdef SOC_BT_SUPPORTED
|
||||
#if SOC_BT_SUPPORTED
|
||||
extern void bt_bb_init_cmplx(void);
|
||||
#endif
|
||||
extern void IRAM_ATTR spi_flash_disable_interrupts_caches_and_other_cpu(void);
|
||||
extern void IRAM_ATTR spi_flash_enable_interrupts_caches_and_other_cpu(void);
|
||||
|
||||
//Functions in librtc.a called by WIFI or Blutooth directly in ISR
|
||||
#ifdef SOC_BT_SUPPORTED
|
||||
#if SOC_BT_SUPPORTED
|
||||
extern void bt_bb_init_cmplx_reg(void);
|
||||
extern void bt_track_pll_cap(void);
|
||||
#endif
|
||||
@ -68,7 +68,7 @@ static IRAM_ATTR void test_phy_rtc_cache_task(void *arg)
|
||||
spi_flash_enable_interrupts_caches_and_other_cpu();
|
||||
}
|
||||
|
||||
#ifdef SOC_BT_SUPPORTED
|
||||
#if SOC_BT_SUPPORTED
|
||||
ESP_LOGI(TAG, "Test bt_bb_init_cmplx_reg()...");
|
||||
spi_flash_disable_interrupts_caches_and_other_cpu();
|
||||
bt_bb_init_cmplx_reg();
|
||||
|
@ -38,7 +38,7 @@
|
||||
#define SDSPI_HOST_ID HSPI_HOST
|
||||
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
#include "driver/sdmmc_host.h"
|
||||
|
||||
|
||||
|
@ -25,7 +25,7 @@
|
||||
#include "soc/soc_caps.h"
|
||||
#include "driver/sdmmc_defs.h"
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
#include "driver/sdmmc_host.h"
|
||||
#endif
|
||||
|
||||
|
@ -23,7 +23,7 @@ extern "C" {
|
||||
#include "soc/soc_caps.h"
|
||||
|
||||
typedef enum {
|
||||
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
||||
#if SOC_LEDC_SUPPORT_HS_MODE
|
||||
LEDC_HIGH_SPEED_MODE = 0, /*!< LEDC high speed speed_mode */
|
||||
#endif
|
||||
LEDC_LOW_SPEED_MODE, /*!< LEDC low speed speed_mode */
|
||||
@ -45,7 +45,7 @@ typedef enum {
|
||||
typedef enum {
|
||||
LEDC_SLOW_CLK_RTC8M = 0, /*!< LEDC low speed timer clock source is 8MHz RTC clock*/
|
||||
LEDC_SLOW_CLK_APB, /*!< LEDC low speed timer clock source is 80MHz APB clock*/
|
||||
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
LEDC_SLOW_CLK_XTAL, /*!< LEDC low speed timer clock source XTAL clock*/
|
||||
#endif
|
||||
} ledc_slow_clk_sel_t;
|
||||
@ -55,7 +55,7 @@ typedef enum {
|
||||
LEDC_USE_REF_TICK, /*!< LEDC timer select REF_TICK clock as source clock*/
|
||||
LEDC_USE_APB_CLK, /*!< LEDC timer select APB clock as source clock*/
|
||||
LEDC_USE_RTC8M_CLK, /*!< LEDC timer select RTC8M_CLK as source clock. Only for low speed channels and this parameter must be the same for all low speed channels*/
|
||||
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
LEDC_USE_XTAL_CLK, /*!< LEDC timer select XTAL clock as source clock*/
|
||||
#endif
|
||||
} ledc_clk_cfg_t;
|
||||
|
@ -133,7 +133,7 @@ typedef struct {
|
||||
uint32_t tx_lsbfirst : 1; ///< Whether LSB is sent first for TX data, device specific
|
||||
uint32_t rx_lsbfirst : 1; ///< Whether LSB is received first for RX data, device specific
|
||||
uint32_t no_compensate : 1; ///< No need to add dummy to compensate the timing, device specific
|
||||
#ifdef SOC_SPI_SUPPORT_AS_CS
|
||||
#if SOC_SPI_SUPPORT_AS_CS
|
||||
uint32_t as_cs : 1; ///< Whether to toggle the CS while the clock toggles, device specific
|
||||
#endif
|
||||
uint32_t positive_cs : 1; ///< Whether the postive CS feature is abled, device specific
|
||||
|
@ -302,7 +302,7 @@ void timer_hal_get_status_reg_mask_bit(timer_hal_context_t *hal, uint32_t *statu
|
||||
*/
|
||||
#define timer_hal_get_intr_status_reg(hal) timer_ll_get_intr_status_reg((hal)->dev)
|
||||
|
||||
#ifdef SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
#if SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
/**
|
||||
* @brief Set clock source.
|
||||
*
|
||||
|
@ -98,7 +98,7 @@ typedef enum {
|
||||
TIMER_AUTORELOAD_MAX,
|
||||
} timer_autoreload_t;
|
||||
|
||||
#ifdef SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
#if SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
/**
|
||||
* @brief Select timer source clock.
|
||||
*/
|
||||
@ -118,7 +118,7 @@ typedef struct {
|
||||
timer_count_dir_t counter_dir; /*!< Counter direction */
|
||||
timer_autoreload_t auto_reload; /*!< Timer auto-reload */
|
||||
uint32_t divider; /*!< Counter clock divider. The divider's range is from from 2 to 65536. */
|
||||
#ifdef SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
#if SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
timer_src_clk_t clk_src; /*!< Use XTAL as source clock. */
|
||||
#endif
|
||||
} timer_config_t;
|
||||
|
@ -37,7 +37,7 @@ void ledc_hal_get_clk_cfg(ledc_hal_context_t *hal, ledc_timer_t timer_sel, ledc_
|
||||
ledc_hal_get_slow_clk_sel(hal, &slow_clk);
|
||||
if (slow_clk == LEDC_SLOW_CLK_RTC8M) {
|
||||
*clk_cfg = LEDC_USE_RTC8M_CLK;
|
||||
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
} else if (slow_clk == LEDC_SLOW_CLK_XTAL) {
|
||||
*clk_cfg = LEDC_USE_XTAL_CLK;
|
||||
#endif
|
||||
@ -50,7 +50,7 @@ void ledc_hal_set_slow_clk(ledc_hal_context_t *hal, ledc_clk_cfg_t clk_cfg)
|
||||
{
|
||||
// For low speed channels, if RTC_8MCLK is used as the source clock, the `slow_clk_sel` register should be cleared, otherwise it should be set.
|
||||
ledc_slow_clk_sel_t slow_clk_sel = LEDC_SLOW_CLK_APB;
|
||||
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
|
||||
slow_clk_sel = (clk_cfg == LEDC_USE_RTC8M_CLK) ? LEDC_SLOW_CLK_RTC8M :
|
||||
((clk_cfg == LEDC_USE_XTAL_CLK) ? LEDC_SLOW_CLK_XTAL : LEDC_SLOW_CLK_APB);
|
||||
#else
|
||||
|
@ -49,7 +49,7 @@ void spi_hal_setup_device(spi_hal_context_t *hal, const spi_hal_dev_config_t *de
|
||||
{
|
||||
//Configure clock settings
|
||||
spi_dev_t *hw = hal->hw;
|
||||
#ifdef SOC_SPI_SUPPORT_AS_CS
|
||||
#if SOC_SPI_SUPPORT_AS_CS
|
||||
spi_ll_master_set_cksel(hw, dev->cs_pin_id, dev->as_cs);
|
||||
#endif
|
||||
spi_ll_master_set_pos_cs(hw, dev->cs_pin_id, dev->positive_cs);
|
||||
|
@ -32,7 +32,7 @@ bool twai_hal_init(twai_hal_context_t *hal_ctx)
|
||||
if (!twai_ll_is_in_reset_mode(hal_ctx->dev)) { //Must enter reset mode to write to config registers
|
||||
return false;
|
||||
}
|
||||
#ifdef SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT
|
||||
#if SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT
|
||||
twai_ll_enable_extended_reg_layout(hal_ctx->dev); //Changes the address layout of the registers
|
||||
#endif
|
||||
twai_ll_set_mode(hal_ctx->dev, TWAI_MODE_LISTEN_ONLY); //Freeze REC by changing to LOM mode
|
||||
|
@ -47,7 +47,7 @@ IRAM_ATTR static void *dram_alloc_to_iram_addr(void *addr, size_t len)
|
||||
assert(esp_ptr_in_diram_dram((void *)dend));
|
||||
assert((dstart & 3) == 0);
|
||||
assert((dend & 3) == 0);
|
||||
#ifdef SOC_DIRAM_INVERTED // We want the word before the result to hold the DRAM address
|
||||
#if SOC_DIRAM_INVERTED // We want the word before the result to hold the DRAM address
|
||||
uint32_t *iptr = esp_ptr_diram_dram_to_iram((void *)dend);
|
||||
#else
|
||||
uint32_t *iptr = esp_ptr_diram_dram_to_iram((void *)dstart);
|
||||
|
@ -21,7 +21,7 @@
|
||||
#include "unity.h"
|
||||
#include "driver/gpio.h"
|
||||
#include "soc/soc_caps.h"
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
#include "driver/sdmmc_host.h"
|
||||
#endif
|
||||
#include "driver/sdspi_host.h"
|
||||
@ -83,7 +83,7 @@ TEST_CASE("MMC_RSP_BITS", "[sd]")
|
||||
TEST_ASSERT_EQUAL_HEX32(0x11, MMC_RSP_BITS(data, 59, 5));
|
||||
}
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
|
||||
static void probe_sd(int slot, int width, int freq_khz, int ddr)
|
||||
{
|
||||
@ -328,7 +328,7 @@ __attribute__((unused)) static void read_write_test(sdmmc_card_t* card)
|
||||
do_single_write_read_test(card, card->csd.capacity/2, 128, 1);
|
||||
}
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
void test_sd_rw_blocks(int slot, int width)
|
||||
{
|
||||
sdmmc_host_t config = SDMMC_HOST_DEFAULT();
|
||||
@ -403,7 +403,7 @@ TEST_CASE("SDMMC read/write test (SD slot 1, in SPI mode)", "[sdspi][test_env=UT
|
||||
}
|
||||
#endif //DISABLED_FOR_TARGETS(ESP32S2)
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
TEST_CASE("reads and writes with an unaligned buffer", "[sd][test_env=UT_T1_SDMODE]")
|
||||
{
|
||||
sd_test_board_power_on();
|
||||
@ -467,7 +467,7 @@ __attribute__((unused)) static void test_cd_input(int gpio_cd_num, const sdmmc_h
|
||||
free(card);
|
||||
}
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
TEST_CASE("CD input works in SD mode", "[sd][test_env=UT_T1_SDMODE]")
|
||||
{
|
||||
sd_test_board_power_on();
|
||||
@ -541,7 +541,7 @@ __attribute__((unused)) static void test_wp_input(int gpio_wp_num, const sdmmc_h
|
||||
free(card);
|
||||
}
|
||||
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
TEST_CASE("WP input works in SD mode", "[sd][test_env=UT_T1_SDMODE]")
|
||||
{
|
||||
sd_test_board_power_on();
|
||||
|
@ -13,7 +13,7 @@
|
||||
// limitations under the License.
|
||||
|
||||
#include "soc/soc_caps.h"
|
||||
#ifdef SOC_SDMMC_HOST_SUPPORTED
|
||||
#if SOC_SDMMC_HOST_SUPPORTED
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
@ -385,4 +385,4 @@ TEST_CASE("can probe and talk to ESP32 SDIO slave", "[sdio][ignore]")
|
||||
free(card);
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif //SOC_SDMMC_HOST_SUPPORTED
|
@ -104,12 +104,9 @@
|
||||
#define SOC_GPIO_PORT (1)
|
||||
#define SOC_GPIO_PIN_COUNT 40
|
||||
|
||||
|
||||
// On ESP32 those PADs which have RTC functions must set pullup/down/capability via RTC register.
|
||||
// On ESP32-S2, Digital IOs have their own registers to control pullup/down/capability, independent with RTC registers.
|
||||
#define SOC_GPIO_SUPPORT_RTC_INDEPENDENT (0)
|
||||
// Force hold is a new function of ESP32-S2
|
||||
#define SOC_GPIO_SUPPORT_FORCE_HOLD (0)
|
||||
// SOC_GPIO_SUPPORT_RTC_INDEPENDENT not defined. On ESP32 those PADs which have RTC functions must
|
||||
// set pullup/down/capability via RTC register. On ESP32-S2, Digital IOs have their own registers to
|
||||
// control pullup/down/capability, independent with RTC registers.
|
||||
|
||||
// 0~39 except from 20, 24, 28~31 are valid
|
||||
#define SOC_GPIO_VALID_GPIO_MASK (0xFFFFFFFFFFULL & ~(0ULL | BIT20 | BIT24 | BIT28 | BIT29 | BIT30 | BIT31))
|
||||
@ -121,17 +118,12 @@
|
||||
#define SOC_I2C_NUM (2)
|
||||
|
||||
#define SOC_I2C_FIFO_LEN (32) /*!< I2C hardware FIFO depth */
|
||||
//ESP32 do not support hardware FSM reset
|
||||
#define SOC_I2C_SUPPORT_HW_FSM_RST (0)
|
||||
//ESP32 do not support hardware clear bus
|
||||
#define SOC_I2C_SUPPORT_HW_CLR_BUS (0)
|
||||
|
||||
/*-------------------------- I2S CAPS ----------------------------------------*/
|
||||
// ESP32 have 2 I2S
|
||||
#define SOC_I2S_NUM (2)
|
||||
|
||||
#define SOC_I2S_SUPPORTS_PDM (1) // ESP32 support PDM
|
||||
#define SOC_I2S_SUPPORTS_DMA_EQUAL (0) // ESP32 don't support dma equal
|
||||
#define SOC_I2S_SUPPORTS_ADC_DAC (1) // ESP32 support ADC and DAC
|
||||
|
||||
#define SOC_I2S_MAX_BUFFER_SIZE (4 * 1024 * 1024) //the maximum RAM can be allocated
|
||||
|
@ -109,9 +109,7 @@
|
||||
// ESP32-S2 have 2 I2S
|
||||
#define SOC_I2S_NUM (1)
|
||||
|
||||
#define SOC_I2S_SUPPORTS_PDM (0) // ESP32-S2 don't support PDM
|
||||
#define SOC_I2S_SUPPORTS_DMA_EQUAL (1) // ESP32-S2 need dma equal
|
||||
#define SOC_I2S_SUPPORTS_ADC_DAC (0) // ESP32-S2 don't support ADC and DAC
|
||||
|
||||
#define SOC_I2S_MAX_BUFFER_SIZE (4 * 1024 * 1024) //the maximum RAM can be allocated
|
||||
|
||||
@ -183,7 +181,7 @@
|
||||
#define SOC_SYSTIMER_BIT_WIDTH_HI (32) // Bit width of systimer high part
|
||||
|
||||
/*-------------------------- TIMER GROUP CAPS --------------------------------*/
|
||||
#define SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
#define SOC_TIMER_GROUP_SUPPORT_XTAL 1
|
||||
|
||||
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
|
||||
#define SOC_TOUCH_SENSOR_NUM (15) /*! 15 Touch channels */
|
||||
|
@ -20,7 +20,6 @@
|
||||
|
||||
#define SOC_SPI_MAXIMUM_BUFFER_SIZE 72
|
||||
|
||||
//#define SOC_SPI_SUPPORT_AS_CS //don't support to toggle the CS while the clock toggles
|
||||
#define SOC_SPI_SUPPORT_DDRCLK 1
|
||||
#define SOC_SPI_SLAVE_SUPPORT_SEG_TRANS 1
|
||||
#define SOC_SPI_SUPPORT_CD_SIG 1
|
||||
|
@ -14,4 +14,4 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#define SOC_TIMER_GROUP_SUPPORT_XTAL
|
||||
#define SOC_TIMER_GROUP_SUPPORT_XTAL 1
|
||||
|
@ -28,7 +28,7 @@ typedef struct {
|
||||
const uint8_t sig_out0_idx;
|
||||
} ledc_signal_conn_t;
|
||||
|
||||
#ifdef SOC_LEDC_SUPPORT_HS_MODE
|
||||
#if SOC_LEDC_SUPPORT_HS_MODE
|
||||
extern const ledc_signal_conn_t ledc_periph_signal[2];
|
||||
#else
|
||||
extern const ledc_signal_conn_t ledc_periph_signal[1];
|
||||
|
Loading…
x
Reference in New Issue
Block a user