mirror of
https://github.com/esphome/esphome.git
synced 2025-10-24 04:33:49 +01:00
add nrf sdk build
This commit is contained in:
@@ -1,7 +1,13 @@
|
||||
import esphome.codegen as cg
|
||||
import esphome.config_validation as cv
|
||||
from esphome import pins
|
||||
from esphome.const import CONF_ANALOG, CONF_INPUT, CONF_NUMBER
|
||||
from esphome.const import (
|
||||
CONF_ANALOG,
|
||||
CONF_INPUT,
|
||||
CONF_NUMBER,
|
||||
KEY_CORE,
|
||||
KEY_TARGET_FRAMEWORK,
|
||||
)
|
||||
|
||||
from esphome.core import CORE
|
||||
from esphome.components.esp32 import get_esp32_variant
|
||||
@@ -194,6 +200,12 @@ def validate_adc_pin(value):
|
||||
)(value)
|
||||
|
||||
if CORE.is_nrf52:
|
||||
if CORE.data[KEY_CORE][KEY_TARGET_FRAMEWORK] == "zephyr":
|
||||
# TODO
|
||||
raise cv.Invalid(
|
||||
f"ADC is not imlemented on {CORE.data[KEY_CORE][KEY_TARGET_FRAMEWORK]}"
|
||||
)
|
||||
|
||||
conf = pins.gpio_pin_schema(
|
||||
{CONF_ANALOG: True, CONF_INPUT: True}, internal=True
|
||||
)(value)
|
||||
|
@@ -294,7 +294,7 @@ float ADCSensor::sample() {
|
||||
}
|
||||
#endif // USE_LIBRETINY
|
||||
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
float ADCSensor::sample() {
|
||||
// https://infocenter.nordicsemi.com/pdf/nRF52840_PS_v1.1.pdf
|
||||
// 6.23.2 Reference voltage and gain settings
|
||||
|
@@ -14,6 +14,8 @@ CONFIG_SCHEMA = cv.All(
|
||||
}
|
||||
).extend(cv.COMPONENT_SCHEMA),
|
||||
cv.only_on_nrf52,
|
||||
# TODO implement
|
||||
cv.only_with_arduino,
|
||||
)
|
||||
|
||||
|
||||
|
@@ -35,10 +35,10 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
#include "nrf52/nrf_mbr.h"
|
||||
#include <Adafruit_TinyUSB.h>
|
||||
#include "esphome/core/application.h"
|
||||
#include "nrf52/nrf_mbr.h"
|
||||
#endif
|
||||
|
||||
namespace esphome {
|
||||
@@ -61,7 +61,7 @@ static uint32_t get_free_heap() {
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
static std::string nrf52_get_reset_reason_name(){
|
||||
uint32_t rr = readResetReason();
|
||||
if (rr & POWER_RESETREAS_VBUS_Msk){
|
||||
@@ -416,7 +416,8 @@ void DebugComponent::dump_config() {
|
||||
reset_reason = lt_get_reboot_reason_name(lt_get_reboot_reason());
|
||||
#endif // USE_LIBRETINY
|
||||
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
//TODO fixme
|
||||
ESP_LOGD(TAG, "bootloader version %lu.%lu.%lu", (bootloaderVersion >> 16) & 0xFF, (bootloaderVersion >> 8) & 0xFF, bootloaderVersion & 0xFF);
|
||||
ESP_LOGD(TAG, "MBR bootloader addr 0x%08lx, UICR bootloader addr 0x%08lx", (*((uint32_t *)MBR_BOOTLOADER_ADDR)), NRF_UICR->NRFFW[0]);
|
||||
ESP_LOGD(TAG, "MBR param page addr 0x%08lx, UICR param page addr 0x%08lx", (*((uint32_t *) MBR_PARAM_PAGE_ADDR)), NRF_UICR->NRFFW[1]);
|
||||
@@ -437,6 +438,7 @@ void DebugComponent::dump_config() {
|
||||
}
|
||||
|
||||
void DebugComponent::loop() {
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
//TODO move to logger
|
||||
//TOOD do not print when exit from deep sleep
|
||||
static bool d = false;
|
||||
@@ -446,6 +448,7 @@ void DebugComponent::loop() {
|
||||
}
|
||||
d = !d;
|
||||
}
|
||||
#endif
|
||||
// log when free heap space has halved
|
||||
uint32_t new_free_heap = get_free_heap();
|
||||
if (new_free_heap < this->free_heap_ / 2) {
|
||||
|
@@ -1,4 +1,4 @@
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
#include "deep_sleep_backend_nrf52.h"
|
||||
#include "nrf_power.h"
|
||||
#include <cassert>
|
||||
|
@@ -1,5 +1,5 @@
|
||||
#pragma once
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
|
||||
#include "esphome/core/optional.h"
|
||||
#include "Arduino.h"
|
||||
|
@@ -76,7 +76,7 @@ void DeepSleepComponent::dump_config() {
|
||||
ESP_LOGCONFIG(TAG, " GPIO Wakeup Run Duration: %" PRIu32 " ms", this->wakeup_cause_to_run_duration_->gpio_cause);
|
||||
}
|
||||
#endif
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
backend_.dump_config();
|
||||
#endif
|
||||
}
|
||||
@@ -172,7 +172,7 @@ void DeepSleepComponent::begin_sleep(bool manual) {
|
||||
#ifdef USE_ESP8266
|
||||
ESP.deepSleep(*this->sleep_duration_); // NOLINT(readability-static-accessed-through-instance)
|
||||
#endif
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
backend_.begin_sleep(this->sleep_duration_);
|
||||
setup_deep_sleep_();
|
||||
#endif
|
||||
|
@@ -123,7 +123,7 @@ class DeepSleepComponent : public Component {
|
||||
optional<uint32_t> run_duration_;
|
||||
bool next_enter_deep_sleep_{false};
|
||||
bool prevent_{false};
|
||||
#ifdef USE_NRF52
|
||||
#if defined(USE_NRF52) && defined(USE_ARDUINO)
|
||||
Nrf52DeepSleepBackend backend_;
|
||||
#endif
|
||||
};
|
||||
|
@@ -1,5 +1,5 @@
|
||||
#include "dfu.h"
|
||||
#ifdef USE_NRF52
|
||||
#ifdef USE_ZEPHYR
|
||||
#include <zephyr/device.h>
|
||||
#include <zephyr/drivers/uart.h>
|
||||
#include <zephyr/drivers/uart/cdc_acm.h>
|
||||
@@ -18,7 +18,7 @@ volatile bool goto_dfu = false;
|
||||
#define DFU_DBL_RESET_MAGIC 0x5A1AD5 // SALADS
|
||||
uint32_t *dbl_reset_mem = ((uint32_t *) DFU_DBL_RESET_MEM);
|
||||
|
||||
#ifdef USE_NRF52
|
||||
#ifdef USE_ZEPHYR
|
||||
#define DEVICE_AND_COMMA(node_id) DEVICE_DT_GET(node_id),
|
||||
|
||||
const struct device *cdc_dev[] = {DT_FOREACH_STATUS_OKAY(zephyr_cdc_acm_uart, DEVICE_AND_COMMA)};
|
||||
@@ -31,7 +31,7 @@ static void cdc_dte_rate_callback(const struct device *, uint32_t rate){
|
||||
#endif
|
||||
|
||||
void DeviceFirmwareUpdate::setup() {
|
||||
#ifdef USE_NRF52
|
||||
#ifdef USE_ZEPHYR
|
||||
for (int idx = 0; idx < ARRAY_SIZE(cdc_dev); idx++) {
|
||||
cdc_acm_dte_rate_callback_set(cdc_dev[idx], cdc_dte_rate_callback);
|
||||
}
|
||||
|
@@ -9,21 +9,18 @@ from esphome.const import (
|
||||
PLATFORM_NRF52,
|
||||
CONF_TYPE,
|
||||
CONF_FRAMEWORK,
|
||||
CONF_VARIANT,
|
||||
)
|
||||
from esphome.core import CORE, coroutine_with_priority
|
||||
from esphome.helpers import (
|
||||
write_file_if_changed,
|
||||
copy_file_if_changed,
|
||||
)
|
||||
from typing import Union
|
||||
|
||||
# force import gpio to register pin schema
|
||||
from .gpio import nrf52_pin_to_code # noqa
|
||||
|
||||
# def AUTO_LOAD():
|
||||
# # if CORE.using_arduino:
|
||||
# return ["nrf52_nrfx"]
|
||||
# # return []
|
||||
|
||||
KEY_NRF52 = "nrf52"
|
||||
|
||||
|
||||
@@ -68,18 +65,29 @@ PLATFORM_FRAMEWORK_SCHEMA = cv.All(
|
||||
_platform_check_versions,
|
||||
)
|
||||
|
||||
FRAMEWORK_ZEPHYR = "zephyr"
|
||||
FRAMEWORK_ARDUINO = "arduino"
|
||||
FRAMEWORK_SCHEMA = cv.typed_schema(
|
||||
{
|
||||
FRAMEWORK_ZEPHYR: PLATFORM_FRAMEWORK_SCHEMA,
|
||||
FRAMEWORK_ARDUINO: PLATFORM_FRAMEWORK_SCHEMA,
|
||||
},
|
||||
lower=True,
|
||||
space="-",
|
||||
default_type=FRAMEWORK_ARDUINO,
|
||||
ZEPHYR_VARIANT_GENERIC = "generic"
|
||||
ZEPHYR_VARIANT_NRF_SDK = "nrf-sdk"
|
||||
ZEPHYR_VARIANTS = [
|
||||
ZEPHYR_VARIANT_GENERIC,
|
||||
ZEPHYR_VARIANT_NRF_SDK,
|
||||
]
|
||||
|
||||
FRAMEWORK_VARIANTS = [
|
||||
"zephyr",
|
||||
"arduino",
|
||||
]
|
||||
|
||||
FRAMEWORK_SCHEMA = cv.All(
|
||||
cv.Schema(
|
||||
{
|
||||
cv.Required(CONF_TYPE): cv.one_of(*FRAMEWORK_VARIANTS, lower=True),
|
||||
cv.Optional(CONF_VARIANT): cv.one_of(*ZEPHYR_VARIANTS, lower=True),
|
||||
}
|
||||
),
|
||||
_platform_check_versions,
|
||||
)
|
||||
|
||||
|
||||
CONFIG_SCHEMA = cv.All(
|
||||
cv.Schema(
|
||||
{
|
||||
@@ -119,20 +127,24 @@ async def to_code(config):
|
||||
config[CONF_BOARD] = "adafruit_itsybitsy_nrf52840"
|
||||
elif CORE.using_arduino:
|
||||
# it has most generic GPIO mapping
|
||||
# TODO does it matter if custom board is defined?
|
||||
config[CONF_BOARD] = "nrf52840_dk_adafruit"
|
||||
cg.add_platformio_option("board", config[CONF_BOARD])
|
||||
cg.add_build_flag("-DUSE_NRF52")
|
||||
cg.add_define("ESPHOME_BOARD", config[CONF_BOARD])
|
||||
cg.add_define("ESPHOME_VARIANT", "nrf52840")
|
||||
cg.add_define("ESPHOME_VARIANT", "NRF52")
|
||||
conf = config[CONF_FRAMEWORK]
|
||||
cg.add_platformio_option(CONF_FRAMEWORK, conf[CONF_TYPE])
|
||||
cg.add_platformio_option("platform", conf[CONF_PLATFORM_VERSION])
|
||||
|
||||
# make sure that firmware.zip is created
|
||||
# for Adafruit_nRF52_Bootloader
|
||||
# TODO add bootloader type to config
|
||||
cg.add_platformio_option("board_upload.protocol", "nrfutil")
|
||||
cg.add_platformio_option("board_upload.use_1200bps_touch", "true")
|
||||
cg.add_platformio_option("board_upload.require_upload_port", "true")
|
||||
cg.add_platformio_option("board_upload.wait_for_upload_port", "true")
|
||||
cg.add_platformio_option("extra_scripts", [f"pre:build_{conf[CONF_TYPE]}.py"])
|
||||
if CORE.using_arduino:
|
||||
cg.add_build_flag("-DUSE_ARDUINO")
|
||||
# watchdog
|
||||
@@ -144,12 +156,28 @@ async def to_code(config):
|
||||
cg.add_platformio_option(
|
||||
"board_build.variants_dir", os.path.dirname(os.path.realpath(__file__))
|
||||
)
|
||||
cg.add_library("https://github.com/NordicSemiconductor/nrfx#v2.1.0", None, None)
|
||||
elif CORE.using_zephyr:
|
||||
cg.add_build_flag("-DUSE_ZEPHYR")
|
||||
cg.add_platformio_option(
|
||||
"platform_packages", ["framework-zephyr@~2.30400.230914"]
|
||||
)
|
||||
# cpp support
|
||||
if conf[CONF_VARIANT] == ZEPHYR_VARIANT_GENERIC:
|
||||
cg.add_platformio_option(
|
||||
"platform_packages",
|
||||
[
|
||||
"platformio/framework-zephyr@^2.30500.231204",
|
||||
# "platformio/toolchain-gccarmnoneeabi@^1.120301.0"
|
||||
],
|
||||
)
|
||||
elif conf[CONF_VARIANT] == ZEPHYR_VARIANT_NRF_SDK:
|
||||
cg.add_platformio_option(
|
||||
"platform_packages",
|
||||
[
|
||||
"platformio/framework-zephyr@https://github.com/tomaszduda23/framework-sdk-nrf",
|
||||
"platformio/toolchain-gccarmnoneeabi@https://github.com/tomaszduda23/toolchain-sdk-ng",
|
||||
],
|
||||
)
|
||||
else:
|
||||
raise NotImplementedError
|
||||
# c++ support
|
||||
add_zephyr_prj_conf_option("CONFIG_NEWLIB_LIBC", False)
|
||||
add_zephyr_prj_conf_option("CONFIG_NEWLIB_LIBC_NANO", True)
|
||||
add_zephyr_prj_conf_option("CONFIG_NEWLIB_LIBC_FLOAT_PRINTF", True)
|
||||
@@ -158,8 +186,14 @@ async def to_code(config):
|
||||
# watchdog
|
||||
add_zephyr_prj_conf_option("CONFIG_WATCHDOG", True)
|
||||
add_zephyr_prj_conf_option("CONFIG_WDT_DISABLE_AT_BOOT", False)
|
||||
# TODO debug only
|
||||
add_zephyr_prj_conf_option("CONFIG_DEBUG_THREAD_INFO", True)
|
||||
|
||||
else:
|
||||
raise NotImplementedError
|
||||
# add_zephyr_prj_conf_option("CONFIG_USE_SEGGER_RTT", True)
|
||||
# add_zephyr_prj_conf_option("CONFIG_RTT_CONSOLE", True)
|
||||
# add_zephyr_prj_conf_option("CONFIG_UART_CONSOLE", False)
|
||||
|
||||
|
||||
def _format_prj_conf_val(value: PrjConfValueType) -> str:
|
||||
@@ -172,6 +206,10 @@ def _format_prj_conf_val(value: PrjConfValueType) -> str:
|
||||
raise ValueError
|
||||
|
||||
|
||||
overlay = """
|
||||
"""
|
||||
|
||||
|
||||
# Called by writer.py
|
||||
def copy_files():
|
||||
if CORE.using_zephyr:
|
||||
@@ -183,4 +221,17 @@ def copy_files():
|
||||
)
|
||||
+ "\n"
|
||||
)
|
||||
|
||||
write_file_if_changed(CORE.relative_build_path("zephyr/prj.conf"), contents)
|
||||
write_file_if_changed(CORE.relative_build_path("zephyr/app.overlay"), overlay)
|
||||
|
||||
dir = os.path.dirname(__file__)
|
||||
build_zephyr_file = os.path.join(
|
||||
dir, f"build_{CORE.data[KEY_CORE][KEY_TARGET_FRAMEWORK]}.py.script"
|
||||
)
|
||||
copy_file_if_changed(
|
||||
build_zephyr_file,
|
||||
CORE.relative_build_path(
|
||||
f"build_{CORE.data[KEY_CORE][KEY_TARGET_FRAMEWORK]}.py"
|
||||
),
|
||||
)
|
||||
|
14
esphome/components/nrf52/build_arduino.py.script
Normal file
14
esphome/components/nrf52/build_arduino.py.script
Normal file
@@ -0,0 +1,14 @@
|
||||
import os
|
||||
|
||||
Import("env")
|
||||
|
||||
def skip_nrfx_from_build(env, node):
|
||||
if os.path.join("FrameworkArduino", "nordic", "nrfx") in node.path:
|
||||
return node
|
||||
if os.path.join("nrfx") in node.path:
|
||||
if os.path.join("drivers", "src", "nrfx_wdt.c") in node.path:
|
||||
return node
|
||||
return None
|
||||
return node
|
||||
|
||||
env.AddBuildMiddleware(skip_nrfx_from_build)
|
4
esphome/components/nrf52/build_zephyr.py.script
Normal file
4
esphome/components/nrf52/build_zephyr.py.script
Normal file
@@ -0,0 +1,4 @@
|
||||
Import("env")
|
||||
|
||||
board_config = env.BoardConfig()
|
||||
board_config.update("frameworks", ["arduino", "zephyr"])
|
@@ -111,6 +111,11 @@ void NRF52GPIOPin::detach_interrupt() const {
|
||||
|
||||
} // namespace nrf52
|
||||
|
||||
bool IRAM_ATTR ISRInternalGPIOPin::digital_read() {
|
||||
// TODO
|
||||
return false;
|
||||
}
|
||||
|
||||
} // namespace esphome
|
||||
|
||||
#endif
|
||||
|
@@ -1,181 +0,0 @@
|
||||
/*
|
||||
* Copyright (c) 2015 - 2020, Nordic Semiconductor ASA
|
||||
* All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice, this
|
||||
* list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in the
|
||||
* documentation and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
#include <nrfx.h>
|
||||
|
||||
#if NRFX_CHECK(NRFX_WDT_ENABLED)
|
||||
|
||||
#if !(NRFX_CHECK(NRFX_WDT0_ENABLED) || NRFX_CHECK(NRFX_WDT1_ENABLED))
|
||||
#error "No enabled WDT instances. Check <nrfx_config.h>."
|
||||
#endif
|
||||
|
||||
#include <nrfx_wdt.h>
|
||||
|
||||
#define NRFX_LOG_MODULE WDT
|
||||
#include <nrfx_log.h>
|
||||
|
||||
// Control block - driver instance local data.
|
||||
typedef struct
|
||||
{
|
||||
nrfx_drv_state_t state;
|
||||
uint8_t alloc_index;
|
||||
#if !NRFX_CHECK(NRFX_WDT_CONFIG_NO_IRQ)
|
||||
nrfx_wdt_event_handler_t wdt_event_handler;
|
||||
#endif
|
||||
} wdt_control_block_t;
|
||||
|
||||
static wdt_control_block_t m_cb[NRFX_WDT_ENABLED_COUNT];
|
||||
|
||||
nrfx_err_t nrfx_wdt_init(nrfx_wdt_t const * p_instance,
|
||||
nrfx_wdt_config_t const * p_config,
|
||||
nrfx_wdt_event_handler_t wdt_event_handler)
|
||||
{
|
||||
NRFX_ASSERT(p_config);
|
||||
nrfx_err_t err_code;
|
||||
|
||||
wdt_control_block_t * p_cb = &m_cb[p_instance->drv_inst_idx];
|
||||
|
||||
#if NRFX_CHECK(NRFX_WDT_CONFIG_NO_IRQ)
|
||||
(void)wdt_event_handler;
|
||||
#else
|
||||
p_cb->wdt_event_handler = wdt_event_handler;
|
||||
#endif
|
||||
|
||||
if (p_cb->state == NRFX_DRV_STATE_UNINITIALIZED)
|
||||
{
|
||||
p_cb->state = NRFX_DRV_STATE_INITIALIZED;
|
||||
}
|
||||
else
|
||||
{
|
||||
err_code = NRFX_ERROR_INVALID_STATE;
|
||||
NRFX_LOG_WARNING("Function: %s, error code: %s.",
|
||||
__func__,
|
||||
NRFX_LOG_ERROR_STRING_GET(err_code));
|
||||
return err_code;
|
||||
}
|
||||
|
||||
nrf_wdt_behaviour_set(p_instance->p_reg, p_config->behaviour);
|
||||
|
||||
uint64_t ticks = (p_config->reload_value * 32768ULL) / 1000;
|
||||
NRFX_ASSERT(ticks <= UINT32_MAX);
|
||||
|
||||
nrf_wdt_reload_value_set(p_instance->p_reg, (uint32_t) ticks);
|
||||
|
||||
#if !NRFX_CHECK(NRFX_WDT_CONFIG_NO_IRQ)
|
||||
if (wdt_event_handler)
|
||||
{
|
||||
nrf_wdt_int_enable(p_instance->p_reg, NRF_WDT_INT_TIMEOUT_MASK);
|
||||
NRFX_IRQ_PRIORITY_SET(nrfx_get_irq_number(p_instance->p_reg), p_config->interrupt_priority);
|
||||
NRFX_IRQ_ENABLE(nrfx_get_irq_number(p_instance->p_reg));
|
||||
}
|
||||
#endif
|
||||
|
||||
err_code = NRFX_SUCCESS;
|
||||
NRFX_LOG_INFO("Function: %s, error code: %s.", __func__, NRFX_LOG_ERROR_STRING_GET(err_code));
|
||||
return err_code;
|
||||
}
|
||||
|
||||
|
||||
void nrfx_wdt_enable(nrfx_wdt_t const * p_instance)
|
||||
{
|
||||
wdt_control_block_t * p_cb = &m_cb[p_instance->drv_inst_idx];
|
||||
NRFX_ASSERT(p_cb->alloc_index != 0);
|
||||
NRFX_ASSERT(p_cb->state == NRFX_DRV_STATE_INITIALIZED);
|
||||
nrf_wdt_task_trigger(p_instance->p_reg, NRF_WDT_TASK_START);
|
||||
p_cb->state = NRFX_DRV_STATE_POWERED_ON;
|
||||
NRFX_LOG_INFO("Enabled.");
|
||||
}
|
||||
|
||||
|
||||
void nrfx_wdt_feed(nrfx_wdt_t const * p_instance)
|
||||
{
|
||||
wdt_control_block_t const * p_cb = &m_cb[p_instance->drv_inst_idx];
|
||||
NRFX_ASSERT(p_cb->state == NRFX_DRV_STATE_POWERED_ON);
|
||||
for (uint8_t i = 0; i < p_cb->alloc_index; i++)
|
||||
{
|
||||
nrf_wdt_reload_request_set(p_instance->p_reg, (nrf_wdt_rr_register_t)(NRF_WDT_RR0 + i));
|
||||
}
|
||||
}
|
||||
|
||||
nrfx_err_t nrfx_wdt_channel_alloc(nrfx_wdt_t const * p_instance, nrfx_wdt_channel_id * p_channel_id)
|
||||
{
|
||||
nrfx_err_t result;
|
||||
wdt_control_block_t * p_cb = &m_cb[p_instance->drv_inst_idx];
|
||||
|
||||
NRFX_ASSERT(p_channel_id);
|
||||
NRFX_ASSERT(p_cb->state == NRFX_DRV_STATE_INITIALIZED);
|
||||
|
||||
NRFX_CRITICAL_SECTION_ENTER();
|
||||
if (p_cb->alloc_index < NRF_WDT_CHANNEL_NUMBER)
|
||||
{
|
||||
*p_channel_id = (nrfx_wdt_channel_id)(NRF_WDT_RR0 + p_cb->alloc_index);
|
||||
p_cb->alloc_index++;
|
||||
nrf_wdt_reload_request_enable(p_instance->p_reg, *p_channel_id);
|
||||
result = NRFX_SUCCESS;
|
||||
}
|
||||
else
|
||||
{
|
||||
result = NRFX_ERROR_NO_MEM;
|
||||
}
|
||||
NRFX_CRITICAL_SECTION_EXIT();
|
||||
NRFX_LOG_INFO("Function: %s, error code: %s.", __func__, NRFX_LOG_ERROR_STRING_GET(result));
|
||||
return result;
|
||||
}
|
||||
|
||||
void nrfx_wdt_channel_feed(nrfx_wdt_t const * p_instance, nrfx_wdt_channel_id channel_id)
|
||||
{
|
||||
NRFX_ASSERT(m_cb[p_instance->drv_inst_idx].state == NRFX_DRV_STATE_POWERED_ON);
|
||||
nrf_wdt_reload_request_set(p_instance->p_reg, channel_id);
|
||||
}
|
||||
|
||||
#if NRFX_CHECK(NRFX_WDT0_ENABLED) && !NRFX_CHECK(NRFX_WDT_CONFIG_NO_IRQ)
|
||||
void nrfx_wdt_0_irq_handler(void)
|
||||
{
|
||||
if (nrf_wdt_event_check(NRF_WDT0, NRF_WDT_EVENT_TIMEOUT))
|
||||
{
|
||||
m_cb[NRFX_WDT0_INST_IDX].wdt_event_handler();
|
||||
nrf_wdt_event_clear(NRF_WDT0, NRF_WDT_EVENT_TIMEOUT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if NRFX_CHECK(NRFX_WDT1_ENABLED) && !NRFX_CHECK(NRFX_WDT_CONFIG_NO_IRQ)
|
||||
void nrfx_wdt_1_irq_handler(void)
|
||||
{
|
||||
if (nrf_wdt_event_check(NRF_WDT1, NRF_WDT_EVENT_TIMEOUT))
|
||||
{
|
||||
m_cb[NRFX_WDT1_INST_IDX].wdt_event_handler();
|
||||
nrf_wdt_event_clear(NRF_WDT1, NRF_WDT_EVENT_TIMEOUT);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // NRFX_CHECK(NRFX_WDT_ENABLED)
|
@@ -1,10 +1,17 @@
|
||||
---
|
||||
nrf52:
|
||||
board: nrf52840
|
||||
framework:
|
||||
type: arduino
|
||||
|
||||
esphome:
|
||||
name: nrf52-test
|
||||
|
||||
logger:
|
||||
level: DEBUG
|
||||
logs:
|
||||
switch: NONE
|
||||
|
||||
switch:
|
||||
- platform: gpio
|
||||
pin:
|
||||
@@ -14,10 +21,9 @@ switch:
|
||||
output: true
|
||||
id: gpio_15
|
||||
|
||||
logger:
|
||||
|
||||
interval:
|
||||
- interval: 1sec
|
||||
- interval: 100ms
|
||||
then:
|
||||
- switch.toggle: gpio_15
|
||||
|
||||
@@ -38,8 +44,34 @@ sensor:
|
||||
pin: P0.29
|
||||
id: adc4
|
||||
update_interval: 1s
|
||||
- platform: uptime
|
||||
name: Uptime Sensor
|
||||
update_interval: 5s
|
||||
|
||||
dfu:
|
||||
reset_output: rest_gpio
|
||||
|
||||
output:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 14
|
||||
inverted: true
|
||||
mode:
|
||||
output: true
|
||||
id: rest_gpio
|
||||
|
||||
beacon:
|
||||
|
||||
debug:
|
||||
update_interval: 1s
|
||||
|
||||
text_sensor:
|
||||
- platform: debug
|
||||
device:
|
||||
name: "Device Info"
|
||||
reset_reason:
|
||||
name: "Reset Reason"
|
||||
|
||||
deep_sleep:
|
||||
run_duration: 10s
|
||||
sleep_duration: 10s
|
69
tests/test12.1.yaml
Normal file
69
tests/test12.1.yaml
Normal file
@@ -0,0 +1,69 @@
|
||||
---
|
||||
nrf52:
|
||||
board: nrf52840
|
||||
framework:
|
||||
type: zephyr
|
||||
variant: generic
|
||||
|
||||
esphome:
|
||||
name: nrf52-test-zephyr
|
||||
|
||||
logger:
|
||||
|
||||
switch:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 15
|
||||
inverted: true
|
||||
mode:
|
||||
output: true
|
||||
id: gpio_15
|
||||
|
||||
|
||||
interval:
|
||||
- interval: 100ms
|
||||
then:
|
||||
- switch.toggle: gpio_15
|
||||
|
||||
binary_sensor:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 9
|
||||
mode: INPUT_PULLUP
|
||||
|
||||
id: gpio_9
|
||||
|
||||
sensor:
|
||||
- platform: pulse_width
|
||||
pin: P0.10
|
||||
id: gpio_10
|
||||
update_interval: 3s
|
||||
- platform: uptime
|
||||
name: Uptime Sensor
|
||||
update_interval: 5s
|
||||
|
||||
dfu:
|
||||
reset_output: rest_gpio
|
||||
|
||||
output:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 14
|
||||
inverted: true
|
||||
mode:
|
||||
output: true
|
||||
id: rest_gpio
|
||||
|
||||
debug:
|
||||
update_interval: 1s
|
||||
|
||||
text_sensor:
|
||||
- platform: debug
|
||||
device:
|
||||
name: "Device Info"
|
||||
reset_reason:
|
||||
name: "Reset Reason"
|
||||
|
||||
deep_sleep:
|
||||
run_duration: 10s
|
||||
sleep_duration: 10s
|
49
tests/test12.2.yaml
Normal file
49
tests/test12.2.yaml
Normal file
@@ -0,0 +1,49 @@
|
||||
---
|
||||
nrf52:
|
||||
board: nrf52840
|
||||
framework:
|
||||
type: zephyr
|
||||
variant: nrf-sdk
|
||||
|
||||
esphome:
|
||||
name: nrf52-test-zephyr
|
||||
|
||||
logger:
|
||||
|
||||
switch:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 15
|
||||
inverted: true
|
||||
mode:
|
||||
output: true
|
||||
id: gpio_15
|
||||
|
||||
interval:
|
||||
- interval: 500ms
|
||||
then:
|
||||
- switch.toggle: gpio_15
|
||||
|
||||
# sensor:
|
||||
# - platform: uptime
|
||||
# name: Uptime Sensor
|
||||
# update_interval: 5s
|
||||
|
||||
# shell:
|
||||
|
||||
# ipsp:
|
||||
|
||||
# otbr:
|
||||
|
||||
output:
|
||||
- platform: gpio
|
||||
pin:
|
||||
number: 14
|
||||
inverted: true
|
||||
mode:
|
||||
output: true
|
||||
id: rest_gpio
|
||||
|
||||
|
||||
dfu:
|
||||
reset_output: rest_gpio
|
Reference in New Issue
Block a user