#We cannot include the esp32 component directly but we need its includes.
#This is fixed by adding CFLAGS from Makefile.projbuild
-COMPONENTS := esptool_py bootloader bootloader_support log spi_flash micro-ecc
+COMPONENTS := esptool_py bootloader bootloader_support log spi_flash micro-ecc soc
# The bootloader pseudo-component is also included in this build, for its Kconfig.projbuild to be included.
#
#include "soc/soc.h"
#include "soc/cpu.h"
+#include "soc/rtc.h"
#include "soc/dport_reg.h"
#include "soc/io_mux_reg.h"
#include "soc/efuse_reg.h"
#include "bootloader_flash.h"
#include "bootloader_random.h"
#include "bootloader_config.h"
-#include "rtc.h"
+
#include "flash_qio_mode.h"
extern int _bss_start;
void bootloader_main()
{
- /* Set CPU to 80MHz.
- Start by ensuring it is set to XTAL, as PLL must be off first
- (may still be on due to soft reset.)
- */
- rtc_set_cpu_freq(CPU_XTAL);
- rtc_set_cpu_freq(CPU_80M);
+ /* Set CPU to 80MHz. Keep other clocks unmodified. */
+ uart_tx_wait_idle(0);
+ rtc_clk_config_t clk_cfg = RTC_CLK_CONFIG_DEFAULT();
+ clk_cfg.cpu_freq = RTC_CPU_FREQ_80M;
+ clk_cfg.slow_freq = rtc_clk_slow_freq_get();
+ clk_cfg.fast_freq = rtc_clk_fast_freq_get();
+ rtc_clk_init(clk_cfg);
uart_console_configure();
ESP_LOGI(TAG, "ESP-IDF %s 2nd stage bootloader", IDF_VER);
// Set configured UART console baud rate
const int uart_baud = CONFIG_CONSOLE_UART_BAUDRATE;
- uart_div_modify(uart_num, (APB_CLK_FREQ << 4) / uart_baud);
+ uart_div_modify(uart_num, (rtc_clk_apb_freq_get() << 4) / uart_baud);
#endif // CONFIG_CONSOLE_UART_NONE
}
-
-/* empty rtc_printf implementation, to work with librtc
- linking. Can be removed once -lrtc is removed from bootloader's
- main component.mk.
-*/
-int rtc_printf(void)
-{
- return 0;
-}
COMPONENT_ADD_LDFLAGS := -L $(COMPONENT_PATH) -lmain $(addprefix -T ,$(LINKER_SCRIPTS))
COMPONENT_ADD_LINKER_DEPS := $(LINKER_SCRIPTS)
-
-# following lines are a workaround to link librtc into the
-# bootloader, until clock setting code is in a source-based esp-idf
-# component. See also rtc_printf() in bootloader_start.c
-#
-# See also matching COMPONENT_SUBMODULES line in Makefile.projbuild
-COMPONENT_ADD_LDFLAGS += -L $(IDF_PATH)/components/esp32/lib/ -lrtc_clk -lrtc
-COMPONENT_EXTRA_INCLUDES += $(IDF_PATH)/components/esp32/
choice ESP32_DEFAULT_CPU_FREQ_MHZ
prompt "CPU frequency"
- default ESP32_DEFAULT_CPU_FREQ_240
+ default ESP32_DEFAULT_CPU_FREQ_160
help
CPU frequency to be set on application startup.
default ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC
help
Choose which clock is used as RTC clock source.
- The only available option for now is to use internal
- 150kHz RC oscillator.
config ESP32_RTC_CLOCK_SOURCE_INTERNAL_RC
- bool "Internal RC"
+ bool "Internal 150kHz RC oscillator"
config ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL
bool "External 32kHz crystal"
- depends on DOCUMENTATION_FOR_RTC_CNTL
endchoice
config ESP32_DEEP_SLEEP_WAKEUP_DELAY
#
COMPONENT_SRCDIRS := . hwcrypto
-LIBS := core rtc rtc_clk rtc_pm
+LIBS := core rtc
ifdef CONFIG_PHY_ENABLED # BT || WIFI
LIBS += phy coexist
endif
#include "rom/ets_sys.h"
#include "rom/uart.h"
#include "sdkconfig.h"
-#include "rtc.h"
#include "soc/soc.h"
+#include "soc/rtc.h"
#include "soc/rtc_cntl_reg.h"
/*
void esp_set_cpu_freq(void)
{
uint32_t freq_mhz = CONFIG_ESP32_DEFAULT_CPU_FREQ_MHZ;
-
- // freq will be changed to 40MHz in rtc_init_lite,
- // wait uart tx finish, otherwise some uart output will be lost
- uart_tx_wait_idle(CONFIG_CONSOLE_UART_NUM);
-
- rtc_init_lite(XTAL_AUTO);
- // work around a bug that RTC fast memory may be isolated
- // from the system after rtc_init_lite
- SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_NOISO_M);
-
- cpu_freq_t freq = CPU_80M;
+ rtc_cpu_freq_t freq = RTC_CPU_FREQ_80M;
switch(freq_mhz) {
case 240:
- freq = CPU_240M;
+ freq = RTC_CPU_FREQ_240M;
break;
case 160:
- freq = CPU_160M;
+ freq = RTC_CPU_FREQ_160M;
break;
default:
freq_mhz = 80;
/* no break */
case 80:
- freq = CPU_80M;
+ freq = RTC_CPU_FREQ_80M;
break;
}
- // freq will be changed to freq in rtc_set_cpu_freq,
- // wait uart tx finish, otherwise some uart output will be lost
+ // Wait for UART TX to finish, otherwise some UART output will be lost
+ // when switching APB frequency
uart_tx_wait_idle(CONFIG_CONSOLE_UART_NUM);
-
- rtc_set_cpu_freq(freq);
- ets_update_cpu_frequency(freq_mhz);
+ rtc_config_t cfg = RTC_CONFIG_DEFAULT();
+ rtc_init(cfg);
+ rtc_clk_cpu_freq_set(freq);
+#if ESP32_RTC_CLOCK_SOURCE_EXTERNAL_CRYSTAL
+ rtc_clk_slow_freq_set(RTC_SLOW_FREQ_32K_XTAL);
+#endif
}
void IRAM_ATTR ets_update_cpu_frequency(uint32_t ticks_per_us)
#include "rom/cache.h"
#include "soc/cpu.h"
+#include "soc/rtc.h"
#include "soc/dport_reg.h"
#include "soc/io_mux_reg.h"
#include "soc/rtc_cntl_reg.h"
#endif
esp_set_cpu_freq(); // set CPU frequency configured in menuconfig
#ifndef CONFIG_CONSOLE_UART_NONE
- uart_div_modify(CONFIG_CONSOLE_UART_NUM, (APB_CLK_FREQ << 4) / CONFIG_CONSOLE_UART_BAUDRATE);
+ uart_div_modify(CONFIG_CONSOLE_UART_NUM, (rtc_clk_apb_freq_get() << 4) / CONFIG_CONSOLE_UART_BAUDRATE);
#endif
#if CONFIG_BROWNOUT_DET
esp_brownout_init();
#include "rom/rtc.h"
#include "rom/uart.h"
#include "soc/cpu.h"
+#include "soc/rtc.h"
#include "soc/rtc_cntl_reg.h"
+#include "soc/rtc_io_reg.h"
#include "soc/sens_reg.h"
#include "soc/dport_reg.h"
#include "driver/rtc_io.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
-#include "rtc.h"
#include "sdkconfig.h"
/**
static uint32_t get_power_down_flags();
static void ext0_wakeup_prepare();
static void ext1_wakeup_prepare();
+static void timer_wakeup_prepare();
/* Wake from deep sleep stub
See esp_deepsleep.h esp_wake_deep_sleep() comments for details.
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR_M, 0, SENS_FORCE_XPD_SAR_S);
- // Configure pins for external wakeup
- if (s_config.wakeup_triggers & EXT_EVENT0_TRIG_EN) {
- ext0_wakeup_prepare();
- }
- if (s_config.wakeup_triggers & EXT_EVENT1_TRIG_EN) {
- ext1_wakeup_prepare();
- }
- if (s_config.wakeup_triggers & SAR_TRIG_EN) {
- SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_WAKEUP_FORCE_EN);
- }
- // TODO: move timer wakeup configuration into a similar function
- // once rtc_sleep is opensourced.
-
// Flush UARTs so that output is not lost due to APB frequency change
uart_tx_wait_idle(0);
uart_tx_wait_idle(1);
esp_set_deep_sleep_wake_stub(esp_wake_deep_sleep);
}
- rtc_set_cpu_freq(CPU_XTAL);
- uint32_t cycle_h = 0;
- uint32_t cycle_l = 0;
- // For timer wakeup, calibrate clock source against main XTAL
- // This is hardcoded to use 150kHz internal oscillator for now
- if (s_config.sleep_duration > 0) {
- uint32_t period = rtc_slowck_cali(CALI_RTC_MUX, 128);
- rtc_usec2rtc(s_config.sleep_duration >> 32, s_config.sleep_duration & UINT32_MAX,
- period, &cycle_h, &cycle_l);
+ // Configure pins for external wakeup
+ if (s_config.wakeup_triggers & RTC_EXT0_TRIG_EN) {
+ ext0_wakeup_prepare();
}
+ if (s_config.wakeup_triggers & RTC_EXT1_TRIG_EN) {
+ ext1_wakeup_prepare();
+ }
+ // Enable ULP wakeup
+ if (s_config.wakeup_triggers & RTC_ULP_TRIG_EN) {
+ SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_WAKEUP_FORCE_EN);
+ }
+ // Configure timer wakeup
+ if ((s_config.wakeup_triggers & RTC_TIMER_TRIG_EN) &&
+ s_config.sleep_duration > 0) {
+ timer_wakeup_prepare();
+ }
+
// Enter deep sleep
- rtc_slp_prep_lite(pd_flags, 0);
- rtc_sleep(cycle_h, cycle_l, s_config.wakeup_triggers, 0);
+ rtc_sleep_config_t config = RTC_SLEEP_CONFIG_DEFAULT(pd_flags);
+ rtc_sleep_init(config);
+ rtc_sleep_start(s_config.wakeup_triggers, 0);
// Because RTC is in a slower clock domain than the CPU, it
// can take several CPU cycles for the sleep mode to start.
while (1) {
esp_err_t esp_deep_sleep_enable_ulp_wakeup()
{
#ifdef CONFIG_ULP_COPROC_ENABLED
- if(s_config.wakeup_triggers & RTC_EXT_EVENT0_TRIG_EN) {
+ if(s_config.wakeup_triggers & RTC_EXT0_TRIG_EN) {
ESP_LOGE(TAG, "Conflicting wake-up trigger: ext0");
return ESP_ERR_INVALID_STATE;
}
- s_config.wakeup_triggers |= RTC_SAR_TRIG_EN;
+ s_config.wakeup_triggers |= RTC_ULP_TRIG_EN;
return ESP_OK;
#else
return ESP_ERR_INVALID_STATE;
esp_err_t esp_deep_sleep_enable_timer_wakeup(uint64_t time_in_us)
{
- s_config.wakeup_triggers |= RTC_TIMER_EXPIRE_EN;
+ s_config.wakeup_triggers |= RTC_TIMER_TRIG_EN;
s_config.sleep_duration = time_in_us;
return ESP_OK;
}
+static void timer_wakeup_prepare()
+{
+ // Do calibration if not using 32k XTAL
+ uint32_t period;
+ if (rtc_clk_slow_freq_get() != RTC_SLOW_FREQ_32K_XTAL) {
+ period = rtc_clk_cal(RTC_CAL_RTC_MUX, 128);
+ } else {
+ period = (uint32_t) ((1000000ULL /* us*Hz */ << RTC_CLK_CAL_FRACT) / 32768 /* Hz */);
+ }
+ uint64_t rtc_count_delta = rtc_time_us_to_slowclk(s_config.sleep_duration, period);
+ uint64_t cur_rtc_count = rtc_time_get();
+ rtc_sleep_set_wakeup_time(cur_rtc_count + rtc_count_delta);
+}
+
esp_err_t esp_deep_sleep_enable_touchpad_wakeup()
{
- if (s_config.wakeup_triggers & (RTC_EXT_EVENT0_TRIG_EN)) {
+ if (s_config.wakeup_triggers & (RTC_EXT0_TRIG_EN)) {
ESP_LOGE(TAG, "Conflicting wake-up trigger: ext0");
return ESP_ERR_INVALID_STATE;
}
if (!RTC_GPIO_IS_VALID_GPIO(gpio_num)) {
return ESP_ERR_INVALID_ARG;
}
- if (s_config.wakeup_triggers & (RTC_TOUCH_TRIG_EN | RTC_SAR_TRIG_EN)) {
+ if (s_config.wakeup_triggers & (RTC_TOUCH_TRIG_EN | RTC_ULP_TRIG_EN)) {
ESP_LOGE(TAG, "Conflicting wake-up triggers: touch / ULP");
return ESP_ERR_INVALID_STATE;
}
s_config.ext0_rtc_gpio_num = rtc_gpio_desc[gpio_num].rtc_num;
s_config.ext0_trigger_level = level;
- s_config.wakeup_triggers |= RTC_EXT_EVENT0_TRIG_EN;
+ s_config.wakeup_triggers |= RTC_EXT0_TRIG_EN;
return ESP_OK;
}
}
s_config.ext1_rtc_gpio_mask = rtc_gpio_mask;
s_config.ext1_trigger_mode = mode;
- s_config.wakeup_triggers |= RTC_EXT_EVENT1_TRIG_EN;
+ s_config.wakeup_triggers |= RTC_EXT1_TRIG_EN;
return ESP_OK;
}
}
uint32_t wakeup_cause = REG_GET_FIELD(RTC_CNTL_WAKEUP_STATE_REG, RTC_CNTL_WAKEUP_CAUSE);
- if (wakeup_cause & RTC_EXT_EVENT0_TRIG) {
+ if (wakeup_cause & RTC_EXT0_TRIG_EN) {
return ESP_DEEP_SLEEP_WAKEUP_EXT0;
- } else if (wakeup_cause & RTC_EXT_EVENT1_TRIG) {
+ } else if (wakeup_cause & RTC_EXT1_TRIG_EN) {
return ESP_DEEP_SLEEP_WAKEUP_EXT1;
- } else if (wakeup_cause & RTC_TIMER_EXPIRE) {
+ } else if (wakeup_cause & RTC_TIMER_TRIG_EN) {
return ESP_DEEP_SLEEP_WAKEUP_TIMER;
- } else if (wakeup_cause & RTC_TOUCH_TRIG) {
+ } else if (wakeup_cause & RTC_TOUCH_TRIG_EN) {
return ESP_DEEP_SLEEP_WAKEUP_TOUCHPAD;
- } else if (wakeup_cause & RTC_SAR_TRIG) {
+ } else if (wakeup_cause & RTC_ULP_TRIG_EN) {
return ESP_DEEP_SLEEP_WAKEUP_ULP;
} else {
return ESP_DEEP_SLEEP_WAKEUP_UNDEFINED;
// RTC_PERIPH is needed for EXT0 wakeup.
// If RTC_PERIPH is auto, and EXT0 isn't enabled, power down RTC_PERIPH.
if (s_config.pd_options[ESP_PD_DOMAIN_RTC_PERIPH] == ESP_PD_OPTION_AUTO) {
- if (s_config.wakeup_triggers & RTC_EXT_EVENT0_TRIG_EN) {
+ if (s_config.wakeup_triggers & RTC_EXT0_TRIG_EN) {
s_config.pd_options[ESP_PD_DOMAIN_RTC_PERIPH] = ESP_PD_OPTION_ON;
- } else if (s_config.wakeup_triggers & (RTC_TOUCH_TRIG_EN | RTC_SAR_TRIG_EN)) {
+ } else if (s_config.wakeup_triggers & (RTC_TOUCH_TRIG_EN | RTC_ULP_TRIG_EN)) {
// In both rev. 0 and rev. 1 of ESP32, forcing power up of RTC_PERIPH
// prevents ULP timer and touch FSMs from working correctly.
s_config.pd_options[ESP_PD_DOMAIN_RTC_PERIPH] = ESP_PD_OPTION_OFF;
option_str[s_config.pd_options[ESP_PD_DOMAIN_RTC_FAST_MEM]]);
// Prepare flags based on the selected options
- uint32_t pd_flags = DEEP_SLEEP_PD_NORMAL;
+ uint32_t pd_flags = RTC_SLEEP_PD_DIG;
if (s_config.pd_options[ESP_PD_DOMAIN_RTC_FAST_MEM] != ESP_PD_OPTION_ON) {
- pd_flags |= DEEP_SLEEP_PD_RTC_FAST_MEM;
+ pd_flags |= RTC_SLEEP_PD_RTC_FAST_MEM;
}
if (s_config.pd_options[ESP_PD_DOMAIN_RTC_SLOW_MEM] != ESP_PD_OPTION_ON) {
- pd_flags |= DEEP_SLEEP_PD_RTC_SLOW_MEM;
+ pd_flags |= RTC_SLEEP_PD_RTC_SLOW_MEM;
}
if (s_config.pd_options[ESP_PD_DOMAIN_RTC_PERIPH] != ESP_PD_OPTION_ON) {
- pd_flags |= DEEP_SLEEP_PD_RTC_PERIPH;
+ pd_flags |= RTC_SLEEP_PD_RTC_PERIPH;
}
return pd_flags;
}
* RTC_CNTL_STORE7_REG FAST_RTC_MEMORY_CRC
*************************************************************************************
*/
+
#define RTC_BOOT_TIME_LOW_REG RTC_CNTL_STORE2_REG
#define RTC_BOOT_TIME_HIGH_REG RTC_CNTL_STORE3_REG
+#define RTC_XTAL_FREQ_REG RTC_CNTL_STORE4_REG
+#define RTC_APB_FREQ_REG RTC_CNTL_STORE5_REG
#define RTC_ENTRY_ADDR_REG RTC_CNTL_STORE6_REG
#define RTC_MEMORY_CRC_REG RTC_CNTL_STORE7_REG
*libesp32.a:heap_alloc_caps.o(.literal .text .literal.* .text.*)
*libphy.a:(.literal .text .literal.* .text.*)
*librtc.a:(.literal .text .literal.* .text.*)
- *librtc_clk.a:(.literal .text .literal.* .text.*)
- *librtc_pm.a:(.literal .text .literal.* .text.*)
+ *libsoc.a:(.literal .text .literal.* .text.*)
*libpp.a:pp.o(.literal .text .literal.* .text.*)
*libpp.a:lmac.o(.literal .text .literal.* .text.*)
*libpp.a:wdev.o(.literal .text .literal.* .text.*)
*/
void coex_bt_high_prio(void);
+/**
+ * @brief Shutdown PHY and RF.
+ */
+void phy_close_rf(void);
+
#ifdef __cplusplus
}
#endif
#include "rom/ets_sys.h"
#include "rom/rtc.h"
+#include "soc/rtc.h"
#include "soc/dport_reg.h"
#include "esp_err.h"
#ifdef CONFIG_PHY_ENABLED
#include "phy.h"
#include "phy_init_data.h"
-#include "rtc.h"
#include "esp_coexist.h"
static const char* TAG = "phy_init";
+++ /dev/null
-// 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.
-
-/**
- * @file rtc.h
- * @brief Declarations of APIs provided by librtc.a
- *
- * This file is not in the include directory of esp32 component, so it is not
- * part of the public API. As the source code of librtc.a is gradually moved
- * into the ESP-IDF, some of these APIs will be exposed to applications.
- *
- * For now, only esp_deep_sleep function declared in esp_deepsleep.h
- * is part of public API.
- */
-
-#pragma once
-#include <stdint.h>
-#include <stddef.h>
-#include "soc/soc.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-
-typedef enum{
- XTAL_40M = 40,
- XTAL_26M = 26,
- XTAL_24M = 24,
- XTAL_AUTO = 0
-} xtal_freq_t;
-
-typedef enum{
- CPU_XTAL = 0,
- CPU_80M = 1,
- CPU_160M = 2,
- CPU_240M = 3,
- CPU_2M = 4
-} cpu_freq_t;
-
-typedef enum {
- CALI_RTC_MUX = 0,
- CALI_8MD256 = 1,
- CALI_32K_XTAL = 2
-} cali_clk_t;
-
-/**
- * This function must be called to initialize RTC library
- * @param xtal_freq Frequency of main crystal
- */
-void rtc_init_lite(xtal_freq_t xtal_freq);
-
-/**
- * Switch CPU frequency
- * @param cpu_freq new CPU frequency
- */
-void rtc_set_cpu_freq(cpu_freq_t cpu_freq);
-
-/**
- * @brief Return RTC slow clock's period
- * @param cali_clk clock to calibrate
- * @param slow_clk_cycles number of slow clock cycles to average
- * @param xtal_freq chip's main XTAL freq
- * @return average slow clock period in microseconds, Q13.19 fixed point format
- */
-uint32_t rtc_slowck_cali(cali_clk_t cali_clk, uint32_t slow_clk_cycles);
-
-/**
- * @brief Convert from microseconds to slow clock cycles
- * @param time_in_us_h Time in microseconds, higher 32 bit part
- * @param time_in_us_l Time in microseconds, lower 32 bit part
- * @param slow_clk_period Period of slow clock in microseconds, Q13.19 fixed point format (as returned by rtc_slowck_cali).
- * @param[out] cylces_h output, higher 32 bit part of number of slow clock cycles
- * @param[out] cycles_l output, lower 32 bit part of number of slow clock cycles
- */
-void rtc_usec2rtc(uint32_t time_in_us_h, uint32_t time_in_us_l, uint32_t slow_clk_period, uint32_t *cylces_h, uint32_t *cycles_l);
-
-
-#define DEEP_SLEEP_PD_NORMAL BIT(0) /*!< Base deep sleep mode */
-#define DEEP_SLEEP_PD_RTC_PERIPH BIT(1) /*!< Power down RTC peripherals */
-#define DEEP_SLEEP_PD_RTC_SLOW_MEM BIT(2) /*!< Power down RTC SLOW memory */
-#define DEEP_SLEEP_PD_RTC_FAST_MEM BIT(3) /*!< Power down RTC FAST memory */
-
-/**
- * @brief Prepare for entering sleep mode
- * @param deep_slp DEEP_SLEEP_PD_ flags combined with OR (DEEP_SLEEP_PD_NORMAL must be included)
- * @param cpu_lp_mode for deep sleep, should be 0
- */
-void rtc_slp_prep_lite(uint32_t deep_slp, uint32_t cpu_lp_mode);
-
-
-#define RTC_EXT_EVENT0_TRIG BIT(0)
-#define RTC_EXT_EVENT1_TRIG BIT(1)
-#define RTC_GPIO_TRIG BIT(2)
-#define RTC_TIMER_EXPIRE BIT(3)
-#define RTC_SDIO_TRIG BIT(4)
-#define RTC_MAC_TRIG BIT(5)
-#define RTC_UART0_TRIG BIT(6)
-#define RTC_UART1_TRIG BIT(7)
-#define RTC_TOUCH_TRIG BIT(8)
-#define RTC_SAR_TRIG BIT(9)
-#define RTC_BT_TRIG BIT(10)
-
-
-#define RTC_EXT_EVENT0_TRIG_EN RTC_EXT_EVENT0_TRIG
-#define RTC_EXT_EVENT1_TRIG_EN RTC_EXT_EVENT1_TRIG
-#define RTC_GPIO_TRIG_EN RTC_GPIO_TRIG
-#define RTC_TIMER_EXPIRE_EN RTC_TIMER_EXPIRE
-#define RTC_SDIO_TRIG_EN RTC_SDIO_TRIG
-#define RTC_MAC_TRIG_EN RTC_MAC_TRIG
-#define RTC_UART0_TRIG_EN RTC_UART0_TRIG
-#define RTC_UART1_TRIG_EN RTC_UART1_TRIG
-#define RTC_TOUCH_TRIG_EN RTC_TOUCH_TRIG
-#define RTC_SAR_TRIG_EN RTC_SAR_TRIG
-#define RTC_BT_TRIG_EN RTC_BT_TRIG
-
-/**
- * @brief Enter sleep mode for given number of cycles
- * @param cycles_h higher 32 bit part of number of slow clock cycles
- * @param cycles_l lower 32 bit part of number of slow clock cycles
- * @param wakeup_opt wake up reason to enable (RTC_xxx_EN flags combined with OR)
- * @param reject_opt reserved, should be 0
- * @return TBD
- */
-uint32_t rtc_sleep(uint32_t cycles_h, uint32_t cycles_l, uint32_t wakeup_opt, uint32_t reject_opt);
-
-/**
- * @brief Shutdown PHY and RF. TODO: convert this function to another one.
- */
-void phy_close_rf(void);
-
-#ifdef __cplusplus
-}
-#endif
-
#include "soc/timer_group_reg.h"
#include "soc/timer_group_struct.h"
#include "soc/cpu.h"
+#include "soc/rtc.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/xtensa_api.h"
-#include "rtc.h"
static const char* TAG = "system_api";
REG_WRITE(DPORT_PERIP_RST_EN_REG, 0);
// Set CPU back to XTAL source, no PLL, same as hard reset
- rtc_set_cpu_freq(CPU_XTAL);
+ rtc_clk_cpu_freq_set(RTC_CPU_FREQ_XTAL);
// Reset CPUs
if (core_id == 0) {
--- /dev/null
+# currently the only SoC supported; to be moved into Kconfig
+SOC_NAME := esp32
+
+COMPONENT_SRCDIRS := $(SOC_NAME)
+COMPONENT_ADD_INCLUDEDIRS := $(SOC_NAME)/include
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+/**
+ * @file i2c_apll.h
+ * @brief Register definitions for audio PLL (APLL)
+ *
+ * This file lists register fields of APLL, located on an internal configuration
+ * bus. These definitions are used via macros defined in i2c_rtc_clk.h, by
+ * rtc_clk_apll_enable function in rtc_clk.c.
+ */
+
+#define I2C_APLL 0X6D
+#define I2C_APLL_HOSTID 3
+
+#define I2C_APLL_IR_CAL_DELAY 0
+#define I2C_APLL_IR_CAL_DELAY_MSB 3
+#define I2C_APLL_IR_CAL_DELAY_LSB 0
+
+#define I2C_APLL_IR_CAL_RSTB 0
+#define I2C_APLL_IR_CAL_RSTB_MSB 4
+#define I2C_APLL_IR_CAL_RSTB_LSB 4
+
+#define I2C_APLL_IR_CAL_START 0
+#define I2C_APLL_IR_CAL_START_MSB 5
+#define I2C_APLL_IR_CAL_START_LSB 5
+
+#define I2C_APLL_IR_CAL_UNSTOP 0
+#define I2C_APLL_IR_CAL_UNSTOP_MSB 6
+#define I2C_APLL_IR_CAL_UNSTOP_LSB 6
+
+#define I2C_APLL_OC_ENB_FCAL 0
+#define I2C_APLL_OC_ENB_FCAL_MSB 7
+#define I2C_APLL_OC_ENB_FCAL_LSB 7
+
+#define I2C_APLL_IR_CAL_EXT_CAP 1
+#define I2C_APLL_IR_CAL_EXT_CAP_MSB 4
+#define I2C_APLL_IR_CAL_EXT_CAP_LSB 0
+
+#define I2C_APLL_IR_CAL_ENX_CAP 1
+#define I2C_APLL_IR_CAL_ENX_CAP_MSB 5
+#define I2C_APLL_IR_CAL_ENX_CAP_LSB 5
+
+#define I2C_APLL_OC_LBW 1
+#define I2C_APLL_OC_LBW_MSB 6
+#define I2C_APLL_OC_LBW_LSB 6
+
+#define I2C_APLL_IR_CAL_CK_DIV 2
+#define I2C_APLL_IR_CAL_CK_DIV_MSB 3
+#define I2C_APLL_IR_CAL_CK_DIV_LSB 0
+
+#define I2C_APLL_OC_DCHGP 2
+#define I2C_APLL_OC_DCHGP_MSB 6
+#define I2C_APLL_OC_DCHGP_LSB 4
+
+#define I2C_APLL_OC_ENB_VCON 2
+#define I2C_APLL_OC_ENB_VCON_MSB 7
+#define I2C_APLL_OC_ENB_VCON_LSB 7
+
+#define I2C_APLL_OR_CAL_CAP 3
+#define I2C_APLL_OR_CAL_CAP_MSB 4
+#define I2C_APLL_OR_CAL_CAP_LSB 0
+
+#define I2C_APLL_OR_CAL_UDF 3
+#define I2C_APLL_OR_CAL_UDF_MSB 5
+#define I2C_APLL_OR_CAL_UDF_LSB 5
+
+#define I2C_APLL_OR_CAL_OVF 3
+#define I2C_APLL_OR_CAL_OVF_MSB 6
+#define I2C_APLL_OR_CAL_OVF_LSB 6
+
+#define I2C_APLL_OR_CAL_END 3
+#define I2C_APLL_OR_CAL_END_MSB 7
+#define I2C_APLL_OR_CAL_END_LSB 7
+
+#define I2C_APLL_OR_OUTPUT_DIV 4
+#define I2C_APLL_OR_OUTPUT_DIV_MSB 4
+#define I2C_APLL_OR_OUTPUT_DIV_LSB 0
+
+#define I2C_APLL_OC_TSCHGP 4
+#define I2C_APLL_OC_TSCHGP_MSB 6
+#define I2C_APLL_OC_TSCHGP_LSB 6
+
+#define I2C_APLL_EN_FAST_CAL 4
+#define I2C_APLL_EN_FAST_CAL_MSB 7
+#define I2C_APLL_EN_FAST_CAL_LSB 7
+
+#define I2C_APLL_OC_DHREF_SEL 5
+#define I2C_APLL_OC_DHREF_SEL_MSB 1
+#define I2C_APLL_OC_DHREF_SEL_LSB 0
+
+#define I2C_APLL_OC_DLREF_SEL 5
+#define I2C_APLL_OC_DLREF_SEL_MSB 3
+#define I2C_APLL_OC_DLREF_SEL_LSB 2
+
+#define I2C_APLL_SDM_DITHER 5
+#define I2C_APLL_SDM_DITHER_MSB 4
+#define I2C_APLL_SDM_DITHER_LSB 4
+
+#define I2C_APLL_SDM_STOP 5
+#define I2C_APLL_SDM_STOP_MSB 5
+#define I2C_APLL_SDM_STOP_LSB 5
+
+#define I2C_APLL_SDM_RSTB 5
+#define I2C_APLL_SDM_RSTB_MSB 6
+#define I2C_APLL_SDM_RSTB_LSB 6
+
+#define I2C_APLL_OC_DVDD 6
+#define I2C_APLL_OC_DVDD_MSB 4
+#define I2C_APLL_OC_DVDD_LSB 0
+
+#define I2C_APLL_DSDM2 7
+#define I2C_APLL_DSDM2_MSB 5
+#define I2C_APLL_DSDM2_LSB 0
+
+#define I2C_APLL_DSDM1 8
+#define I2C_APLL_DSDM1_MSB 7
+#define I2C_APLL_DSDM1_LSB 0
+
+#define I2C_APLL_DSDM0 9
+#define I2C_APLL_DSDM0_MSB 7
+#define I2C_APLL_DSDM0_LSB 0
+
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+/**
+ * @file i2c_apll.h
+ * @brief Register definitions for digital PLL (BBPLL)
+ *
+ * This file lists register fields of BBPLL, located on an internal configuration
+ * bus. These definitions are used via macros defined in i2c_rtc_clk.h, by
+ * rtc_clk_cpu_freq_set function in rtc_clk.c.
+ */
+
+#define I2C_BBPLL 0x66
+#define I2C_BBPLL_HOSTID 4
+
+#define I2C_BBPLL_IR_CAL_DELAY 0
+#define I2C_BBPLL_IR_CAL_DELAY_MSB 3
+#define I2C_BBPLL_IR_CAL_DELAY_LSB 0
+
+#define I2C_BBPLL_IR_CAL_CK_DIV 0
+#define I2C_BBPLL_IR_CAL_CK_DIV_MSB 7
+#define I2C_BBPLL_IR_CAL_CK_DIV_LSB 4
+
+#define I2C_BBPLL_IR_CAL_EXT_CAP 1
+#define I2C_BBPLL_IR_CAL_EXT_CAP_MSB 3
+#define I2C_BBPLL_IR_CAL_EXT_CAP_LSB 0
+
+#define I2C_BBPLL_IR_CAL_ENX_CAP 1
+#define I2C_BBPLL_IR_CAL_ENX_CAP_MSB 4
+#define I2C_BBPLL_IR_CAL_ENX_CAP_LSB 4
+
+#define I2C_BBPLL_IR_CAL_RSTB 1
+#define I2C_BBPLL_IR_CAL_RSTB_MSB 5
+#define I2C_BBPLL_IR_CAL_RSTB_LSB 5
+
+#define I2C_BBPLL_IR_CAL_START 1
+#define I2C_BBPLL_IR_CAL_START_MSB 6
+#define I2C_BBPLL_IR_CAL_START_LSB 6
+
+#define I2C_BBPLL_IR_CAL_UNSTOP 1
+#define I2C_BBPLL_IR_CAL_UNSTOP_MSB 7
+#define I2C_BBPLL_IR_CAL_UNSTOP_LSB 7
+
+#define I2C_BBPLL_OC_REF_DIV 2
+#define I2C_BBPLL_OC_REF_DIV_MSB 3
+#define I2C_BBPLL_OC_REF_DIV_LSB 0
+
+#define I2C_BBPLL_OC_DIV_10_8 2
+#define I2C_BBPLL_OC_DIV_10_8_MSB 6
+#define I2C_BBPLL_OC_DIV_10_8_LSB 4
+
+#define I2C_BBPLL_OC_LREF 2
+#define I2C_BBPLL_OC_LREF_MSB 7
+#define I2C_BBPLL_OC_LREF_LSB 7
+
+#define I2C_BBPLL_OC_DIV_7_0 3
+#define I2C_BBPLL_OC_DIV_7_0_MSB 7
+#define I2C_BBPLL_OC_DIV_7_0_LSB 0
+
+#define I2C_BBPLL_OC_ENB_FCAL 4
+#define I2C_BBPLL_OC_ENB_FCAL_MSB 0
+#define I2C_BBPLL_OC_ENB_FCAL_LSB 0
+
+#define I2C_BBPLL_OC_DCHGP 4
+#define I2C_BBPLL_OC_DCHGP_MSB 3
+#define I2C_BBPLL_OC_DCHGP_LSB 1
+
+#define I2C_BBPLL_OC_DHREF_SEL 4
+#define I2C_BBPLL_OC_DHREF_SEL_MSB 5
+#define I2C_BBPLL_OC_DHREF_SEL_LSB 4
+
+#define I2C_BBPLL_OC_DLREF_SEL 4
+#define I2C_BBPLL_OC_DLREF_SEL_MSB 7
+#define I2C_BBPLL_OC_DLREF_SEL_LSB 6
+
+#define I2C_BBPLL_OC_DCUR 5
+#define I2C_BBPLL_OC_DCUR_MSB 2
+#define I2C_BBPLL_OC_DCUR_LSB 0
+
+#define I2C_BBPLL_OC_BST_DIV 5
+#define I2C_BBPLL_OC_BST_DIV_MSB 3
+#define I2C_BBPLL_OC_BST_DIV_LSB 3
+
+#define I2C_BBPLL_OC_BST_E2C 5
+#define I2C_BBPLL_OC_BST_E2C_MSB 4
+#define I2C_BBPLL_OC_BST_E2C_LSB 4
+
+#define I2C_BBPLL_OC_TSCHGP 5
+#define I2C_BBPLL_OC_TSCHGP_MSB 5
+#define I2C_BBPLL_OC_TSCHGP_LSB 5
+
+#define I2C_BBPLL_OC_BW 5
+#define I2C_BBPLL_OC_BW_MSB 7
+#define I2C_BBPLL_OC_BW_LSB 6
+
+#define I2C_BBPLL_OR_LOCK1 6
+#define I2C_BBPLL_OR_LOCK1_MSB 0
+#define I2C_BBPLL_OR_LOCK1_LSB 0
+
+#define I2C_BBPLL_OR_LOCK2 6
+#define I2C_BBPLL_OR_LOCK2_MSB 1
+#define I2C_BBPLL_OR_LOCK2_LSB 1
+
+#define I2C_BBPLL_OR_CAL_CAP 7
+#define I2C_BBPLL_OR_CAL_CAP_MSB 3
+#define I2C_BBPLL_OR_CAL_CAP_LSB 0
+
+#define I2C_BBPLL_OR_CAL_UDF 7
+#define I2C_BBPLL_OR_CAL_UDF_MSB 4
+#define I2C_BBPLL_OR_CAL_UDF_LSB 4
+
+#define I2C_BBPLL_OR_CAL_OVF 7
+#define I2C_BBPLL_OR_CAL_OVF_MSB 5
+#define I2C_BBPLL_OR_CAL_OVF_LSB 5
+
+#define I2C_BBPLL_OR_CAL_END 7
+#define I2C_BBPLL_OR_CAL_END_MSB 6
+#define I2C_BBPLL_OR_CAL_END_LSB 6
+
+#define I2C_BBPLL_BBADC_DELAY1 8
+#define I2C_BBPLL_BBADC_DELAY1_MSB 1
+#define I2C_BBPLL_BBADC_DELAY1_LSB 0
+
+#define I2C_BBPLL_BBADC_DELAY2 8
+#define I2C_BBPLL_BBADC_DELAY2_MSB 3
+#define I2C_BBPLL_BBADC_DELAY2_LSB 2
+
+#define I2C_BBPLL_BBADC_DELAY3 8
+#define I2C_BBPLL_BBADC_DELAY3_MSB 5
+#define I2C_BBPLL_BBADC_DELAY3_LSB 4
+
+#define I2C_BBPLL_BBADC_DELAY4 8
+#define I2C_BBPLL_BBADC_DELAY4_MSB 7
+#define I2C_BBPLL_BBADC_DELAY4_LSB 6
+
+#define I2C_BBPLL_BBADC_DELAY5 9
+#define I2C_BBPLL_BBADC_DELAY5_MSB 1
+#define I2C_BBPLL_BBADC_DELAY5_LSB 0
+
+#define I2C_BBPLL_BBADC_DELAY6 9
+#define I2C_BBPLL_BBADC_DELAY6_MSB 3
+#define I2C_BBPLL_BBADC_DELAY6_LSB 2
+
+#define I2C_BBPLL_BBADC_DSMP 9
+#define I2C_BBPLL_BBADC_DSMP_MSB 7
+#define I2C_BBPLL_BBADC_DSMP_LSB 4
+
+#define I2C_BBPLL_DTEST 10
+#define I2C_BBPLL_DTEST_MSB 1
+#define I2C_BBPLL_DTEST_LSB 0
+
+#define I2C_BBPLL_ENT_ADC 10
+#define I2C_BBPLL_ENT_ADC_MSB 3
+#define I2C_BBPLL_ENT_ADC_LSB 2
+
+#define I2C_BBPLL_BBADC_DIV 10
+#define I2C_BBPLL_BBADC_DIV_MSB 5
+#define I2C_BBPLL_BBADC_DIV_LSB 4
+
+#define I2C_BBPLL_ENT_PLL 10
+#define I2C_BBPLL_ENT_PLL_MSB 6
+#define I2C_BBPLL_ENT_PLL_LSB 6
+
+#define I2C_BBPLL_OC_ENB_VCON 10
+#define I2C_BBPLL_OC_ENB_VCON_MSB 7
+#define I2C_BBPLL_OC_ENB_VCON_LSB 7
+
+#define I2C_BBPLL_DIV_DAC 11
+#define I2C_BBPLL_DIV_DAC_MSB 0
+#define I2C_BBPLL_DIV_DAC_LSB 0
+
+#define I2C_BBPLL_DIV_CPU 11
+#define I2C_BBPLL_DIV_CPU_MSB 1
+#define I2C_BBPLL_DIV_CPU_LSB 1
+
+#define I2C_BBPLL_BBADC_INPUT_SHORT 11
+#define I2C_BBPLL_BBADC_INPUT_SHORT_MSB 2
+#define I2C_BBPLL_BBADC_INPUT_SHORT_LSB 2
+
+#define I2C_BBPLL_BBADC_CAL_9_8 11
+#define I2C_BBPLL_BBADC_CAL_9_8_MSB 4
+#define I2C_BBPLL_BBADC_CAL_9_8_LSB 3
+
+#define I2C_BBPLL_BBADC_DCM 11
+#define I2C_BBPLL_BBADC_DCM_MSB 6
+#define I2C_BBPLL_BBADC_DCM_LSB 5
+
+#define I2C_BBPLL_ENDIV5 11
+#define I2C_BBPLL_ENDIV5_MSB 7
+#define I2C_BBPLL_ENDIV5_LSB 7
+
+#define I2C_BBPLL_BBADC_CAL_7_0 12
+#define I2C_BBPLL_BBADC_CAL_7_0_MSB 7
+#define I2C_BBPLL_BBADC_CAL_7_0_LSB 0
+
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+#include "i2c_apll.h"
+#include "i2c_bbpll.h"
+
+/* Analog function control register */
+#define ANA_CONFIG_REG 0x6000E044
+#define ANA_CONFIG_S (8)
+#define ANA_CONFIG_M (0x3FF)
+/* Clear to enable APLL */
+#define I2C_APLL_M (BIT(14))
+/* Clear to enable BBPLL */
+#define I2C_BBPLL_M (BIT(17))
+
+/* ROM functions which read/write internal control bus */
+uint8_t rom_i2c_readReg(uint8_t block, uint8_t host_id, uint8_t reg_add);
+uint8_t rom_i2c_readReg_Mask(uint8_t block, uint8_t host_id, uint8_t reg_add, uint8_t msb, uint8_t lsb);
+void rom_i2c_writeReg(uint8_t block, uint8_t host_id, uint8_t reg_add, uint8_t data);
+void rom_i2c_writeReg_Mask(uint8_t block, uint8_t host_id, uint8_t reg_add, uint8_t msb, uint8_t lsb, uint8_t data);
+
+/* Convenience macros for the above functions, these use register definitions
+ * from i2c_apll.h/i2c_bbpll.h header files.
+ */
+#define I2C_WRITEREG_MASK_RTC(block, reg_add, indata) \
+ rom_i2c_writeReg_Mask(block, block##_HOSTID, reg_add, reg_add##_MSB, reg_add##_LSB, indata)
+
+#define I2C_READREG_MASK_RTC(block, reg_add) \
+ rom_i2c_readReg_Mask(block, block##_HOSTID, reg_add, reg_add##_MSB, reg_add##_LSB)
+
+#define I2C_WRITEREG_RTC(block, reg_add, indata) \
+ rom_i2c_writeReg(block, block##_HOSTID, reg_add, indata)
+
+#define I2C_READREG_RTC(block, reg_add) \
+ rom_i2c_readReg(block, block##_HOSTID, reg_add)
#ifndef _SOC_BB_REG_H_
#define _SOC_BB_REG_H_
-#define apb_bb_offset 0x6001c000
+/* Some of the baseband control registers.
+ * PU/PD fields defined here are used in sleep related functions.
+ */
+
+#define BBPD_CTRL (DR_REG_BB_BASE + 0x0054)
+#define BB_FFT_FORCE_PU (BIT(3))
+#define BB_FFT_FORCE_PU_S 3
+#define BB_FFT_FORCE_PD (BIT(2))
+#define BB_FFT_FORCE_PD_S 2
+#define BB_DC_EST_FORCE_PU (BIT(1))
+#define BB_DC_EST_FORCE_PU_S 1
+#define BB_DC_EST_FORCE_PD (BIT(0))
+#define BB_DC_EST_FORCE_PD_S 0
-#define BB_DLY apb_bb_offset + 0x00009b00 // reg 00
-#define BB_TEST apb_bb_offset + 0x00009b08 // reg 02
-#define BB_TM1 apb_bb_offset + 0x00009b0c // reg 03
-#define BB_TM_CNTL apb_bb_offset + 0x00009b14 // reg 05
-#define BB_DEL_CNTL apb_bb_offset + 0x00009b28 // reg 10
-#define BB_PARAL_CNTL apb_bb_offset + 0x00009b2c // reg 11
-#define BB_FSM1 apb_bb_offset + 0x00009b44 // reg 17
-#define BB_MXG apb_bb_offset + 0x00009b48 // reg 18
-#define BB_MNOF apb_bb_offset + 0x00009b4c // reg 19
-#define BB_SIZE apb_bb_offset + 0x00009b50 // reg 20
-#define BB_TM3a apb_bb_offset + 0x00009b54 // reg 21
-#define BB_TM4a apb_bb_offset + 0x00009b58 // reg 22
-#define BB_GAIN apb_bb_offset + 0x00009b5c // reg 23
-#define BB_CNTL apb_bb_offset + 0x00009b60 // reg 24
-#define BB_CAD apb_bb_offset + 0x00009b64 // reg 25
-#define BB_DET apb_bb_offset + 0x00009b68 // reg 26
-#define BB_DETL apb_bb_offset + 0x00009b6c // reg 27
-
-#define BB_MASK_PCLL apb_bb_offset + 0x00009d08 // reg 66
-#define BB_MASK_PCLH apb_bb_offset + 0x00009d0c // reg 67
-#define BB_RX_CTRL4 apb_bb_offset + 0x00009d10 // reg 68
-#define BB_RX_CTRL apb_bb_offset + 0x00009d1c // reg 71
-#define BB_RX_CTRL2 apb_bb_offset + 0x00009d20 // reg 72
-#define BB_RX_CTRL3 apb_bb_offset + 0x00009d24 // reg 73
-#define BB_DEL4 apb_bb_offset + 0x00009d40 // reg 80
-#define BB_TM5 apb_bb_offset + 0x00009d44 // reg 81
-#define BB_TM6 apb_bb_offset + 0x00009d48 // reg 82
-#define BB_PMCTRL apb_bb_offset + 0x00009d4c // reg 83
-#define BB_PWR apb_bb_offset + 0x00009d68 // reg 90
-#define BB_BCTRL2 apb_bb_offset + 0x00009d70 // reg 92
-
-#define BB_MASK_PL apb_bb_offset + 0x00009884 // reg 97
-#define BB_MASK_PCHL apb_bb_offset + 0x00009888 // reg 98
-#define BB_MASK_PCHH apb_bb_offset + 0x0000988c // reg 99
-
-#define BB_MASK_CL apb_bb_offset + 0x0000989c // reg 103
-#define BB_TONE apb_bb_offset + 0x000098a0 // reg 104
-#define BB_MASK_CH apb_bb_offset + 0x000098d4 // reg 117
-#define BB_SER apb_bb_offset + 0x000098ec // reg 123
-#define BB_GN_TB apb_bb_offset + 0x00009e00 // reg 128
-
-#define BB_MODE apb_bb_offset + 0x00009c00 // reg 640
-#define BB_TXCTRL apb_bb_offset + 0x00009c04 // reg 641
-#define BB_BCTRL3 apb_bb_offset + 0x00009c08 // reg 642
-#define BB_BCTRL apb_bb_offset + 0x00009c28 // reg 650
-#define BB_SMCTRL apb_bb_offset + 0x00009c48 // reg 658
-#define BB_SMCTRL2 apb_bb_offset + 0x00009c4C // reg 659
-#define BB_TXCNT apb_bb_offset + 0x00009c58 // reg 662
-#define BB_RXCTRL apb_bb_offset + 0x00009c68 // reg 666
-
-#define BB_TXGAIN apb_bb_offset + 0x00009900 // reg 704
-
-#define BB_RXS_CNTL apb_bb_offset + 0x00009988 // reg 738
-#define BB_MASK2_PCLL apb_bb_offset + 0x000099a8 // reg 746
-#define BB_MASK2_PCLH apb_bb_offset + 0x000099ac // reg 747
-#define BB_MASK_PH apb_bb_offset + 0x000099b0 // reg 748
-#define BB_MASK2_PCHL apb_bb_offset + 0x000099b8 // reg 750
-#define BB_MASK2_PCHH apb_bb_offset + 0x000099bc // reg 751
-//
-#define BB_TX_TONE_CNTL apb_bb_offset + 0x000099f0 // reg 764
-#define BB_ADD_CNTL0 apb_bb_offset + 0x00009a28 // reg 778
-#define BB_ADD_CNTL2 apb_bb_offset + 0x00009a2c // reg 779
-#define BB_GAIN_CNTL0 apb_bb_offset + 0x00009a34 // reg 781
-#define BB_GAIN_CNTL1 apb_bb_offset + 0x00009a38 // reg 782
-#define BB_GAIN_CNTL2 apb_bb_offset + 0x00009a3c // reg 783
-#define BB_AGCMEM_CTRL apb_bb_offset + 0x00009a68 // reg 794
-
-#define BB_11B_RECORD apb_bb_offset + 0x00009808 // reg 802
-#define BB_FILTER_CNTL apb_bb_offset + 0x0000980c // reg 803
-#define BB_ANALOG_CTRL1 apb_bb_offset + 0x00009838
-#define BB_ANALOG_CTRL2 apb_bb_offset + 0x0000983c //reg 815
-#define BB_ANALOG_CTRL3 apb_bb_offset + 0x00009840 //reg 816
-#define BB_RFCFG_CTRL0 apb_bb_offset + 0x00009844 //reg 817
-#define BB_RFCFG_CTRL1 apb_bb_offset + 0x00009848 //reg 818
-
-#define BB_ADD_CNTL1 apb_bb_offset + 0x00009860 //reg824
-#define BB_PA_CNTL apb_bb_offset + 0x00009864 //reg825
-#define BB_RFCFG_CTRL2 apb_bb_offset + 0x0000986c //reg827
-#define BB_RXDEL_CTRL apb_bb_offset + 0x00009d18
-#define BB_RXLENGTH_CTRL apb_bb_offset + 0x00009d1c
#endif /* _SOC_BB_REG_H_ */
--- /dev/null
+// 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.
+
+#pragma once
+
+#include "soc/soc.h"
+
+/* Some of the RF frontend control registers.
+ * PU/PD fields defined here are used in sleep related functions.
+ */
+
+#define FE_GEN_CTRL (DR_REG_FE_BASE + 0x0090)
+#define FE_IQ_EST_FORCE_PU (BIT(5))
+#define FE_IQ_EST_FORCE_PU_S 5
+#define FE_IQ_EST_FORCE_PD (BIT(4))
+#define FE_IQ_EST_FORCE_PD_S 4
+
+#define FE2_TX_INTERP_CTRL (DR_REG_FE2_BASE + 0x00f0)
+#define FE2_TX_INF_FORCE_PU (BIT(10))
+#define FE2_TX_INF_FORCE_PU_S 10
+#define FE2_TX_INF_FORCE_PD (BIT(9))
+#define FE2_TX_INF_FORCE_PD_S 9
--- /dev/null
+// 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.
+
+#pragma once
+
+#include "soc/soc.h"
+
+/* Some of the WiFi RX control registers.
+ * PU/PD fields defined here are used in sleep related functions.
+ */
+
+#define NRXPD_CTRL (DR_REG_NRX_BASE + 0x00d4)
+#define NRX_CHAN_EST_FORCE_PU (BIT(7))
+#define NRX_CHAN_EST_FORCE_PU_S 7
+#define NRX_CHAN_EST_FORCE_PD (BIT(6))
+#define NRX_CHAN_EST_FORCE_PD_S 6
+#define NRX_RX_ROT_FORCE_PU (BIT(5))
+#define NRX_RX_ROT_FORCE_PU_S 5
+#define NRX_RX_ROT_FORCE_PD (BIT(4))
+#define NRX_RX_ROT_FORCE_PD_S 4
+#define NRX_VIT_FORCE_PU (BIT(3))
+#define NRX_VIT_FORCE_PU_S 3
+#define NRX_VIT_FORCE_PD (BIT(2))
+#define NRX_VIT_FORCE_PD_S 2
+#define NRX_DEMAP_FORCE_PU (BIT(1))
+#define NRX_DEMAP_FORCE_PU_S 1
+#define NRX_DEMAP_FORCE_PD (BIT(0))
+#define NRX_DEMAP_FORCE_PD_S 0
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+#pragma once
+
+#include <stdbool.h>
+#include <stddef.h>
+#include <stdint.h>
+#include "soc/soc.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @file rtc.h
+ * @brief Low-level RTC power, clock, and sleep functions.
+ *
+ * Functions in this file facilitate configuration of ESP32's RTC_CNTL peripheral.
+ * RTC_CNTL peripheral handles many functions:
+ * - enables/disables clocks and power to various parts of the chip; this is
+ * done using direct register access (forcing power up or power down) or by
+ * allowing state machines to control power and clocks automatically
+ * - handles sleep and wakeup functions
+ * - maintains a 48-bit counter which can be used for timekeeping
+ *
+ * These functions are not thread safe, and should not be viewed as high level
+ * APIs. For example, while this file provides a function which can switch
+ * CPU frequency, this function is on its own is not sufficient to implement
+ * frequency switching in ESP-IDF context: some coordination with RTOS,
+ * peripheral drivers, and WiFi/BT stacks is also required.
+ *
+ * These functions will normally not be used in applications directly.
+ * ESP-IDF provides, or will provide, drivers and other facilities to use
+ * RTC subsystem functionality.
+ *
+ * The functions are loosely split into the following groups:
+ * - rtc_clk: clock switching, calibration
+ * - rtc_time: reading RTC counter, conversion between counter values and time
+ * - rtc_sleep: entry into sleep modes
+ * - rtc_init: initialization
+ */
+
+
+/**
+ * @brief Possible main XTAL frequency values.
+ *
+ * Enum values should be equal to frequency in MHz.
+ */
+typedef enum {
+ RTC_XTAL_FREQ_AUTO = 0, //!< Automatic XTAL frequency detection
+ RTC_XTAL_FREQ_40M = 40, //!< 40 MHz XTAL
+ RTC_XTAL_FREQ_26M = 26, //!< 26 MHz XTAL
+ RTC_XTAL_FREQ_24M = 24, //!< 24 MHz XTAL
+} rtc_xtal_freq_t;
+
+/**
+ * @brief CPU frequency values
+ */
+typedef enum {
+ RTC_CPU_FREQ_XTAL = 0, //!< Main XTAL frequency
+ RTC_CPU_FREQ_80M = 1, //!< 80 MHz
+ RTC_CPU_FREQ_160M = 2, //!< 160 MHz
+ RTC_CPU_FREQ_240M = 3, //!< 240 MHz
+ RTC_CPU_FREQ_2M = 4, //!< 2 MHz
+} rtc_cpu_freq_t;
+
+/**
+ * @brief RTC SLOW_CLK frequency values
+ */
+typedef enum {
+ RTC_SLOW_FREQ_RTC = 0, //!< Internal 150 kHz RC oscillator
+ RTC_SLOW_FREQ_32K_XTAL = 1, //!< External 32 kHz XTAL
+ RTC_SLOW_FREQ_8MD256 = 2, //!< Internal 8 MHz RC oscillator, divided by 256
+} rtc_slow_freq_t;
+
+/**
+ * @brief RTC FAST_CLK frequency values
+ */
+typedef enum {
+ RTC_FAST_FREQ_XTALD4 = 0, //!< Main XTAL, divided by 4
+ RTC_FAST_FREQ_8M = 1, //!< Internal 8 MHz RC oscillator
+} rtc_fast_freq_t;
+
+/**
+ * @brief Clock source to be calibrated using rtc_clk_cal function
+ */
+typedef enum {
+ RTC_CAL_RTC_MUX = 0, //!< Currently selected RTC SLOW_CLK
+ RTC_CAL_8MD256 = 1, //!< Internal 8 MHz RC oscillator, divided by 256
+ RTC_CAL_32K_XTAL = 2 //!< External 32 kHz XTAL
+} rtc_cal_sel_t;
+
+/**
+ * Initialization parameters for rtc_clk_init
+ */
+typedef struct {
+ rtc_xtal_freq_t xtal_freq : 8; //!< Main XTAL frequency
+ rtc_cpu_freq_t cpu_freq : 3; //!< CPU frequency to set
+ rtc_fast_freq_t fast_freq : 1; //!< RTC_FAST_CLK frequency to set
+ rtc_slow_freq_t slow_freq : 2; //!< RTC_SLOW_CLK frequency to set
+ uint32_t clk_8m_div : 3; //!< RTC 8M clock divider (division is by clk_8m_div+1, i.e. 0 means 8MHz frequency)
+ uint32_t slow_clk_dcap : 8; //!< RTC 150k clock adjustment parameter (higher value leads to lower frequency)
+ uint32_t clk_8m_dfreq : 8; //!< RTC 8m clock adjustment parameter (higher value leads to higher frequency)
+} rtc_clk_config_t;
+
+/**
+ * Default initializer for rtc_clk_config_t
+ */
+#define RTC_CLK_CONFIG_DEFAULT() { \
+ .xtal_freq = RTC_XTAL_FREQ_AUTO, \
+ .cpu_freq = RTC_CPU_FREQ_80M, \
+ .fast_freq = RTC_FAST_FREQ_8M, \
+ .slow_freq = RTC_SLOW_FREQ_RTC, \
+ .clk_8m_div = 0, \
+ .slow_clk_dcap = RTC_CNTL_SCK_DCAP_DEFAULT, \
+ .clk_8m_dfreq = RTC_CNTL_CK8M_DFREQ_DEFAULT, \
+}
+
+/**
+ * Initialize clocks and set CPU frequency
+ *
+ * If cfg.xtal_freq is set to RTC_XTAL_FREQ_AUTO, this function will attempt
+ * to auto detect XTAL frequency. Auto detection is performed by comparing
+ * XTAL frequency with the frequency of internal 8MHz oscillator. Note that at
+ * high temperatures the frequency of the internal 8MHz oscillator may drift
+ * enough for auto detection to be unreliable.
+ * Auto detection code will attempt to distinguish between 26MHz and 40MHz
+ * crystals. 24 MHz crystals are not supported by auto detection code.
+ * If XTAL frequency can not be auto detected, this 26MHz frequency will be used.
+ *
+ * @param cfg clock configuration as rtc_clk_config_t
+ */
+void rtc_clk_init(rtc_clk_config_t cfg);
+
+/**
+ * @brief Get main XTAL frequency
+ *
+ * This is the value passed to rtc_clk_init function, or if the value was
+ * RTC_XTAL_FREQ_AUTO, the detected XTAL frequency.
+ *
+ * @return XTAL frequency, one of rtc_xtal_freq_t
+ */
+rtc_xtal_freq_t rtc_clk_xtal_freq_get();
+
+/**
+ * @brief Enable or disable 32 kHz XTAL oscillator
+ * @param en true to enable, false to disable
+ */
+void rtc_clk_32k_enable(bool en);
+
+/**
+ * @brief Get the state of 32k XTAL oscillator
+ * @return true if 32k XTAL oscillator has been enabled
+ */
+bool rtc_clk_32k_enabled();
+
+/**
+ * @brief Enable or disable 8 MHz internal oscillator
+ *
+ * Output from 8 MHz internal oscillator is passed into a configurable
+ * divider, which by default divides the input clock frequency by 256.
+ * Output of the divider may be used as RTC_SLOW_CLK source.
+ * Output of the divider is referred to in register descriptions and code as
+ * 8md256 or simply d256. Divider values other than 256 may be configured, but
+ * this facility is not currently needed, so is not exposed in the code.
+ *
+ * When 8MHz/256 divided output is not needed, the divider should be disabled
+ * to reduce power consumption.
+ *
+ * @param clk_8m_en true to enable 8MHz generator
+ * @param d256_en true to enable /256 divider
+ */
+void rtc_clk_8m_enable(bool clk_8m_en, bool d256_en);
+
+/**
+ * @brief Get the state of 8 MHz internal oscillator
+ * @return true if the oscillator is enabled
+ */
+bool rtc_clk_8m_enabled();
+
+/**
+ * @brief Get the state of /256 divider which is applied to 8MHz clock
+ * @return true if the divided output is enabled
+ */
+bool rtc_clk_8md256_enabled();
+
+/**
+ * @brief Enable or disable APLL
+ *
+ * Output frequency is given by the formula:
+ * apll_freq = xtal_freq * (4 + sdm2 + sdm1/256 + sdm0/65536)/((o_div + 2) * 2)
+ *
+ * The dividend in this expression should be in the range of 240 - 600 MHz.
+ *
+ * In rev. 0 of ESP32, sdm0 and sdm1 are unused and always set to 0.
+ *
+ * @param enable true to enable, false to disable
+ * @param sdm0 frequency adjustment parameter, 0..255
+ * @param sdm1 frequency adjustment parameter, 0..255
+ * @param sdm2 frequency adjustment parameter, 0..63
+ * @param o_div frequency divider, 0..31
+ */
+void rtc_clk_apll_enable(bool enable, uint32_t sdm0, uint32_t sdm1,
+ uint32_t sdm2, uint32_t o_div);
+
+/**
+ * @brief Select source for RTC_SLOW_CLK
+ * @param slow_freq clock source (one of rtc_slow_freq_t values)
+ */
+void rtc_clk_slow_freq_set(rtc_slow_freq_t slow_freq);
+
+/**
+ * @brief Get the RTC_SLOW_CLK source
+ * @return currently selected clock source (one of rtc_slow_freq_t values)
+ */
+rtc_slow_freq_t rtc_clk_slow_freq_get();
+
+/**
+ * @brief Select source for RTC_FAST_CLK
+ * @param fast_freq clock source (one of rtc_fast_freq_t values)
+ */
+void rtc_clk_fast_freq_set(rtc_fast_freq_t fast_freq);
+
+/**
+ * @brief Get the RTC_FAST_CLK source
+ * @return currently selected clock source (one of rtc_fast_freq_t values)
+ */
+rtc_fast_freq_t rtc_clk_fast_freq_get();
+
+/**
+ * @brief Switch CPU frequency
+ *
+ * If a PLL-derived frequency is requested (80, 160, 240 MHz), this function
+ * will enable the PLL. Otherwise, PLL will be disabled.
+ * Note: this function is not optimized for switching speed. It may take several
+ * hundred microseconds to perform frequency switch.
+ *
+ * @param cpu_freq new CPU frequency
+ */
+void rtc_clk_cpu_freq_set(rtc_cpu_freq_t cpu_freq);
+
+/**
+ * @brief Get the currently selected CPU frequency
+ *
+ * Although CPU can be clocked by APLL and RTC 8M sources, such support is not
+ * exposed through this library. As such, this function will not return
+ * meaningful values when these clock sources are configured (e.g. using direct
+ * access to clock selection registers). In debug builds, it will assert; in
+ * release builds, it will return RTC_CPU_FREQ_XTAL.
+ *
+ * @return CPU frequency (one of rtc_cpu_freq_t values)
+ */
+rtc_cpu_freq_t rtc_clk_cpu_freq_get();
+
+/**
+ * @brief Get corresponding frequency value for rtc_cpu_freq_t enum value
+ * @param cpu_freq CPU frequency, on of rtc_cpu_freq_t values
+ * @return CPU frequency, in HZ
+ */
+uint32_t rtc_clk_cpu_freq_value(rtc_cpu_freq_t cpu_freq);
+
+/**
+ * @brief Store new APB frequency value into RTC_APB_FREQ_REG
+ *
+ * This function doesn't change any hardware clocks.
+ *
+ * Functions which perform frequency switching and change APB frequency call
+ * this function to update the value of APB frequency stored in RTC_APB_FREQ_REG
+ * (one of RTC general purpose retention registers). This should not normally
+ * be called from application code.
+ *
+ * @param apb_freq new APB frequency, in Hz
+ */
+void rtc_clk_apb_freq_update(uint32_t apb_freq);
+
+/**
+ * @brief Get the current stored APB frequency.
+ * @return The APB frequency value as last set via rtc_clk_apb_freq_update(), in Hz.
+ */
+uint32_t rtc_clk_apb_freq_get();
+
+#define RTC_CLK_CAL_FRACT 19 //!< Number of fractional bits in values returned by rtc_clk_cal
+
+/**
+ * @brief Measure RTC slow clock's period, based on main XTAL frequency
+ *
+ * This function will time out and return 0 if the time for the given number
+ * of cycles to be counted exceeds the expected time twice. This may happen if
+ * 32k XTAL is being calibrated, but the oscillator has not started up (due to
+ * incorrect loading capacitance, board design issue, or lack of 32 XTAL on board).
+ *
+ * @param cal_clk clock to be measured
+ * @param slow_clk_cycles number of slow clock cycles to average
+ * @return average slow clock period in microseconds, Q13.19 fixed point format,
+ * or 0 if calibration has timed out
+ */
+uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slow_clk_cycles);
+
+/**
+ * @brief Convert time interval from microseconds to RTC_SLOW_CLK cycles
+ * @param time_in_us Time interval in microseconds
+ * @param slow_clk_period Period of slow clock in microseconds, Q13.19
+ * fixed point format (as returned by rtc_slowck_cali).
+ * @return number of slow clock cycles
+ */
+uint64_t rtc_time_us_to_slowclk(uint64_t time_in_us, uint32_t period);
+
+/**
+ * @brief Convert time interval from RTC_SLOW_CLK to microseconds
+ * @param time_in_us Time interval in RTC_SLOW_CLK cycles
+ * @param slow_clk_period Period of slow clock in microseconds, Q13.19
+ * fixed point format (as returned by rtc_slowck_cali).
+ * @return time interval in microseconds
+ */
+uint64_t rtc_time_slowclk_to_us(uint64_t rtc_cycles, uint32_t period);
+
+/**
+ * @brief Get current value of RTC counter
+ *
+ * RTC has a 48-bit counter which is incremented by 2 every 2 RTC_SLOW_CLK
+ * cycles. Counter value is not writable by software. The value is not adjusted
+ * when switching to a different RTC_SLOW_CLK source.
+ *
+ * Note: this function may take up to 1 RTC_SLOW_CLK cycle to execute
+ *
+ * @return current value of RTC counter
+ */
+uint64_t rtc_time_get();
+
+/**
+ * @brief sleep configuration for rtc_sleep_init function
+ */
+typedef struct {
+ uint32_t soc_clk_sel : 2; //!< SoC clock select, see RTC_CNTL_SOC_CLK_SEL
+ uint32_t lslp_mem_inf_fpu : 1; //!< force normal voltage in sleep mode (digital domain memory)
+ uint32_t rtc_mem_inf_fpu : 1; //!< force normal voltage in sleep mode (RTC memory)
+ uint32_t rtc_mem_inf_follow_cpu : 1;//!< keep low voltage in sleep mode (even if ULP/touch is used)
+ uint32_t rtc_fastmem_pd_en : 1; //!< power down RTC fast memory
+ uint32_t rtc_slowmem_pd_en : 1; //!< power down RTC slow memory
+ uint32_t rtc_peri_pd_en : 1; //!< power down RTC peripherals
+ uint32_t wifi_pd_en : 1; //!< power down WiFi
+ uint32_t rom_mem_pd_en : 1; //!< power down main RAM and ROM
+ uint32_t deep_slp : 1; //!< power down digital domain
+ uint32_t wdt_flashboot_mod_en : 1; //!< enable WDT flashboot mode
+ uint32_t dig_dbias_wak : 3; //!< set bias for digital domain, in active mode
+ uint32_t dig_dbias_slp : 3; //!< set bias for digital domain, in sleep mode
+ uint32_t rtc_dbias_wak : 3; //!< set bias for RTC domain, in active mode
+ uint32_t rtc_dbias_slp : 3; //!< set bias for RTC domain, in sleep mode
+ uint32_t lslp_meminf_pd : 1; //!< remove all peripheral force power up flags
+} rtc_sleep_config_t;
+
+/**
+ * Default initializer for rtc_sleep_config_t
+ *
+ * This initializer sets all fields to "reasonable" values (e.g. suggested for
+ * production use) based on a combination of RTC_SLEEP_PD_x flags.
+ *
+ * @param RTC_SLEEP_PD_x flags combined using bitwise OR
+ */
+#define RTC_SLEEP_CONFIG_DEFAULT(sleep_flags) { \
+ .soc_clk_sel = RTC_CNTL_SOC_CLK_SEL_XTL, \
+ .lslp_mem_inf_fpu = 0, \
+ .rtc_mem_inf_fpu = 0, \
+ .rtc_mem_inf_follow_cpu = ((sleep_flags) & RTC_SLEEP_PD_RTC_MEM_FOLLOW_CPU) ? 1 : 0, \
+ .rtc_fastmem_pd_en = ((sleep_flags) & RTC_SLEEP_PD_RTC_FAST_MEM) ? 1 : 0, \
+ .rtc_slowmem_pd_en = ((sleep_flags) & RTC_SLEEP_PD_RTC_SLOW_MEM) ? 1 : 0, \
+ .rtc_peri_pd_en = ((sleep_flags) & RTC_SLEEP_PD_RTC_PERIPH) ? 1 : 0, \
+ .wifi_pd_en = 0, \
+ .rom_mem_pd_en = 0, \
+ .deep_slp = ((sleep_flags) & RTC_SLEEP_PD_DIG) ? 1 : 0, \
+ .wdt_flashboot_mod_en = 0, \
+ .dig_dbias_wak = RTC_CNTL_DBIAS_1V10, \
+ .dig_dbias_slp = RTC_CNTL_DBIAS_0V90, \
+ .rtc_dbias_wak = RTC_CNTL_DBIAS_0V90, \
+ .rtc_dbias_slp = RTC_CNTL_DBIAS_0V90, \
+ .lslp_meminf_pd = 1 \
+};
+
+#define RTC_SLEEP_PD_DIG BIT(0) //!< Deep sleep (power down digital domain)
+#define RTC_SLEEP_PD_RTC_PERIPH BIT(1) //!< Power down RTC peripherals
+#define RTC_SLEEP_PD_RTC_SLOW_MEM BIT(2) //!< Power down RTC SLOW memory
+#define RTC_SLEEP_PD_RTC_FAST_MEM BIT(3) //!< Power down RTC FAST memory
+#define RTC_SLEEP_PD_RTC_MEM_FOLLOW_CPU BIT(4) //!< RTC FAST and SLOW memories are automatically powered up and down along with the CPU
+
+/**
+ * @brief Prepare the chip to enter sleep mode
+ *
+ * This function configures various power control state machines to handle
+ * entry into light sleep or deep sleep mode, switches APB and CPU clock source
+ * (usually to XTAL), and sets bias voltages for digital and RTC power domains.
+ *
+ * This function does not actually enter sleep mode; this is done using
+ * rtc_sleep_start function. Software may do some other actions between
+ * rtc_sleep_init and rtc_sleep_start, such as set wakeup timer and configure
+ * wakeup sources.
+ * @param cfg sleep mode configuration
+ */
+void rtc_sleep_init(rtc_sleep_config_t cfg);
+
+
+/**
+ * @brief Set target value of RTC counter for RTC_TIMER_TRIG_EN wakeup source
+ * @param t value of RTC counter at which wakeup from sleep will happen;
+ * only the lower 48 bits are used
+ */
+void rtc_sleep_set_wakeup_time(uint64_t t);
+
+
+#define RTC_EXT0_TRIG_EN BIT(0) //!< EXT0 GPIO wakeup
+#define RTC_EXT1_TRIG_EN BIT(1) //!< EXT1 GPIO wakeup
+#define RTC_GPIO_TRIG_EN BIT(2) //!< GPIO wakeup (light sleep only)
+#define RTC_TIMER_TRIG_EN BIT(3) //!< Timer wakeup
+#define RTC_SDIO_TRIG_EN BIT(4) //!< SDIO wakeup (light sleep only)
+#define RTC_MAC_TRIG_EN BIT(5) //!< MAC wakeup (light sleep only)
+#define RTC_UART0_TRIG_EN BIT(6) //!< UART0 wakeup (light sleep only)
+#define RTC_UART1_TRIG_EN BIT(7) //!< UART1 wakeup (light sleep only)
+#define RTC_TOUCH_TRIG_EN BIT(8) //!< Touch wakeup
+#define RTC_ULP_TRIG_EN BIT(9) //!< ULP wakeup
+#define RTC_BT_TRIG_EN BIT(10) //!< BT wakeup (light sleep only)
+
+/**
+ * @brief Enter deep or light sleep mode
+ *
+ * This function enters the sleep mode previously configured using rtc_sleep_init
+ * function. Before entering sleep, software should configure wake up sources
+ * appropriately (set up GPIO wakeup registers, timer wakeup registers,
+ * and so on).
+ *
+ * If deep sleep mode was configured using rtc_sleep_init, and sleep is not
+ * rejected by hardware (based on reject_opt flags), this function never returns.
+ * When the chip wakes up from deep sleep, CPU is reset and execution starts
+ * from ROM bootloader.
+ *
+ * If light sleep mode was configured using rtc_sleep_init, this function
+ * returns on wakeup, or if sleep is rejected by hardware.
+ *
+ * @param wakeup_opt bit mask wake up reasons to enable (RTC_xxx_TRIG_EN flags
+ * combined with OR)
+ * @param reject_opt bit mask of sleep reject reasons:
+ * - RTC_CNTL_GPIO_REJECT_EN
+ * - RTC_CNTL_SDIO_REJECT_EN
+ * These flags are used to prevent entering sleep when e.g.
+ * an external host is communicating via SDIO slave
+ * @return non-zero if sleep was rejected by hardware
+ */
+uint32_t rtc_sleep_start(uint32_t wakeup_opt, uint32_t reject_opt);
+
+/**
+ * RTC power and clock control initialization settings
+ */
+typedef struct {
+ uint32_t ck8m_wait : 8; //!< Number of rtc_fast_clk cycles to wait for 8M clock to be ready
+ uint32_t xtal_wait : 8; //!< Number of rtc_fast_clk cycles to wait for XTAL clock to be ready
+ uint32_t pll_wait : 8; //!< Number of rtc_fast_clk cycles to wait for PLL to be ready
+ uint32_t clkctl_init : 1; //!< Perform clock control related initialization
+ uint32_t pwrctl_init : 1; //!< Perform power control related initialization
+ uint32_t rtc_dboost_fpd : 1; //!< Force power down RTC_DBOOST
+} rtc_config_t;
+
+/**
+ * Default initializer of rtc_config_t.
+ *
+ * This initializer sets all fields to "reasonable" values (e.g. suggested for
+ * production use).
+ */
+#define RTC_CONFIG_DEFAULT() {\
+ .ck8m_wait = RTC_CNTL_CK8M_WAIT_DEFAULT, \
+ .xtal_wait = RTC_CNTL_XTL_BUF_WAIT_DEFAULT, \
+ .pll_wait = RTC_CNTL_PLL_BUF_WAIT_DEFAULT, \
+ .clkctl_init = 1, \
+ .pwrctl_init = 1, \
+ .rtc_dboost_fpd = 1 \
+}
+
+/**
+ * Initialize RTC clock and power control related functions
+ * @param cfg configuration options as rtc_config_t
+ */
+void rtc_init(rtc_config_t cfg);
+
+
+#ifdef __cplusplus
+}
+#endif
+
#define RTC_CNTL_PLL_BUF_WAIT_M ((RTC_CNTL_PLL_BUF_WAIT_V)<<(RTC_CNTL_PLL_BUF_WAIT_S))
#define RTC_CNTL_PLL_BUF_WAIT_V 0xFF
#define RTC_CNTL_PLL_BUF_WAIT_S 24
+#define RTC_CNTL_PLL_BUF_WAIT_DEFAULT 20
/* RTC_CNTL_XTL_BUF_WAIT : R/W ;bitpos:[23:14] ;default: 10'd80 ; */
/*description: XTAL wait cycles in slow_clk_rtc*/
#define RTC_CNTL_XTL_BUF_WAIT 0x000003FF
#define RTC_CNTL_XTL_BUF_WAIT_M ((RTC_CNTL_XTL_BUF_WAIT_V)<<(RTC_CNTL_XTL_BUF_WAIT_S))
#define RTC_CNTL_XTL_BUF_WAIT_V 0x3FF
#define RTC_CNTL_XTL_BUF_WAIT_S 14
+#define RTC_CNTL_XTL_BUF_WAIT_DEFAULT 20
/* RTC_CNTL_CK8M_WAIT : R/W ;bitpos:[13:6] ;default: 8'h10 ; */
/*description: CK8M wait cycles in slow_clk_rtc*/
#define RTC_CNTL_CK8M_WAIT 0x000000FF
#define RTC_CNTL_CK8M_WAIT_M ((RTC_CNTL_CK8M_WAIT_V)<<(RTC_CNTL_CK8M_WAIT_S))
#define RTC_CNTL_CK8M_WAIT_V 0xFF
#define RTC_CNTL_CK8M_WAIT_S 6
+#define RTC_CNTL_CK8M_WAIT_DEFAULT 20
/* RTC_CNTL_CPU_STALL_WAIT : R/W ;bitpos:[5:1] ;default: 5'd1 ; */
/*description: CPU stall wait cycles in fast_clk_rtc*/
#define RTC_CNTL_CPU_STALL_WAIT 0x0000001F
#define RTC_CNTL_SOC_CLK_SEL_M ((RTC_CNTL_SOC_CLK_SEL_V)<<(RTC_CNTL_SOC_CLK_SEL_S))
#define RTC_CNTL_SOC_CLK_SEL_V 0x3
#define RTC_CNTL_SOC_CLK_SEL_S 27
+#define RTC_CNTL_SOC_CLK_SEL_XTL 0
+#define RTC_CNTL_SOC_CLK_SEL_PLL 1
+#define RTC_CNTL_SOC_CLK_SEL_8M 2
+#define RTC_CNTL_SOC_CLK_SEL_APLL 3
/* RTC_CNTL_CK8M_FORCE_PU : R/W ;bitpos:[26] ;default: 1'd0 ; */
/*description: CK8M force power up*/
#define RTC_CNTL_CK8M_FORCE_PU (BIT(26))
#define RTC_CNTL_CK8M_DFREQ_M ((RTC_CNTL_CK8M_DFREQ_V)<<(RTC_CNTL_CK8M_DFREQ_S))
#define RTC_CNTL_CK8M_DFREQ_V 0xFF
#define RTC_CNTL_CK8M_DFREQ_S 17
+#define RTC_CNTL_CK8M_DFREQ_DEFAULT 172
/* RTC_CNTL_CK8M_FORCE_NOGATING : R/W ;bitpos:[16] ;default: 1'd0 ; */
/*description: CK8M force no gating during sleep*/
#define RTC_CNTL_CK8M_FORCE_NOGATING (BIT(16))
#define RTC_CNTL_SCK_DCAP_M ((RTC_CNTL_SCK_DCAP_V)<<(RTC_CNTL_SCK_DCAP_S))
#define RTC_CNTL_SCK_DCAP_V 0xFF
#define RTC_CNTL_SCK_DCAP_S 14
+#define RTC_CNTL_SCK_DCAP_DEFAULT 255
/* RTC_CNTL_DIG_DBIAS_WAK : R/W ;bitpos:[13:11] ;default: 3'd4 ; */
/*description: DIG_REG_DBIAS during wakeup*/
#define RTC_CNTL_DIG_DBIAS_WAK 0x00000007
#define RTC_CNTL_SCK_DCAP_FORCE_V 0x1
#define RTC_CNTL_SCK_DCAP_FORCE_S 7
+/* Approximate mapping of voltages to RTC_CNTL_DBIAS_WAK, RTC_CNTL_DBIAS_SLP,
+ * RTC_CNTL_DIG_DBIAS_WAK, RTC_CNTL_DIG_DBIAS_SLP values.
+ * Valid if RTC_CNTL_DBG_ATTEN is 0.
+ */
+#define RTC_CNTL_DBIAS_0V90 0
+#define RTC_CNTL_DBIAS_0V95 1
+#define RTC_CNTL_DBIAS_1V00 2
+#define RTC_CNTL_DBIAS_1V05 3
+#define RTC_CNTL_DBIAS_1V10 4
+#define RTC_CNTL_DBIAS_1V15 5
+#define RTC_CNTL_DBIAS_1V20 6
+#define RTC_CNTL_DBIAS_1V25 7
+
#define RTC_CNTL_PWC_REG (DR_REG_RTCCNTL_BASE + 0x80)
/* RTC_CNTL_PD_EN : R/W ;bitpos:[20] ;default: 1'd0 ; */
/*description: enable power down rtc_peri in sleep*/
#define RTC_CNTL_FASTMEM_FORCE_NOISO_V 0x1
#define RTC_CNTL_FASTMEM_FORCE_NOISO_S 0
+/* Useful groups of RTC_CNTL_PWC_REG bits */
+#define RTC_CNTL_MEM_FORCE_ISO \
+ (RTC_CNTL_SLOWMEM_FORCE_ISO | RTC_CNTL_FASTMEM_FORCE_ISO)
+#define RTC_CNTL_MEM_FORCE_NOISO \
+ (RTC_CNTL_SLOWMEM_FORCE_NOISO | RTC_CNTL_FASTMEM_FORCE_NOISO)
+#define RTC_CNTL_MEM_PD_EN \
+ (RTC_CNTL_SLOWMEM_PD_EN | RTC_CNTL_FASTMEM_PD_EN)
+#define RTC_CNTL_MEM_FORCE_PU \
+ (RTC_CNTL_SLOWMEM_FORCE_PU | RTC_CNTL_FASTMEM_FORCE_PU)
+#define RTC_CNTL_MEM_FORCE_PD \
+ (RTC_CNTL_SLOWMEM_FORCE_PD | RTC_CNTL_FASTMEM_FORCE_PD)
+#define RTC_CNTL_MEM_FOLW_CPU \
+ (RTC_CNTL_SLOWMEM_FOLW_CPU | RTC_CNTL_FASTMEM_FOLW_CPU)
+#define RTC_CNTL_MEM_FORCE_LPU \
+ (RTC_CNTL_SLOWMEM_FORCE_LPU | RTC_CNTL_FASTMEM_FORCE_LPU)
+#define RTC_CNTL_MEM_FORCE_LPD \
+ (RTC_CNTL_SLOWMEM_FORCE_LPD | RTC_CNTL_FASTMEM_FORCE_LPD)
+
#define RTC_CNTL_DIG_PWC_REG (DR_REG_RTCCNTL_BASE + 0x84)
/* RTC_CNTL_DG_WRAP_PD_EN : R/W ;bitpos:[31] ;default: 0 ; */
/*description: enable power down digital core in sleep*/
#define RTC_CNTL_LSLP_MEM_FORCE_PD_V 0x1
#define RTC_CNTL_LSLP_MEM_FORCE_PD_S 3
+/* Useful groups of RTC_CNTL_DIG_PWC_REG bits */
+#define RTC_CNTL_CPU_ROM_RAM_PD_EN \
+ (RTC_CNTL_INTER_RAM4_PD_EN | RTC_CNTL_INTER_RAM3_PD_EN |\
+ RTC_CNTL_INTER_RAM2_PD_EN | RTC_CNTL_INTER_RAM1_PD_EN |\
+ RTC_CNTL_INTER_RAM0_PD_EN | RTC_CNTL_ROM0_PD_EN)
+#define RTC_CNTL_CPU_ROM_RAM_FORCE_PU \
+ (RTC_CNTL_INTER_RAM4_FORCE_PU | RTC_CNTL_INTER_RAM3_FORCE_PU |\
+ RTC_CNTL_INTER_RAM2_FORCE_PU | RTC_CNTL_INTER_RAM1_FORCE_PU |\
+ RTC_CNTL_INTER_RAM0_FORCE_PU | RTC_CNTL_ROM0_FORCE_PU)
+#define RTC_CNTL_CPU_ROM_RAM_FORCE_PD \
+ (RTC_CNTL_INTER_RAM4_FORCE_PD | RTC_CNTL_INTER_RAM3_FORCE_PD |\
+ RTC_CNTL_INTER_RAM2_FORCE_PD | RTC_CNTL_INTER_RAM1_FORCE_PD |\
+ RTC_CNTL_INTER_RAM0_FORCE_PD | RTC_CNTL_ROM0_FORCE_PD
+
#define RTC_CNTL_DIG_ISO_REG (DR_REG_RTCCNTL_BASE + 0x88)
/* RTC_CNTL_DG_WRAP_FORCE_NOISO : R/W ;bitpos:[31] ;default: 1'd1 ; */
/*description: digital core force no ISO*/
#define RTC_CNTL_DIG_ISO_FORCE_OFF_V 0x1
#define RTC_CNTL_DIG_ISO_FORCE_OFF_S 7
+/* Useful groups of RTC_CNTL_DIG_ISO_REG bits */
+#define RTC_CNTL_CPU_ROM_RAM_FORCE_ISO \
+ (RTC_CNTL_INTER_RAM4_FORCE_ISO | RTC_CNTL_INTER_RAM3_FORCE_ISO |\
+ RTC_CNTL_INTER_RAM2_FORCE_ISO | RTC_CNTL_INTER_RAM1_FORCE_ISO |\
+ RTC_CNTL_INTER_RAM0_FORCE_ISO | RTC_CNTL_ROM0_FORCE_ISO)
+#define RTC_CNTL_CPU_ROM_RAM_FORCE_NOISO \
+ (RTC_CNTL_INTER_RAM4_FORCE_NOISO | RTC_CNTL_INTER_RAM3_FORCE_NOISO |\
+ RTC_CNTL_INTER_RAM2_FORCE_NOISO | RTC_CNTL_INTER_RAM1_FORCE_NOISO |\
+ RTC_CNTL_INTER_RAM0_FORCE_NOISO | RTC_CNTL_ROM0_FORCE_NOISO)
+
#define RTC_CNTL_WDTCONFIG0_REG (DR_REG_RTCCNTL_BASE + 0x8c)
/* RTC_CNTL_WDT_EN : R/W ;bitpos:[31] ;default: 1'h0 ; */
/*description: enable RTC WDT*/
#define RTC_IO_DEBUG_SEL0_M ((RTC_IO_DEBUG_SEL0_V)<<(RTC_IO_DEBUG_SEL0_S))
#define RTC_IO_DEBUG_SEL0_V 0x1F
#define RTC_IO_DEBUG_SEL0_S 0
+#define RTC_IO_DEBUG_SEL0_32K_XTAL 4
+#define RTC_IO_DEBUG_SEL0_150K_OSC 5
#define RTC_IO_DIG_PAD_HOLD_REG (DR_REG_RTCIO_BASE + 0x74)
/* RTC_IO_DIG_PAD_HOLD : R/W ;bitpos:[31:0] ;default: 1'd0 ; */
#define DR_REG_LEDC_BASE 0x3ff59000
#define DR_REG_EFUSE_BASE 0x3ff5A000
#define DR_REG_SPI_ENCRYPT_BASE 0x3ff5B000
+#define DR_REG_NRX_BASE 0x3ff5CC00
+#define DR_REG_BB_BASE 0x3ff5D000
#define DR_REG_PWM_BASE 0x3ff5E000
#define DR_REG_TIMERGROUP0_BASE 0x3ff5F000
#define DR_REG_TIMERGROUP1_BASE 0x3ff60000
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include <stdbool.h>
+#include <stdint.h>
+#include <stddef.h>
+#include <assert.h>
+#include "rom/ets_sys.h"
+#include "rom/rtc.h"
+#include "rom/uart.h"
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+#include "soc/rtc_io_reg.h"
+#include "soc/sens_reg.h"
+#include "soc/dport_reg.h"
+#include "soc/efuse_reg.h"
+#include "soc/apb_ctrl_reg.h"
+#include "i2c_rtc_clk.h"
+#include "soc_log.h"
+#include "sdkconfig.h"
+
+#define MHZ (1000000)
+
+static const char* TAG = "rtc_clk";
+
+/* Various constants related to the analog internals of the chip.
+ * Defined here because they don't have any use outside of this file.
+ */
+
+#define BBPLL_ENDIV5_VAL_320M 0x43
+#define BBPLL_BBADC_DSMP_VAL_320M 0x84
+#define BBPLL_ENDIV5_VAL_480M 0xc3
+#define BBPLL_BBADC_DSMP_VAL_480M 0x74
+
+#define APLL_SDM_STOP_VAL_1 0x09
+#define APLL_SDM_STOP_VAL_2_REV0 0x69
+#define APLL_SDM_STOP_VAL_2_REV1 0x49
+
+#define APLL_CAL_DELAY_1 0x0f
+#define APLL_CAL_DELAY_2 0x3f
+#define APLL_CAL_DELAY_3 0x1f
+
+#define XTAL_32K_DAC_VAL 1
+#define XTAL_32K_DRES_VAL 3
+#define XTAL_32K_DBIAS_VAL 0
+
+/* Delays for various clock sources to be enabled/switched.
+ * All values are in microseconds.
+ * TODO: some of these are excessive, and should be reduced.
+ */
+#define DELAY_CPU_FREQ_SWITCH_TO_XTAL 80
+#define DELAY_CPU_FREQ_SWITCH_TO_PLL 10
+#define DELAY_PLL_DBIAS_RAISE 3
+#define DELAY_PLL_ENABLE 80
+#define DELAY_FAST_CLK_SWITCH 3
+#define DELAY_SLOW_CLK_SWITCH 300
+#define DELAY_8M_ENABLE 50
+
+
+void rtc_clk_32k_enable(bool enable)
+{
+ if (enable) {
+ SET_PERI_REG_MASK(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_X32N_MUX_SEL | RTC_IO_X32P_MUX_SEL);
+ CLEAR_PERI_REG_MASK(RTC_IO_XTAL_32K_PAD_REG,
+ RTC_IO_X32P_RDE | RTC_IO_X32P_RUE | RTC_IO_X32N_RUE |
+ RTC_IO_X32N_RDE | RTC_IO_X32N_MUX_SEL | RTC_IO_X32P_MUX_SEL);
+ REG_SET_FIELD(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_DAC_XTAL_32K, XTAL_32K_DAC_VAL);
+ REG_SET_FIELD(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_DRES_XTAL_32K, XTAL_32K_DRES_VAL);
+ REG_SET_FIELD(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_DBIAS_XTAL_32K, XTAL_32K_DBIAS_VAL);
+ SET_PERI_REG_MASK(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_XPD_XTAL_32K);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_XPD_XTAL_32K);
+ }
+}
+
+bool rtc_clk_32k_enabled()
+{
+ return GET_PERI_REG_MASK(RTC_IO_XTAL_32K_PAD_REG, RTC_IO_XPD_XTAL_32K) != 0;
+}
+
+void rtc_clk_8m_enable(bool clk_8m_en, bool d256_en)
+{
+ if (clk_8m_en) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M);
+ /* no need to wait once enabled by software */
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_CK8M_WAIT, 1);
+ if (d256_en) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M_DIV);
+ } else {
+ SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M_DIV);
+ }
+ ets_delay_us(DELAY_8M_ENABLE);
+ } else {
+ SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M);
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_CK8M_WAIT, RTC_CNTL_CK8M_WAIT_DEFAULT);
+ }
+}
+
+bool rtc_clk_8m_enabled()
+{
+ return GET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M) == 0;
+}
+
+bool rtc_clk_8md256_enabled()
+{
+ return GET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ENB_CK8M_DIV) == 0;
+}
+
+void rtc_clk_apll_enable(bool enable, uint32_t sdm0, uint32_t sdm1, uint32_t sdm2, uint32_t o_div)
+{
+ REG_SET_FIELD(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PLLA_FORCE_PD, enable ? 0 : 1);
+ REG_SET_FIELD(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PLLA_FORCE_PU, enable ? 1 : 0);
+ REG_SET_FIELD(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_I2C_FORCE_PD, enable ? 0 : 1);
+
+ if (!enable &&
+ REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL) != RTC_CNTL_SOC_CLK_SEL_PLL) {
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_I2C_FORCE_PD);
+ }
+
+ if (enable) {
+ uint8_t sdm_stop_val_2 = APLL_SDM_STOP_VAL_2_REV1;
+ uint32_t is_rev0 = (GET_PERI_REG_BITS2(EFUSE_BLK0_RDATA3_REG, 1, 15) == 0);
+ if (is_rev0) {
+ sdm0 = 0;
+ sdm1 = 0;
+ sdm_stop_val_2 = APLL_SDM_STOP_VAL_2_REV0;
+ }
+ I2C_WRITEREG_MASK_RTC(I2C_APLL, I2C_APLL_DSDM2, sdm2);
+ I2C_WRITEREG_MASK_RTC(I2C_APLL, I2C_APLL_DSDM0, sdm0);
+ I2C_WRITEREG_MASK_RTC(I2C_APLL, I2C_APLL_DSDM1, sdm1);
+ I2C_WRITEREG_RTC(I2C_APLL, I2C_APLL_SDM_STOP, APLL_SDM_STOP_VAL_1);
+ I2C_WRITEREG_RTC(I2C_APLL, I2C_APLL_SDM_STOP, sdm_stop_val_2);
+ I2C_WRITEREG_MASK_RTC(I2C_APLL, I2C_APLL_OR_OUTPUT_DIV, o_div);
+
+ /* calibration */
+ I2C_WRITEREG_RTC(I2C_APLL, I2C_APLL_IR_CAL_DELAY, APLL_CAL_DELAY_1);
+ I2C_WRITEREG_RTC(I2C_APLL, I2C_APLL_IR_CAL_DELAY, APLL_CAL_DELAY_2);
+ I2C_WRITEREG_RTC(I2C_APLL, I2C_APLL_IR_CAL_DELAY, APLL_CAL_DELAY_3);
+
+ /* wait for calibration end */
+ while (!(I2C_READREG_MASK_RTC(I2C_APLL, I2C_APLL_OR_CAL_END))) {
+ /* use ets_delay_us so the RTC bus doesn't get flooded */
+ ets_delay_us(1);
+ }
+ }
+}
+
+void rtc_clk_slow_freq_set(rtc_slow_freq_t slow_freq)
+{
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ANA_CLK_RTC_SEL, slow_freq);
+ ets_delay_us(DELAY_SLOW_CLK_SWITCH);
+}
+
+rtc_slow_freq_t rtc_clk_slow_freq_get()
+{
+ return REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ANA_CLK_RTC_SEL);
+}
+
+
+void rtc_clk_fast_freq_set(rtc_fast_freq_t fast_freq)
+{
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_FAST_CLK_RTC_SEL, fast_freq);
+ ets_delay_us(DELAY_FAST_CLK_SWITCH);
+}
+
+rtc_fast_freq_t rtc_clk_fast_freq_get()
+{
+ return REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_FAST_CLK_RTC_SEL);
+}
+
+void rtc_clk_bbpll_set(rtc_xtal_freq_t xtal_freq, rtc_cpu_freq_t cpu_freq)
+{
+ uint8_t div_ref;
+ uint8_t div7_0;
+ uint8_t div10_8;
+ uint8_t lref;
+ uint8_t dcur;
+ uint8_t bw;
+
+ if (cpu_freq != RTC_CPU_FREQ_240M) {
+ /* Configure 320M PLL */
+ switch (xtal_freq) {
+ case RTC_XTAL_FREQ_40M:
+ div_ref = 0;
+ div7_0 = 32;
+ div10_8 = 0;
+ lref = 0;
+ dcur = 6;
+ bw = 3;
+ break;
+ case RTC_XTAL_FREQ_26M:
+ div_ref = 12;
+ div7_0 = 224;
+ div10_8 = 4;
+ lref = 1;
+ dcur = 0;
+ bw = 1;
+ break;
+ case RTC_XTAL_FREQ_24M:
+ div_ref = 11;
+ div7_0 = 224;
+ div10_8 = 4;
+ lref = 1;
+ dcur = 0;
+ bw = 1;
+ break;
+ default:
+ div_ref = 12;
+ div7_0 = 224;
+ div10_8 = 4;
+ lref = 0;
+ dcur = 0;
+ bw = 0;
+ break;
+ }
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_ENDIV5, BBPLL_ENDIV5_VAL_320M);
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_BBADC_DSMP, BBPLL_BBADC_DSMP_VAL_320M);
+ } else {
+ /* Raise the voltage */
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, RTC_CNTL_DBIAS_1V25);
+ ets_delay_us(DELAY_PLL_DBIAS_RAISE);
+ /* Configure 480M PLL */
+ switch (xtal_freq) {
+ case RTC_XTAL_FREQ_40M:
+ div_ref = 0;
+ div7_0 = 28;
+ div10_8 = 0;
+ lref = 0;
+ dcur = 6;
+ bw = 3;
+ break;
+ case RTC_XTAL_FREQ_26M:
+ div_ref = 12;
+ div7_0 = 144;
+ div10_8 = 4;
+ lref = 1;
+ dcur = 0;
+ bw = 1;
+ break;
+ case RTC_XTAL_FREQ_24M:
+ div_ref = 11;
+ div7_0 = 144;
+ div10_8 = 4;
+ lref = 1;
+ dcur = 0;
+ bw = 1;
+ break;
+ default:
+ div_ref = 12;
+ div7_0 = 224;
+ div10_8 = 4;
+ lref = 0;
+ dcur = 0;
+ bw = 0;
+ break;
+ }
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_ENDIV5, BBPLL_ENDIV5_VAL_480M);
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_BBADC_DSMP, BBPLL_BBADC_DSMP_VAL_480M);
+ }
+
+ uint8_t i2c_bbpll_lref = (lref << 7) | (div10_8 << 4) | (div_ref);
+ uint8_t i2c_bbpll_div_7_0 = div7_0;
+ uint8_t i2c_bbpll_dcur = (bw << 6) | dcur;
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_OC_LREF, i2c_bbpll_lref);
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_OC_DIV_7_0, i2c_bbpll_div_7_0);
+ I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_OC_DCUR, i2c_bbpll_dcur);
+ ets_delay_us(DELAY_PLL_ENABLE);
+}
+
+void rtc_clk_cpu_freq_set(rtc_cpu_freq_t cpu_freq)
+{
+ rtc_xtal_freq_t xtal_freq = rtc_clk_xtal_freq_get();
+ /* Switch CPU to XTAL frequency first */
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, RTC_CNTL_DBIAS_1V10);
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, RTC_CNTL_SOC_CLK_SEL_XTL);
+ REG_SET_FIELD(APB_CTRL_SYSCLK_CONF_REG, APB_CTRL_PRE_DIV_CNT, 0);
+ ets_update_cpu_frequency(xtal_freq);
+ ets_delay_us(DELAY_CPU_FREQ_SWITCH_TO_XTAL);
+ REG_SET_FIELD(DPORT_CPU_PER_CONF_REG, DPORT_CPUPERIOD_SEL, 0);
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG,
+ RTC_CNTL_BB_I2C_FORCE_PD | RTC_CNTL_BBPLL_FORCE_PD |
+ RTC_CNTL_BBPLL_I2C_FORCE_PD);
+ rtc_clk_apb_freq_update(xtal_freq * MHZ);
+
+ /* is APLL under force power down? */
+ uint32_t apll_fpd = REG_GET_FIELD(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PLLA_FORCE_PD);
+ if (apll_fpd) {
+ /* then also power down the internal I2C bus */
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_I2C_FORCE_PD);
+ }
+ /* now switch to the desired frequency */
+ if (cpu_freq == RTC_CPU_FREQ_XTAL) {
+ /* already at XTAL, nothing to do */
+ } else if (cpu_freq == RTC_CPU_FREQ_2M) {
+ /* set up divider to produce 2MHz from XTAL */
+ REG_SET_FIELD(APB_CTRL_SYSCLK_CONF_REG, APB_CTRL_PRE_DIV_CNT, (xtal_freq / 2) - 1);
+ ets_update_cpu_frequency(2);
+ rtc_clk_apb_freq_update(2 * MHZ);
+ /* lower the voltage */
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, RTC_CNTL_DBIAS_1V00);
+ } else {
+ /* use PLL as clock source */
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG,
+ RTC_CNTL_BIAS_I2C_FORCE_PD | RTC_CNTL_BB_I2C_FORCE_PD |
+ RTC_CNTL_BBPLL_FORCE_PD | RTC_CNTL_BBPLL_I2C_FORCE_PD);
+ rtc_clk_bbpll_set(xtal_freq, cpu_freq);
+ if (cpu_freq == RTC_CPU_FREQ_80M) {
+ REG_SET_FIELD(DPORT_CPU_PER_CONF_REG, DPORT_CPUPERIOD_SEL, 0);
+ ets_update_cpu_frequency(80);
+ } else if (cpu_freq == RTC_CPU_FREQ_160M) {
+ REG_SET_FIELD(DPORT_CPU_PER_CONF_REG, DPORT_CPUPERIOD_SEL, 1);
+ ets_update_cpu_frequency(160);
+ } else if (cpu_freq == RTC_CPU_FREQ_240M) {
+ REG_SET_FIELD(DPORT_CPU_PER_CONF_REG, DPORT_CPUPERIOD_SEL, 2);
+ ets_update_cpu_frequency(240);
+ }
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, RTC_CNTL_SOC_CLK_SEL_PLL);
+ ets_delay_us(DELAY_CPU_FREQ_SWITCH_TO_PLL);
+ rtc_clk_apb_freq_update(80 * MHZ);
+ }
+}
+
+rtc_cpu_freq_t rtc_clk_cpu_freq_get()
+{
+ uint32_t soc_clk_sel = REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL);
+ switch (soc_clk_sel) {
+ case RTC_CNTL_SOC_CLK_SEL_XTL: {
+ uint32_t pre_div = REG_GET_FIELD(APB_CTRL_SYSCLK_CONF_REG, APB_CTRL_PRE_DIV_CNT);
+ if (pre_div == 0) {
+ return RTC_CPU_FREQ_XTAL;
+ } else if (pre_div == rtc_clk_xtal_freq_get() / 2 - 1) {
+ return RTC_CPU_FREQ_2M;
+ } else {
+ assert(false && "unsupported frequency");
+ }
+ break;
+ }
+ case RTC_CNTL_SOC_CLK_SEL_PLL: {
+ uint32_t cpuperiod_sel = REG_GET_FIELD(DPORT_CPU_PER_CONF_REG, DPORT_CPUPERIOD_SEL);
+ if (cpuperiod_sel == 0) {
+ return RTC_CPU_FREQ_80M;
+ } else if (cpuperiod_sel == 1) {
+ return RTC_CPU_FREQ_160M;
+ } else if (cpuperiod_sel == 2) {
+ return RTC_CPU_FREQ_240M;
+ } else {
+ assert(false && "unsupported frequency");
+ }
+ break;
+ }
+ case RTC_CNTL_SOC_CLK_SEL_APLL:
+ case RTC_CNTL_SOC_CLK_SEL_8M:
+ default:
+ assert(false && "unsupported frequency");
+ }
+ return RTC_CNTL_SOC_CLK_SEL_XTL;
+}
+
+uint32_t rtc_clk_cpu_freq_value(rtc_cpu_freq_t cpu_freq)
+{
+ switch (cpu_freq) {
+ case RTC_CPU_FREQ_XTAL:
+ return ((uint32_t) rtc_clk_xtal_freq_get()) * MHZ;
+ case RTC_CPU_FREQ_2M:
+ return 2 * MHZ;
+ case RTC_CPU_FREQ_80M:
+ return 80 * MHZ;
+ case RTC_CPU_FREQ_160M:
+ return 160 * MHZ;
+ case RTC_CPU_FREQ_240M:
+ return 240 * MHZ;
+ default:
+ assert(false && "invalid rtc_cpu_freq_t value");
+ return 0;
+ }
+}
+
+/* Values of RTC_XTAL_FREQ_REG and RTC_APB_FREQ_REG are stored as two copies in
+ * lower and upper 16-bit halves. These are the routines to work with such a
+ * representation.
+ */
+static bool clk_val_is_valid(uint32_t val) {
+ return (val & 0xffff) == ((val >> 16) & 0xffff) &&
+ val != 0 &&
+ val != UINT32_MAX;
+}
+
+static uint32_t reg_val_to_clk_val(uint32_t val) {
+ return val & UINT16_MAX;
+}
+
+static uint32_t clk_val_to_reg_val(uint32_t val) {
+ return (val & UINT16_MAX) | ((val & UINT16_MAX) << 16);
+}
+
+rtc_xtal_freq_t rtc_clk_xtal_freq_get()
+{
+ /* We may have already written XTAL value into RTC_XTAL_FREQ_REG */
+ uint32_t xtal_freq_reg = READ_PERI_REG(RTC_XTAL_FREQ_REG);
+ if (!clk_val_is_valid(xtal_freq_reg)) {
+ SOC_LOGW(TAG, "invalid RTC_XTAL_FREQ_REG value: 0x%08x", xtal_freq_reg);
+ return RTC_XTAL_FREQ_AUTO;
+ }
+ return reg_val_to_clk_val(xtal_freq_reg);
+}
+
+void rtc_clk_xtal_freq_update(rtc_xtal_freq_t xtal_freq)
+{
+ WRITE_PERI_REG(RTC_XTAL_FREQ_REG, clk_val_to_reg_val(xtal_freq));
+}
+
+static rtc_xtal_freq_t rtc_clk_xtal_freq_estimate()
+{
+ /* ROM startup code estimates XTAL frequency using an 8MD256 clock and stores
+ * the value into RTC_APB_FREQ_REG. The value is in Hz, right shifted by 12.
+ * Use this value to guess the real XTAL frequency.
+ *
+ * TODO: make this more robust by calibrating again after setting
+ * RTC_CNTL_CK8M_DFREQ.
+ */
+ uint32_t apb_freq_reg = READ_PERI_REG(RTC_APB_FREQ_REG);
+ if (!clk_val_is_valid(apb_freq_reg)) {
+ SOC_LOGW(TAG, "invalid RTC_APB_FREQ_REG value: 0x%08x", apb_freq_reg);
+ return RTC_XTAL_FREQ_AUTO;
+ }
+ uint32_t freq_mhz = (reg_val_to_clk_val(apb_freq_reg) << 12) / MHZ;
+ /* Guess the XTAL type. For now, only 40 and 26MHz are supported.
+ */
+ switch (freq_mhz) {
+ case 21 ... 31:
+ return RTC_XTAL_FREQ_26M;
+ case 32 ... 33:
+ SOC_LOGW(TAG, "Potentially bogus XTAL frequency: %d MHz, guessing 26 MHz", freq_mhz);
+ return RTC_XTAL_FREQ_26M;
+ case 34 ... 35:
+ SOC_LOGW(TAG, "Potentially bogus XTAL frequency: %d MHz, guessing 40 MHz", freq_mhz);
+ return RTC_XTAL_FREQ_40M;
+ case 36 ... 45:
+ return RTC_XTAL_FREQ_40M;
+ default:
+ SOC_LOGW(TAG, "Bogus XTAL frequency: %d MHz", freq_mhz);
+ return RTC_XTAL_FREQ_AUTO;
+ }
+}
+
+void rtc_clk_apb_freq_update(uint32_t apb_freq)
+{
+ WRITE_PERI_REG(RTC_APB_FREQ_REG, clk_val_to_reg_val(apb_freq >> 12));
+}
+
+uint32_t rtc_clk_apb_freq_get()
+{
+ return reg_val_to_clk_val(READ_PERI_REG(RTC_APB_FREQ_REG)) << 12;
+}
+
+
+void rtc_clk_init(rtc_clk_config_t cfg)
+{
+ /* Set tuning parameters for 8M and 150k clocks.
+ * Note: this doesn't attempt to set the clocks to precise frequencies.
+ * Instead, we calibrate these clocks against XTAL frequency later, when necessary.
+ * - SCK_DCAP value controls tuning of 150k clock.
+ * The higher the value of DCAP is, the lower is the frequency.
+ * - CK8M_DFREQ value controls tuning of 8M clock.
+ * CLK_8M_DFREQ constant gives the best temperature characteristics.
+ */
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_SCK_DCAP, cfg.slow_clk_dcap);
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_CK8M_DFREQ, cfg.clk_8m_dfreq);
+
+ /* Configure 8M clock division */
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_CK8M_DIV_SEL, cfg.clk_8m_div);
+
+ /* Enable the internal bus used to configure PLLs */
+ SET_PERI_REG_BITS(ANA_CONFIG_REG, ANA_CONFIG_M, ANA_CONFIG_M, ANA_CONFIG_S);
+ CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, I2C_APLL_M | I2C_BBPLL_M);
+
+ /* Estimate XTAL frequency if requested */
+ rtc_xtal_freq_t xtal_freq = cfg.xtal_freq;
+ if (xtal_freq == RTC_XTAL_FREQ_AUTO) {
+ xtal_freq = rtc_clk_xtal_freq_estimate();
+ if (xtal_freq == RTC_XTAL_FREQ_AUTO) {
+ SOC_LOGW(TAG, "Can't estimate XTAL frequency, assuming 26MHz");
+ xtal_freq = RTC_XTAL_FREQ_26M;
+ }
+ }
+ rtc_clk_xtal_freq_update(xtal_freq);
+ rtc_clk_apb_freq_update(xtal_freq * MHZ);
+ /* Set CPU frequency */
+ rtc_clk_cpu_freq_set(cfg.cpu_freq);
+
+ /* Slow & fast clocks setup */
+ if (cfg.slow_freq == RTC_SLOW_FREQ_32K_XTAL) {
+ rtc_clk_32k_enable(false);
+ }
+ if (cfg.fast_freq == RTC_FAST_FREQ_8M) {
+ bool need_8md256 = cfg.slow_freq == RTC_SLOW_FREQ_8MD256;
+ rtc_clk_8m_enable(true, need_8md256);
+ }
+ rtc_clk_fast_freq_set(cfg.fast_freq);
+ rtc_clk_slow_freq_set(cfg.slow_freq);
+}
+
+/* Name used in libphy.a:phy_chip_v7.o
+ * TODO: update the library to use rtc_clk_xtal_freq_get
+ */
+rtc_xtal_freq_t rtc_get_xtal() __attribute__((alias("rtc_clk_xtal_freq_get")));
+
+
+/* Referenced in librtc.a:rtc.o.
+ * TODO: remove
+ */
+void rtc_uart_div_modify(int latch)
+{
+
+}
+
+/* Referenced in librtc.a:rtc.o.
+ * TODO: remove
+ */
+void rtc_uart_tx_wait_idle(int uart)
+{
+
+}
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include <stdint.h>
+
+#include "soc/soc.h"
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+#include "soc/dport_reg.h"
+
+
+void rtc_init(rtc_config_t cfg)
+{
+ CLEAR_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PVTMON_PU);
+
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_PLL_BUF_WAIT, cfg.pll_wait);
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_XTL_BUF_WAIT, cfg.xtal_wait);
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_CK8M_WAIT, cfg.ck8m_wait);
+
+ REG_SET_FIELD(RTC_CNTL_BIAS_CONF_REG, RTC_CNTL_DBG_ATTEN, 0x3);
+ SET_PERI_REG_MASK(RTC_CNTL_BIAS_CONF_REG,
+ RTC_CNTL_DEC_HEARTBEAT_WIDTH | RTC_CNTL_INC_HEARTBEAT_PERIOD);
+
+ /* Reset RTC bias to default value (needed if waking up from deep sleep) */
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DBIAS_WAK, RTC_CNTL_DBIAS_1V10);
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DBIAS_SLP, RTC_CNTL_DBIAS_1V10);
+
+ if (cfg.clkctl_init) {
+ //clear CMMU clock force on
+ CLEAR_PERI_REG_MASK(DPORT_PRO_CACHE_CTRL1_REG, DPORT_PRO_CMMU_FORCE_ON);
+ CLEAR_PERI_REG_MASK(DPORT_APP_CACHE_CTRL1_REG, DPORT_APP_CMMU_FORCE_ON);
+ //clear rom clock force on
+ SET_PERI_REG_BITS(DPORT_ROM_FO_CTRL_REG, DPORT_SHARE_ROM_FO, 0, DPORT_SHARE_ROM_FO_S);
+ CLEAR_PERI_REG_MASK(DPORT_ROM_FO_CTRL_REG, DPORT_APP_ROM_FO);
+ CLEAR_PERI_REG_MASK(DPORT_ROM_FO_CTRL_REG, DPORT_PRO_ROM_FO);
+ //clear sram clock force on
+ SET_PERI_REG_BITS(DPORT_SRAM_FO_CTRL_0_REG, DPORT_SRAM_FO_0, 0, DPORT_SRAM_FO_0_S);
+ CLEAR_PERI_REG_MASK(DPORT_SRAM_FO_CTRL_0_REG, DPORT_SRAM_FO_1);
+ //clear tag clock force on
+ CLEAR_PERI_REG_MASK(DPORT_TAG_FO_CTRL_REG, DPORT_APP_CACHE_TAG_FORCE_ON);
+ CLEAR_PERI_REG_MASK(DPORT_TAG_FO_CTRL_REG, DPORT_PRO_CACHE_TAG_FORCE_ON);
+ }
+
+ if (cfg.pwrctl_init) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_CK8M_FORCE_PU);
+ //cancel xtal force pu
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_XTL_FORCE_PU);
+ //cancel BIAS force pu
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_CORE_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_I2C_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_FORCE_NOSLEEP);
+ // bias follow 8M
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_CORE_FOLW_8M);
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_I2C_FOLW_8M);
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_SLEEP_FOLW_8M);
+ // CLEAR APLL close
+ CLEAR_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PLLA_FORCE_PU);
+ SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_PLLA_FORCE_PD);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BBPLL_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BBPLL_I2C_FORCE_PU);
+ //cancel RTC REG force PU
+ CLEAR_PERI_REG_MASK(RTC_CNTL_REG, RTC_CNTL_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_REG, RTC_CNTL_DBOOST_FORCE_PU);
+ if (cfg.rtc_dboost_fpd) {
+ SET_PERI_REG_MASK(RTC_CNTL_REG, RTC_CNTL_DBOOST_FORCE_PD);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_REG, RTC_CNTL_DBOOST_FORCE_PD);
+ }
+ //cancel digital pu force
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_LSLP_MEM_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_DG_WRAP_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_WIFI_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_CPU_ROM_RAM_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PWC_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_WRAP_FORCE_NOISO);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_WIFI_FORCE_NOISO);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_CPU_ROM_RAM_FORCE_NOISO);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FORCE_NOISO);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FORCE_NOISO);
+ //cancel digital PADS force no iso
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_UNHOLD);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_DG_PAD_FORCE_NOISO);
+ }
+}
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include <stdint.h>
+#include <assert.h>
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+
+typedef enum {
+ PM_LIGHT_SLEEP = BIT(2), /*!< WiFi PD, memory in light sleep */
+} pm_sleep_mode_t;
+
+typedef enum{
+ PM_SW_NOREJECT = 0,
+ PM_SW_REJECT = 1
+} pm_sw_reject_t;
+
+
+/* These MAC-related functions are defined in the closed source part of
+ * RTC library
+ */
+extern void pm_mac_init();
+extern int pm_check_mac_idle();
+extern void pm_mac_deinit();
+
+/* This sleep-related function is called from the closed source part of RTC
+ * library.
+ */
+pm_sw_reject_t pm_set_sleep_mode(pm_sleep_mode_t sleep_mode, void(*pmac_save_params)())
+{
+ (void) pmac_save_params; /* unused */
+
+ pm_mac_deinit();
+ if (pm_check_mac_idle()) {
+ pm_mac_init();
+ return PM_SW_REJECT;
+ }
+
+ rtc_sleep_config_t cfg = { 0 };
+ cfg.soc_clk_sel = RTC_CNTL_SOC_CLK_SEL_XTL;
+
+ switch (sleep_mode) {
+ case PM_LIGHT_SLEEP:
+ cfg.wifi_pd_en = 1;
+ cfg.dig_dbias_wak = 4;
+ cfg.dig_dbias_slp = 0;
+ cfg.rtc_dbias_wak = 0;
+ cfg.rtc_dbias_slp = 0;
+ cfg.lslp_meminf_pd = 1;
+ rtc_sleep_init(cfg);
+ break;
+
+ default:
+ assert(0 && "unsupported sleep mode");
+ }
+ return PM_SW_NOREJECT;
+}
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include <stdint.h>
+#include "soc/soc.h"
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+#include "soc/dport_reg.h"
+#include "soc/rtc.h"
+#include "soc/i2s_reg.h"
+#include "soc/timer_group_reg.h"
+#include "soc/bb_reg.h"
+#include "soc/nrx_reg.h"
+#include "soc/fe_reg.h"
+#include "soc/rtc.h"
+#include "rom/ets_sys.h"
+
+#define MHZ (1000000)
+
+/* Various delays to be programmed into power control state machines */
+#define ROM_RAM_POWERUP_DELAY 3
+#define ROM_RAM_WAIT_DELAY 3
+#define WIFI_POWERUP_DELAY 3
+#define WIFI_WAIT_DELAY 3
+#define RTC_POWERUP_DELAY 3
+#define RTC_WAIT_DELAY 3
+#define DG_WRAP_POWERUP_DELAY 3
+#define DG_WRAP_WAIT_DELAY 3
+#define RTC_MEM_POWERUP_DELAY 3
+#define RTC_MEM_WAIT_DELAY 3
+
+/**
+ * @brief Power down flags for rtc_sleep_pd function
+ */
+typedef struct {
+ uint32_t dig_pd : 1; //!< Set to 1 to power down digital part in sleep
+ uint32_t rtc_pd : 1; //!< Set to 1 to power down RTC memories in sleep
+ uint32_t cpu_pd : 1; //!< Set to 1 to power down digital memories and CPU in sleep
+ uint32_t i2s_pd : 1; //!< Set to 1 to power down I2S in sleep
+ uint32_t bb_pd : 1; //!< Set to 1 to power down WiFi in sleep
+ uint32_t nrx_pd : 1; //!< Set to 1 to power down WiFi in sleep
+ uint32_t fe_pd : 1; //!< Set to 1 to power down WiFi in sleep
+} rtc_sleep_pd_config_t;
+
+/**
+ * Initializer for rtc_sleep_pd_config_t which sets all flags to the same value
+ */
+#define RTC_SLEEP_PD_CONFIG_ALL(val) {\
+ .dig_pd = (val), \
+ .rtc_pd = (val), \
+ .cpu_pd = (val), \
+ .i2s_pd = (val), \
+ .bb_pd = (val), \
+ .nrx_pd = (val), \
+ .fe_pd = (val), \
+}
+
+/**
+ * Configure whether certain peripherals are powered down in deep sleep
+ * @param cfg power down flags as rtc_sleep_pd_config_t structure
+ */
+static void rtc_sleep_pd(rtc_sleep_pd_config_t cfg)
+{
+ REG_SET_FIELD(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_LSLP_MEM_FORCE_PU, ~cfg.dig_pd);
+ REG_SET_FIELD(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_FORCE_LPU, ~cfg.rtc_pd);
+ REG_SET_FIELD(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_LPU, ~cfg.rtc_pd);
+ REG_SET_FIELD(DPORT_MEM_PD_MASK_REG, DPORT_LSLP_MEM_PD_MASK, ~cfg.cpu_pd);
+ REG_SET_FIELD(I2S_PD_CONF_REG(0), I2S_PLC_MEM_FORCE_PU, ~cfg.i2s_pd);
+ REG_SET_FIELD(I2S_PD_CONF_REG(0), I2S_FIFO_FORCE_PU, ~cfg.i2s_pd);
+ REG_SET_FIELD(BBPD_CTRL, BB_FFT_FORCE_PU, ~cfg.bb_pd);
+ REG_SET_FIELD(BBPD_CTRL, BB_DC_EST_FORCE_PU, ~cfg.bb_pd);
+ REG_SET_FIELD(NRXPD_CTRL, NRX_RX_ROT_FORCE_PU, ~cfg.nrx_pd);
+ REG_SET_FIELD(NRXPD_CTRL, NRX_VIT_FORCE_PU, ~cfg.nrx_pd);
+ REG_SET_FIELD(NRXPD_CTRL, NRX_DEMAP_FORCE_PU, ~cfg.nrx_pd);
+ REG_SET_FIELD(FE_GEN_CTRL, FE_IQ_EST_FORCE_PU, ~cfg.fe_pd);
+ REG_SET_FIELD(FE2_TX_INTERP_CTRL, FE2_TX_INF_FORCE_PU, ~cfg.fe_pd);
+}
+
+void rtc_sleep_init(rtc_sleep_config_t cfg)
+{
+ rtc_xtal_freq_t xtal_freq = rtc_clk_xtal_freq_get();
+ REG_SET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_SOC_CLK_SEL, cfg.soc_clk_sel);
+
+ //set 5 PWC state machine times to fit in main state machine time
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_PLL_BUF_WAIT, 1);
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_XTL_BUF_WAIT, RTC_CNTL_XTL_BUF_WAIT_DEFAULT);
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_CK8M_WAIT, RTC_CNTL_CK8M_WAIT_DEFAULT);
+ //set rom&ram timer
+ REG_SET_FIELD(RTC_CNTL_TIMER3_REG, RTC_CNTL_ROM_RAM_POWERUP_TIMER, ROM_RAM_POWERUP_DELAY);
+ REG_SET_FIELD(RTC_CNTL_TIMER3_REG, RTC_CNTL_ROM_RAM_WAIT_TIMER, ROM_RAM_WAIT_DELAY);
+ //set wifi timer
+ REG_SET_FIELD(RTC_CNTL_TIMER3_REG, RTC_CNTL_WIFI_POWERUP_TIMER, WIFI_POWERUP_DELAY);
+ REG_SET_FIELD(RTC_CNTL_TIMER3_REG, RTC_CNTL_WIFI_WAIT_TIMER, WIFI_WAIT_DELAY);
+ //set rtc peri timer
+ REG_SET_FIELD(RTC_CNTL_TIMER4_REG, RTC_CNTL_POWERUP_TIMER, RTC_POWERUP_DELAY);
+ REG_SET_FIELD(RTC_CNTL_TIMER4_REG, RTC_CNTL_WAIT_TIMER, RTC_WAIT_DELAY);
+ //set digital wrap timer
+ REG_SET_FIELD(RTC_CNTL_TIMER4_REG, RTC_CNTL_DG_WRAP_POWERUP_TIMER, DG_WRAP_POWERUP_DELAY);
+ REG_SET_FIELD(RTC_CNTL_TIMER4_REG, RTC_CNTL_DG_WRAP_WAIT_TIMER, DG_WRAP_WAIT_DELAY);
+ //set rtc memory timer
+ REG_SET_FIELD(RTC_CNTL_TIMER5_REG, RTC_CNTL_RTCMEM_POWERUP_TIMER, RTC_MEM_POWERUP_DELAY);
+ REG_SET_FIELD(RTC_CNTL_TIMER5_REG, RTC_CNTL_RTCMEM_WAIT_TIMER, RTC_MEM_WAIT_DELAY);
+
+ if (cfg.soc_clk_sel == RTC_CNTL_SOC_CLK_SEL_PLL) {
+ REG_SET_FIELD(RTC_CNTL_TIMER1_REG, RTC_CNTL_PLL_BUF_WAIT, RTC_CNTL_PLL_BUF_WAIT_DEFAULT);
+ } else if (cfg.soc_clk_sel == RTC_CNTL_SOC_CLK_SEL_XTL) {
+ ets_update_cpu_frequency(xtal_freq);
+ rtc_clk_apb_freq_update(xtal_freq * MHZ);
+ } else if (cfg.soc_clk_sel == RTC_CNTL_SOC_CLK_SEL_8M) {
+ ets_update_cpu_frequency(8);
+ rtc_clk_apb_freq_update(8 * MHZ);
+ }
+
+ if (cfg.lslp_mem_inf_fpu) {
+ SET_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_LSLP_MEM_FORCE_PU);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_LSLP_MEM_FORCE_PU);
+ }
+
+ rtc_sleep_pd_config_t pd_cfg = RTC_SLEEP_PD_CONFIG_ALL(cfg.lslp_meminf_pd);
+ rtc_sleep_pd(pd_cfg);
+
+ if (cfg.rtc_mem_inf_fpu) {
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FORCE_PU);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FORCE_PU);
+ }
+
+ if (cfg.rtc_mem_inf_follow_cpu) {
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FOLW_CPU);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_MEM_FOLW_CPU);
+ }
+
+ if (cfg.rtc_fastmem_pd_en) {
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_PD_EN);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_NOISO);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_PD_EN);
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_PU);
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_FORCE_NOISO);
+ }
+
+ if (cfg.rtc_slowmem_pd_en) {
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_PD_EN);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_FORCE_PU);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_FORCE_NOISO);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_PD_EN);
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_FORCE_PU);
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_FORCE_NOISO);
+ }
+
+ if (cfg.rtc_peri_pd_en) {
+ SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PD_EN);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PD_EN);
+ }
+
+ if (cfg.wifi_pd_en) {
+ SET_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_WIFI_PD_EN);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_WIFI_PD_EN);
+ }
+
+ if (cfg.rom_mem_pd_en) {
+ SET_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_CPU_ROM_RAM_PD_EN);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_CPU_ROM_RAM_PD_EN);
+ }
+
+ if (cfg.deep_slp) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG,
+ RTC_CNTL_DG_PAD_FORCE_ISO | RTC_CNTL_DG_PAD_FORCE_NOISO);
+ SET_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_DG_WRAP_PD_EN);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG,
+ RTC_CNTL_DG_WRAP_FORCE_PU | RTC_CNTL_DG_WRAP_FORCE_PD);
+ CLEAR_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_FORCE_NOSLEEP);
+ } else {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_PWC_REG, RTC_CNTL_DG_WRAP_PD_EN);
+ SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_FORCE_NOSLEEP);
+ }
+
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DBIAS_SLP, cfg.rtc_dbias_slp);
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DBIAS_WAK, cfg.rtc_dbias_wak);
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_WAK, cfg.dig_dbias_wak);
+ REG_SET_FIELD(RTC_CNTL_REG, RTC_CNTL_DIG_DBIAS_SLP, cfg.dig_dbias_slp);
+}
+
+void rtc_sleep_set_wakeup_time(uint64_t t)
+{
+ WRITE_PERI_REG(RTC_CNTL_SLP_TIMER0_REG, t & UINT32_MAX);
+ WRITE_PERI_REG(RTC_CNTL_SLP_TIMER1_REG, t >> 32);
+}
+
+uint32_t rtc_sleep_start(uint32_t wakeup_opt, uint32_t reject_opt)
+{
+ REG_SET_FIELD(RTC_CNTL_WAKEUP_STATE_REG, RTC_CNTL_WAKEUP_ENA, wakeup_opt);
+ WRITE_PERI_REG(RTC_CNTL_SLP_REJECT_CONF_REG, reject_opt);
+
+ /* Start entry into sleep mode */
+ SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_SLEEP_EN);
+
+ while (GET_PERI_REG_MASK(RTC_CNTL_INT_RAW_REG,
+ RTC_CNTL_SLP_REJECT_INT_RAW | RTC_CNTL_SLP_WAKEUP_INT_RAW) == 0) {
+ ;
+ }
+ /* In deep sleep mode, we never get here */
+ uint32_t reject = REG_GET_FIELD(RTC_CNTL_INT_RAW_REG, RTC_CNTL_SLP_REJECT_INT_RAW);
+ SET_PERI_REG_MASK(RTC_CNTL_INT_CLR_REG,
+ RTC_CNTL_SLP_REJECT_INT_CLR | RTC_CNTL_SLP_WAKEUP_INT_CLR);
+ return reject;
+}
--- /dev/null
+// Copyright 2015-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include <stdint.h>
+#include "rom/ets_sys.h"
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+#include "soc/timer_group_reg.h"
+
+#define MHZ (1000000)
+
+/* Calibration of RTC_SLOW_CLK is performed using a special feature of TIMG0.
+ * This feature counts the number of XTAL clock cycles within a given number of
+ * RTC_SLOW_CLK cycles.
+ *
+ * Slow clock calibration feature has two modes of operation: one-off and cycling.
+ * In cycling mode (which is enabled by default on SoC reset), counting of XTAL
+ * cycles within RTC_SLOW_CLK cycle is done continuously. Cycling mode is enabled
+ * using TIMG_RTC_CALI_START_CYCLING bit. In one-off mode counting is performed
+ * once, and TIMG_RTC_CALI_RDY bit is set when counting is done. One-off mode is
+ * enabled using TIMG_RTC_CALI_START bit.
+ */
+uint32_t rtc_clk_cal(rtc_cal_sel_t cal_clk, uint32_t slowclk_cycles)
+{
+ rtc_xtal_freq_t xtal_freq = rtc_clk_xtal_freq_get();
+ /* Enable requested clock (150k clock is always on) */
+ if (cal_clk == RTC_CAL_32K_XTAL) {
+ SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_XTAL32K_EN);
+ }
+ if (cal_clk == RTC_CAL_8MD256) {
+ SET_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_CLK8M_D256_EN);
+ }
+ /* Prepare calibration */
+ REG_SET_FIELD(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_CLK_SEL, cal_clk);
+ CLEAR_PERI_REG_MASK(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_START_CYCLING);
+ REG_SET_FIELD(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_MAX, slowclk_cycles);
+ /* Figure out how long to wait for calibration to finish */
+ uint32_t expected_freq;
+ rtc_slow_freq_t slow_freq = REG_GET_FIELD(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_ANA_CLK_RTC_SEL);
+ if (cal_clk == RTC_CAL_32K_XTAL ||
+ (cal_clk == RTC_CAL_RTC_MUX && slow_freq == RTC_SLOW_FREQ_32K_XTAL)) {
+ expected_freq = 32768; /* standard 32k XTAL */
+ } else if (cal_clk == RTC_CAL_8MD256 ||
+ (cal_clk == RTC_CAL_RTC_MUX && slow_freq == RTC_SLOW_FREQ_8MD256)) {
+ expected_freq = 8 * MHZ / 256;
+ } else {
+ expected_freq = 150000; /* 150k internal oscillator */
+ }
+ uint32_t us_time_estimate = slowclk_cycles * MHZ / expected_freq;
+ /* Start calibration */
+ CLEAR_PERI_REG_MASK(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_START);
+ SET_PERI_REG_MASK(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_START);
+ /* Wait the expected time calibration should take.
+ * TODO: if running under RTOS, and us_time_estimate > RTOS tick, use the
+ * RTOS delay function.
+ */
+ ets_delay_us(us_time_estimate);
+ /* Wait for calibration to finish up to another us_time_estimate */
+ int timeout_us = us_time_estimate;
+ while (!GET_PERI_REG_MASK(TIMG_RTCCALICFG_REG(0), TIMG_RTC_CALI_RDY) &&
+ timeout_us-- > 0) {
+ ets_delay_us(1);
+ }
+ if (cal_clk == RTC_CAL_32K_XTAL) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_XTAL32K_EN);
+ }
+ if (cal_clk == RTC_CAL_8MD256) {
+ CLEAR_PERI_REG_MASK(RTC_CNTL_CLK_CONF_REG, RTC_CNTL_DIG_CLK8M_D256_EN);
+ }
+ if (timeout_us == 0) {
+ /* timed out waiting for calibration */
+ return 0;
+ }
+
+ uint64_t xtal_cycles = REG_GET_FIELD(TIMG_RTCCALICFG1_REG(0), TIMG_RTC_CALI_VALUE);
+ uint64_t divider = ((uint64_t)xtal_freq) * slowclk_cycles;
+ uint64_t period_64 = (xtal_cycles << RTC_CLK_CAL_FRACT) / divider;
+ uint32_t period = (uint32_t)(period_64 & UINT32_MAX);
+ return period;
+}
+
+uint64_t rtc_time_us_to_slowclk(uint64_t time_in_us, uint32_t period)
+{
+ /* Overflow will happen in this function if time_in_us >= 2^45, which is about 400 days.
+ * TODO: fix overflow.
+ */
+ return (time_in_us << RTC_CLK_CAL_FRACT) / period;
+}
+
+uint64_t rtc_time_slowclk_to_us(uint64_t rtc_cycles, uint32_t period)
+{
+ return (rtc_cycles * period) >> RTC_CLK_CAL_FRACT;
+}
+
+uint64_t rtc_time_get()
+{
+ SET_PERI_REG_MASK(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_UPDATE);
+ while (GET_PERI_REG_MASK(RTC_CNTL_TIME_UPDATE_REG, RTC_CNTL_TIME_VALID) == 0) {
+ ets_delay_us(1); // might take 1 RTC slowclk period, don't flood RTC bus
+ }
+ SET_PERI_REG_MASK(RTC_CNTL_INT_CLR_REG, RTC_CNTL_TIME_VALID_INT_CLR);
+ uint64_t t = READ_PERI_REG(RTC_CNTL_TIME0_REG);
+ t |= ((uint64_t) READ_PERI_REG(RTC_CNTL_TIME1_REG)) << 32;
+ return t;
+}
--- /dev/null
+// Copyright 2016-2017 Espressif Systems (Shanghai) PTE LTD
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#pragma once
+
+/**
+ * @file soc_log.h
+ * @brief SOC library logging functions
+ *
+ * To make SOC library compatible with environments which don't use ESP-IDF,
+ * this header file provides wrappers for logging functions.
+ */
+
+#ifdef ESP_PLATFORM
+#include "esp_log.h"
+#define SOC_LOGE(tag, fmt, ...) ESP_LOGE(tag, fmt, ##__VA_ARGS__)
+#define SOC_LOGW(tag, fmt, ...) ESP_LOGW(tag, fmt, ##__VA_ARGS__)
+#define SOC_LOGI(tag, fmt, ...) ESP_LOGI(tag, fmt, ##__VA_ARGS__)
+#define SOC_LOGD(tag, fmt, ...) ESP_LOGD(tag, fmt, ##__VA_ARGS__)
+#define SOC_LOGV(tag, fmt, ...) ESP_LOGV(tag, fmt, ##__VA_ARGS__)
+
+#else
+#include "rom/ets_sys.h"
+#define SOC_LOGE(tag, fmt, ...) ets_printf("%s(err): " fmt, tag, ##__VA_ARGS__)
+#define SOC_LOGW(tag, fmt, ...) ets_printf("%s(warn): " fmt, tag, ##__VA_ARGS__)
+#define SOC_LOGI(tag, fmt, ...) ets_printf("%s(info): " fmt, tag, ##__VA_ARGS__)
+#define SOC_LOGD(tag, fmt, ...) ets_printf("%s(dbg): " fmt, tag, ##__VA_ARGS__)
+#define SOC_LOGV(tag, fmt, ...) ets_printf("%s: " fmt, tag, ##__VA_ARGS__)
+#endif //ESP_PLATFORM
--- /dev/null
+#include <stdio.h>
+#include "unity.h"
+#include "rom/ets_sys.h"
+#include "soc/rtc.h"
+#include "soc/rtc_cntl_reg.h"
+#include "soc/rtc_io_reg.h"
+#include "soc/sens_reg.h"
+#include "soc/io_mux_reg.h"
+#include "driver/rtc_io.h"
+
+#include "freertos/FreeRTOS.h"
+#include "freertos/task.h"
+
+
+#define CALIBRATE_ONE(cali_clk) calibrate_one(cali_clk, #cali_clk)
+
+static uint32_t calibrate_one(rtc_cal_sel_t cal_clk, const char* name)
+{
+ const uint32_t cal_count = 1000;
+ const float factor = (1 << 19) * 1000.0f;
+ uint32_t cali_val;
+ printf("%s:\n", name);
+ for (int i = 0; i < 5; ++i) {
+ printf("calibrate (%d): ", i);
+ cali_val = rtc_clk_cal(cal_clk, cal_count);
+ printf("%.3f kHz\n", factor / (float) cali_val);
+ }
+ return cali_val;
+}
+
+TEST_CASE("RTC_SLOW_CLK sources calibration", "[rtc_clk]")
+{
+ rtc_clk_32k_enable(true);
+ rtc_clk_8m_enable(true, true);
+
+ CALIBRATE_ONE(RTC_CAL_RTC_MUX);
+ CALIBRATE_ONE(RTC_CAL_8MD256);
+ uint32_t cal_32k = CALIBRATE_ONE(RTC_CAL_32K_XTAL);
+
+ if (cal_32k == 0) {
+ printf("32K XTAL OSC has not started up");
+ } else {
+ printf("switching to RTC_SLOW_FREQ_32K_XTAL: ");
+ rtc_clk_slow_freq_set(RTC_SLOW_FREQ_32K_XTAL);
+ printf("done\n");
+
+ CALIBRATE_ONE(RTC_CAL_RTC_MUX);
+ CALIBRATE_ONE(RTC_CAL_8MD256);
+ CALIBRATE_ONE(RTC_CAL_32K_XTAL);
+ }
+
+ printf("switching to RTC_SLOW_FREQ_8MD256: ");
+ rtc_clk_slow_freq_set(RTC_SLOW_FREQ_8MD256);
+ printf("done\n");
+
+ CALIBRATE_ONE(RTC_CAL_RTC_MUX);
+ CALIBRATE_ONE(RTC_CAL_8MD256);
+ CALIBRATE_ONE(RTC_CAL_32K_XTAL);
+}
+
+/* The following two are not unit tests, but are added here to make it easy to
+ * check the frequency of 150k/32k oscillators. The following two "tests" will
+ * output either 32k or 150k clock to GPIO25.
+ */
+
+static void pull_out_clk(int sel)
+{
+ REG_SET_BIT(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_MUX_SEL_M);
+ REG_CLR_BIT(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_RDE_M | RTC_IO_PDAC1_RUE_M);
+ REG_SET_FIELD(RTC_IO_PAD_DAC1_REG, RTC_IO_PDAC1_FUN_SEL, 1);
+ REG_SET_FIELD(SENS_SAR_DAC_CTRL1_REG, SENS_DEBUG_BIT_SEL, 0);
+ REG_SET_FIELD(RTC_IO_RTC_DEBUG_SEL_REG, RTC_IO_DEBUG_SEL0, sel);
+}
+
+TEST_CASE("Output 150k clock to GPIO25", "[rtc_clk][ignore]")
+{
+ pull_out_clk(RTC_IO_DEBUG_SEL0_150K_OSC);
+}
+
+TEST_CASE("Output 32k XTAL clock to GPIO25", "[rtc_clk][ignore]")
+{
+ rtc_clk_32k_enable(true);
+ pull_out_clk(RTC_IO_DEBUG_SEL0_32K_XTAL);
+}
--- /dev/null
+# currently the only SoC supported; to be moved into Kconfig
+SOC_NAME := esp32
+
+COMPONENT_SRCDIRS := ../$(SOC_NAME)/test
+
+COMPONENT_ADD_LDFLAGS = -Wl,--whole-archive -l$(COMPONENT_NAME) -Wl,--no-whole-archive
+
+